Simbody  3.6
Transform.h
Go to the documentation of this file.
1 #ifndef SimTK_SimTKCOMMON_TRANSFORM_H
2 #define SimTK_SimTKCOMMON_TRANSFORM_H
3 
4 /* -------------------------------------------------------------------------- *
5  * Simbody(tm): SimTKcommon *
6  * -------------------------------------------------------------------------- *
7  * This is part of the SimTK biosimulation toolkit originating from *
8  * Simbios, the NIH National Center for Physics-Based Simulation of *
9  * Biological Structures at Stanford, funded under the NIH Roadmap for *
10  * Medical Research, grant U54 GM072970. See https://simtk.org/home/simbody. *
11  * *
12  * Portions copyright (c) 2005-14 Stanford University and the Authors. *
13  * Authors: Michael Sherman *
14  * Contributors: Paul Mitiguy *
15  * *
16  * Licensed under the Apache License, Version 2.0 (the "License"); you may *
17  * not use this file except in compliance with the License. You may obtain a *
18  * copy of the License at http://www.apache.org/licenses/LICENSE-2.0. *
19  * *
20  * Unless required by applicable law or agreed to in writing, software *
21  * distributed under the License is distributed on an "AS IS" BASIS, *
22  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
23  * See the License for the specific language governing permissions and *
24  * limitations under the License. *
25  * -------------------------------------------------------------------------- */
26 
27 //-----------------------------------------------------------------------------
33 //-----------------------------------------------------------------------------
34 #include <iosfwd> // Forward declaration of iostream
35 //-----------------------------------------------------------------------------
36 
37 
38 //-----------------------------------------------------------------------------
39 namespace SimTK {
40 
41 //-----------------------------------------------------------------------------
42 // Forward declarations (everything is templatized by precision).
43 template <class P> class Transform_;
44 template <class P> class InverseTransform_;
45 
49 
50 
51 //-----------------------------------------------------------------------------
106 //-----------------------------------------------------------------------------
107 template <class P>
108 class Transform_ {
109 public:
111  Transform_() : R_BF(), p_BF(0) { }
112 
114  Transform_( const Rotation_<P>& R, const Vec<3,P>& p ) : R_BF(R), p_BF(p) { }
115 
118  Transform_( const Rotation_<P>& R ) : R_BF(R), p_BF(0) { }
119 
122  Transform_( const Vec<3,P>& p ) : R_BF(), p_BF(p) { }
123 
124  // default copy, assignment, destructor
125 
133  // (Definition is below after InverseTransform is declared.)
134  inline Transform_& operator=( const InverseTransform_<P>& X );
135 
138  template <int S>
139  Transform_& operator+=(const Vec<3,P,S>& offset_B)
140  { p_BF += offset_B; return *this; }
141 
144  template <int S>
145  Transform_& operator-=(const Vec<3,P,S>& offset_B)
146  { p_BF -= offset_B; return *this; }
147 
151  Transform_& set( const Rotation_<P>& R, const Vec<3,P>& p ) { p_BF=p; R_BF=R; return *this; }
152 
156  Transform_& setToZero() { R_BF.setRotationToIdentityMatrix(); p_BF = P(0); return *this; }
157 
162  Transform_& setToNaN() { R_BF.setRotationToNaN(); p_BF.setToNaN(); return *this; }
163 
166  const InverseTransform_<P>& invert() const { return *reinterpret_cast<const InverseTransform_<P>*>(this); }
167 
170  InverseTransform_<P>& updInvert() { return *reinterpret_cast<InverseTransform_<P>*>(this); }
171 
173  const InverseTransform_<P>& operator~() const {return invert();}
174 
177 
180  Transform_ compose(const Transform_& X_FY) const {
181  return Transform_( R_BF * X_FY.R(), p_BF + R_BF * X_FY.p() );
182  }
183 
189  // (Definition is below after InverseTransform_ is declared.)
190  inline Transform_ compose( const InverseTransform_<P>& X_FY ) const;
191 
195  Vec<3,P> xformFrameVecToBase( const Vec<3,P>& vF ) const {return R_BF*vF;}
196 
200  Vec<3,P> xformBaseVecToFrame( const Vec<3,P>& vB ) const { return ~R_BF*vB; }
201 
206  { return p_BF + xformFrameVecToBase(sF); }
207 
212  { return xformBaseVecToFrame(sB - p_BF); }
213 
215  const Rotation_<P>& R() const { return R_BF; }
216 
218  Rotation_<P>& updR() { return R_BF; }
219 
222  const typename Rotation_<P>::ColType& x() const { return R().x(); }
225  const typename Rotation_<P>::ColType& y() const { return R().y(); }
228  const typename Rotation_<P>::ColType& z() const { return R().z(); }
229 
232  const InverseRotation_<P>& RInv() const { return ~R_BF; }
233 
236  InverseRotation_<P>& updRInv() { return ~R_BF; }
237 
239  const Vec<3,P>& p() const { return p_BF; }
240 
243  Vec<3,P>& updP() { return p_BF; }
244 
249  Transform_<P>& setP( const Vec<3,P>& p ) { p_BF=p; return *this; }
250 
254  Vec<3,P> pInv() const { return -(~R_BF*p_BF); }
255 
263  Transform_<P>& setPInv( const Vec<3,P>& p_FB ) { p_BF = -(R_BF*p_FB); return *this; }
264 
268  const Mat<3,4,P>& asMat34() const { return Mat<3,4,P>::getAs(reinterpret_cast<const P*>(this)); }
269 
271  Mat<3,4,P> toMat34() const { return asMat34(); }
272 
274  Mat<4,4,P> toMat44() const {
275  Mat<4,4,P> tmp;
276  tmp.template updSubMat<3,4>(0,0) = asMat34();
277  tmp[3] = Row<4,P>(0,0,0,1);
278  return tmp;
279  }
280 
281  // OBSOLETE -- alternate name for p
282  const Vec<3,P>& T() const {return p();}
283  Vec<3,P>& updT() {return updP();}
284 
285 private:
286  //TODO: these might not pack correctly; should use an array of 12 Reals.
287  Rotation_<P> R_BF; // rotation matrix that expresses F's axes in R
288  Vec<3,P> p_BF; // location of F's origin measured from B's origin, expressed in B
289 };
290 
291 
292 //-----------------------------------------------------------------------------
304 //-----------------------------------------------------------------------------
305 template <class P>
306 class InverseTransform_ {
307 public:
309  InverseTransform_() : R_FB(), p_FB(0) { }
310 
311  // default copy, assignment, destructor
312 
314  operator Transform_<P>() const { return Transform_<P>( R(), p() ); }
315 
316  // Assignment from Transform_. This means that the inverse
317  // transform we're assigning to must end up with the same meaning
318  // as the inverse transform X has, so we'll need:
319  // p* == X.pInv()
320  // R* == X.RInv()
321  // Cost: one frame conversion and a negation for pInv, 18 flops.
323  // Be careful to do this in the right order in case X and this
324  // are the same object, i.e. ~X = X which is weird but has
325  // the same meaning as X = ~X, i.e. invert X in place.
326  p_FB = X.pInv(); // This might change X.p ...
327  R_FB = X.RInv(); // ... but this doesn't depend on X.p.
328  return *this;
329  }
330 
331  // Inverting one of these just recasts it back to a Transform_<P>.
332  const Transform_<P>& invert() const { return *reinterpret_cast<const Transform_<P>*>(this); }
333  Transform_<P>& updInvert() { return *reinterpret_cast<Transform_<P>*>(this); }
334 
335  // Overload transpose to mean inversion.
336  const Transform_<P>& operator~() const { return invert(); }
338 
339  // Return X_BY=X_BF*X_FY, where X_BF (this) is represented here as ~X_FB. This
340  // costs exactly the same as a composition of two Transforms (63 flops).
341  Transform_<P> compose(const Transform_<P>& X_FY) const {
342  return Transform_<P>( ~R_FB * X_FY.R(), ~R_FB *(X_FY.p() - p_FB) );
343  }
344  // Return X_BY=X_BF*X_FY, but now both xforms are represented by their inverses.
345  // This costs one extra vector transformation and a negation (18 flops) more
346  // than a composition of two Transforms, for a total of 81 flops.
348  return Transform_<P>( ~R_FB * X_FY.R(), ~R_FB *(X_FY.p() - p_FB) );
349  }
350 
351  // Forward and inverse vector transformations cost the same here as
352  // for a Transform_<P> (or for that matter, a Rotation_<P>): 15 flops.
353  Vec<3,P> xformFrameVecToBase(const Vec<3,P>& vF) const {return ~R_FB*vF;}
354  Vec<3,P> xformBaseVecToFrame(const Vec<3,P>& vB) const {return R_FB*vB;}
355 
356  // Forward and inverse station shift & transform cost the same here as for a Transform_<P>: 18 flops.
357  Vec<3,P> shiftFrameStationToBase(const Vec<3,P>& sF) const { return ~R_FB*(sF-p_FB); }
358  Vec<3,P> shiftBaseStationToFrame(const Vec<3,P>& sB) const { return R_FB*sB + p_FB; }
359 
360  const InverseRotation_<P>& R() const {return ~R_FB;}
361  InverseRotation_<P>& updR() {return ~R_FB;}
362 
363  const typename InverseRotation_<P>::ColType& x() const {return R().x();}
364  const typename InverseRotation_<P>::ColType& y() const {return R().y();}
365  const typename InverseRotation_<P>::ColType& z() const {return R().z();}
366 
367  const Rotation_<P>& RInv() const {return R_FB;}
368  Rotation_<P>& updRInv() {return R_FB;}
369 
373  Vec<3,P> p() const { return -(~R_FB*p_FB); }
374 
375 
376  // no updP lvalue
377 
378  // Sorry, can't update translation as an lvalue, but here we
379  // want -(R_BF*p_FB)=p_BF => p_FB=-(R_FB*p_BF). Cost: 18 flops.
380  void setP( const Vec<3,P>& p_BF ) { p_FB = -(R_FB*p_BF); }
381 
382  // Inverse translation is free.
383  const Vec<3,P>& pInv() const { return p_FB; }
384  void setPInv( const Vec<3,P>& p ) { p_FB = p; }
385 
388  Mat<3,4,P> toMat34() const { return Transform_<P>(*this).asMat34(); }
389 
391  Mat<4,4,P> toMat44() const { return Transform_<P>(*this).toMat44(); }
392 
393  // OBSOLETE -- alternate name for p.
394  Vec<3,P> T() const {return p();}
395 
396 private:
397  // DATA LAYOUT MUST BE IDENTICAL TO Transform_<P> !!
398  // TODO: redo packing here when it is done for Transform_<P>.
399  Rotation_<P> R_FB; // transpose of our rotation matrix, R_BF
400  Vec<3,P> p_FB; // our translation is -(R_BF*p_FB)=-(~R_FB*p_FB)
401 };
402 
408 template <class P, int S> inline Vec<3,P>
409 operator*(const Transform_<P>& X_BF, const Vec<3,P,S>& s_F)
410 { return X_BF.shiftFrameStationToBase(s_F); }
411 template <class P, int S> inline Vec<3,P>
412 operator*(const InverseTransform_<P>& X_BF, const Vec<3,P,S>& s_F)
413 { return X_BF.shiftFrameStationToBase(s_F); }
414 template <class P, int S> inline Vec<3,P>
415 operator*(const Transform_<P>& X_BF, const Vec<3,negator<P>,S>& s_F)
416 { return X_BF*Vec<3,P>(s_F); }
417 template <class P, int S> inline Vec<3,P>
418 operator*(const InverseTransform_<P>& X_BF, const Vec<3,negator<P>,S>& s_F)
419 { return X_BF*Vec<3,P>(s_F); }
420 
423 template <class P, int S> inline Transform_<P>
424 operator+(const Transform_<P>& X_BF, const Vec<3,P,S>& offset_B)
425 { return Transform_<P>(X_BF) += offset_B; }
428 template <class P, int S> inline Transform_<P>
429 operator+(const Vec<3,P,S>& offset_B, const Transform_<P>& X_BF)
430 { return Transform_<P>(X_BF) += offset_B; }
431 
434 template <class P, int S> inline Transform_<P>
435 operator-(const Transform_<P>& X_BF, const Vec<3,P,S>& offset_B)
436 { return Transform_<P>(X_BF) -= offset_B; }
437 
438 //-----------------------------------------------------------------------------
444 template <class P, int S> inline Vec<4,P>
445 operator*(const Transform_<P>& X_BF, const Vec<4,P,S>& a_F) {
446  assert(a_F[3]==0 || a_F[3]==1);
447  const Vec<3,P,S>& v_F = Vec<3,P,S>::getAs(&a_F[0]); // recast the 1st 3 elements as Vec3
448 
449  Vec<4,P> out;
450  if( a_F[3] == 0 ) { Vec<3,P>::updAs(&out[0]) = X_BF.xformFrameVecToBase(v_F); out[3] = 0; }
451  else { Vec<3,P>::updAs(&out[0]) = X_BF.shiftFrameStationToBase(v_F); out[3] = 1; }
452  return out;
453 }
454 
455 template <class P, int S> inline Vec<4,P>
456 operator*(const InverseTransform_<P>& X_BF, const Vec<4,P,S>& a_F ) {
457  assert(a_F[3]==0 || a_F[3]==1);
458  const Vec<3,P,S>& v_F = Vec<3,P,S>::getAs(&a_F[0]); // recast the 1st 3 elements as Vec3
459 
460  Vec<4,P> out;
461  if( a_F[3] == 0 ) { Vec<3,P>::updAs(&out[0]) = X_BF.xformFrameVecToBase(v_F); out[3] = 0; }
462  else { Vec<3,P>::updAs(&out[0]) = X_BF.shiftFrameStationToBase(v_F); out[3] = 1; }
463  return out;
464 }
465 template <class P, int S> inline Vec<4,P>
466 operator*(const Transform_<P>& X_BF, const Vec<4,negator<P>,S>& s_F) {return X_BF*Vec<4,P>(s_F);}
467 template <class P, int S> inline Vec<4,P>
468 operator*(const InverseTransform_<P>& X_BF, const Vec<4,negator<P>,S>& s_F) {return X_BF*Vec<4,P>(s_F);}
469 //-----------------------------------------------------------------------------
470 
474 template <class P, class E> inline Vector_<E>
475 operator*(const Transform_<P>& X, const VectorBase<E>& v) {
476  Vector_<E> result(v.size());
477  for (int i = 0; i < v.size(); ++i)
478  result[i] = X*v[i];
479  return result;
480 }
481 template <class P, class E> inline Vector_<E>
482 operator*(const VectorBase<E>& v, const Transform_<P>& X) {
483  Vector_<E> result(v.size());
484  for (int i = 0; i < v.size(); ++i)
485  result[i] = X*v[i];
486  return result;
487 }
488 template <class P, class E> inline RowVector_<E>
490  RowVector_<E> result(v.size());
491  for (int i = 0; i < v.size(); ++i)
492  result[i] = X*v[i];
493  return result;
494 }
495 template <class P, class E> inline RowVector_<E>
497  RowVector_<E> result(v.size());
498  for (int i = 0; i < v.size(); ++i)
499  result[i] = X*v[i];
500  return result;
501 }
502 template <class P, class E> inline Matrix_<E>
503 operator*(const Transform_<P>& X, const MatrixBase<E>& v) {
504  Matrix_<E> result(v.nrow(), v.ncol());
505  for (int i = 0; i < v.nrow(); ++i)
506  for (int j = 0; j < v.ncol(); ++j)
507  result(i, j) = X*v(i, j);
508  return result;
509 }
510 template <class P, class E> inline Matrix_<E>
511 operator*(const MatrixBase<E>& v, const Transform_<P>& X) {
512  Matrix_<E> result(v.nrow(), v.ncol());
513  for (int i = 0; i < v.nrow(); ++i)
514  for (int j = 0; j < v.ncol(); ++j)
515  result(i, j) = X*v(i, j);
516  return result;
517 }
518 template <class P, int N, class E, int S> inline Vec<N,E>
519 operator*(const Transform_<P>& X, const Vec<N,E,S>& v) {
520  Vec<N,E> result;
521  for (int i = 0; i < N; ++i)
522  result[i] = X*v[i];
523  return result;
524 }
525 template <class P, int N, class E, int S> inline Vec<N,E>
526 operator*(const Vec<N,E,S>& v, const Transform_<P>& X) {
527  Vec<N,E> result;
528  for (int i = 0; i < N; ++i)
529  result[i] = X*v[i];
530  return result;
531 }
532 template <class P, int N, class E, int S> inline Row<N,E>
533 operator*(const Transform_<P>& X, const Row<N,E,S>& v) {
534  Row<N,E> result;
535  for (int i = 0; i < N; ++i)
536  result[i] = X*v[i];
537  return result;
538 }
539 template <class P, int N, class E, int S> inline Row<N,E>
540 operator*(const Row<N,E,S>& v, const Transform_<P>& X) {
541  Row<N,E> result;
542  for (int i = 0; i < N; ++i)
543  result[i] = X*v[i];
544  return result;
545 }
546 template <class P, int M, int N, class E, int CS, int RS> inline Mat<M,N,E>
548  Mat<M,N,E> result;
549  for (int i = 0; i < M; ++i)
550  for (int j = 0; j < N; ++j)
551  result(i, j) = X*v(i, j);
552  return result;
553 }
554 template <class P, int M, int N, class E, int CS, int RS> inline Mat<M,N,E>
556  Mat<M,N,E> result;
557  for (int i = 0; i < M; ++i)
558  for (int j = 0; j < N; ++j)
559  result(i, j) = X*v(i, j);
560  return result;
561 }
562 
563 // These Transform definitions had to wait for InverseTransform to be declared.
564 
565 template <class P> inline Transform_<P>&
567  // Be careful to do this in the right order in case X and this
568  // are the same object, i.e. we're doing X = ~X, inverting X in place.
569  p_BF = X.p(); // This might change X.p ...
570  R_BF = X.R(); // ... but this doesn't depend on X.p.
571  return *this;
572 }
573 
574 template <class P> inline Transform_<P>
576  return Transform_<P>( R_BF * X_FY.R(), p_BF + R_BF * X_FY.p() );
577 }
578 
582 template <class P> inline Transform_<P>
583 operator*(const Transform_<P>& X1, const Transform_<P>& X2) {return X1.compose(X2);}
584 template <class P> inline Transform_<P>
585 operator*(const Transform_<P>& X1, const InverseTransform_<P>& X2) {return X1.compose(X2);}
586 template <class P> inline Transform_<P>
587 operator*(const InverseTransform_<P>& X1, const Transform_<P>& X2) {return X1.compose(X2);}
588 template <class P> inline Transform_<P>
589 operator*(const InverseTransform_<P>& X1, const InverseTransform_<P>& X2) {return X1.compose(X2);}
590 
594 template <class P> inline bool
595 operator==(const Transform_<P>& X1, const Transform_<P>& X2) {return X1.R()==X2.R() && X1.p()==X2.p();}
596 template <class P> inline bool
597 operator==(const InverseTransform_<P>& X1, const InverseTransform_<P>& X2) {return X1.R()==X2.R() && X1.p()==X2.p();}
598 template <class P> inline bool
599 operator==(const Transform_<P>& X1, const InverseTransform_<P>& X2) {return X1.R()==X2.R() && X1.p()==X2.p();}
600 template <class P> inline bool
601 operator==(const InverseTransform_<P>& X1, const Transform_<P>& X2) {return X1.R()==X2.R() && X1.p()==X2.p();}
602 
605 template <class P> SimTK_SimTKCOMMON_EXPORT std::ostream&
606 operator<<(std::ostream&, const Transform_<P>&);
609 template <class P> SimTK_SimTKCOMMON_EXPORT std::ostream&
610 operator<<(std::ostream&, const InverseTransform_<P>&);
611 
612 
613 
614 //------------------------------------------------------------------------------
615 } // End of namespace SimTK
616 
617 //--------------------------------------------------------------------------
618 #endif // SimTK_SimTKCOMMON_TRANSFORM_H
619 //--------------------------------------------------------------------------
620 
InverseRotation_< P > & updR()
Definition: Transform.h:361
#define SimTK_SimTKCOMMON_EXPORT
Definition: SimTKcommon/include/SimTKcommon/internal/common.h:224
Vec< 3, P > xformBaseVecToFrame(const Vec< 3, P > &vB) const
Transform a vector expressed in our "B" frame to our "F" frame.
Definition: Transform.h:200
(Advanced) This InverseRotation class is the inverse of a Rotation.
Definition: Rotation.h:47
bool operator==(const Transform_< P > &X1, const Transform_< P > &X2)
Comparison operators return true only if the two transforms are bit identical; that&#39;s not too useful...
Definition: Transform.h:595
This file defines the client side of the SimTK::Matrix classes, which hold medium to large...
const Vec< 3, P > & T() const
Definition: Transform.h:282
Vec< 3, P > p() const
Calculate the actual translation vector at a cost of 18 flops.
Definition: Transform.h:373
This is the vector class intended to appear in user code for large, variable size column vectors...
Definition: BigMatrix.h:171
This class is a Vec3 plus an ironclad guarantee either that:
Definition: UnitVec.h:40
This is a dataless rehash of the MatrixBase class to specialize it for RowVectors.
Definition: BigMatrix.h:165
Vec< 3, P > shiftBaseStationToFrame(const Vec< 3, P > &sB) const
Definition: Transform.h:358
This is the top-level SimTK namespace into which all SimTK names are placed to avoid collision with o...
Definition: Assembler.h:37
static Vec & updAs(ELT *p)
Recast a writable ordinary C++ array E[] to a writable Vec<M,E,S>; assumes compatible length...
Definition: Vec.h:908
Transform_< P > compose(const Transform_< P > &X_FY) const
Definition: Transform.h:341
const InverseRotation_< P >::ColType & y() const
Definition: Transform.h:364
Vec< 3, P > shiftBaseStationToFrame(const Vec< 3, P > &sB) const
Transform a point (station) measured from and expressed in our "B" frame to that same point but measu...
Definition: Transform.h:211
Transform_ & operator-=(const Vec< 3, P, S > &offset_B)
Subtract an offset from the position vector in this Transform.
Definition: Transform.h:145
static const Mat & getAs(const ELT *p)
Definition: Mat.h:1081
Transform_(const Vec< 3, P > &p)
Construct or default-convert a translation (expressed as a Vec3) into a transform with that translati...
Definition: Transform.h:122
Transform from frame B to frame F, but with the internal representation inverted. ...
Definition: Transform.h:44
Transform_(const Rotation_< P > &R, const Vec< 3, P > &p)
Combine a rotation and a translation into a transform.
Definition: Transform.h:114
The Rotation class is a Mat33 that guarantees that the matrix can be interpreted as a legitimate 3x3 ...
Definition: Quaternion.h:40
Vec< 3, P > xformBaseVecToFrame(const Vec< 3, P > &vB) const
Definition: Transform.h:354
const Rotation_< P >::ColType & z() const
Return a read-only reference to the z direction (unit vector) of the F frame, expressed in the B fram...
Definition: Transform.h:228
const Rotation_< P > & R() const
Return a read-only reference to the contained rotation R_BF.
Definition: Transform.h:215
Transform_(const Rotation_< P > &R)
Construct or default-convert a rotation into a transform containing that rotation and zero translatio...
Definition: Transform.h:118
const Rotation_< P >::ColType & x() const
Return a read-only reference to the x direction (unit vector) of the F frame, expressed in the B fram...
Definition: Transform.h:222
Vec< 3, P > & updT()
Definition: Transform.h:283
InverseRotation_< P > & updRInv()
Return a writable (lvalue) reference to the inverse (transpose) of our contained rotation, that is R_FB.
Definition: Transform.h:236
negator<N>, where N is a number type (real, complex, conjugate), is represented in memory identically...
Definition: String.h:44
void setP(const Vec< 3, P > &p_BF)
Definition: Transform.h:380
const InverseTransform_< P > & invert() const
Return a read-only inverse of the current Transform_.
Definition: Transform.h:166
Mat< 3, 4, P > toMat34() const
For compatibility with Transform_.
Definition: Transform.h:388
const InverseRotation_< P > & R() const
Definition: Transform.h:360
Vec< 3, P > operator*(const Transform_< P > &X_BF, const Vec< 3, P, S > &s_F)
If we multiply a transform or inverse transform by a 3-vector, we treat the vector as though it had a...
Definition: Transform.h:409
Declares and defines the UnitVec and UnitRow classes.
Vec< 3, P > xformFrameVecToBase(const Vec< 3, P > &vF) const
Transform a vector expressed in our "F" frame to our "B" frame.
Definition: Transform.h:195
Vec< 3, P > shiftFrameStationToBase(const Vec< 3, P > &sF) const
Definition: Transform.h:357
Transform_< P > & setPInv(const Vec< 3, P > &p_FB)
Assign a value to the inverse of our translation vector.
Definition: Transform.h:263
Vec< 3, P > shiftFrameStationToBase(const Vec< 3, P > &sF) const
Transform a point (station) measured from and expressed in our "F" frame to that same point but measu...
Definition: Transform.h:205
const Rotation_< P > & RInv() const
Definition: Transform.h:367
Transform_< P > operator+(const Transform_< P > &X_BF, const Vec< 3, P, S > &offset_B)
Adding a 3-vector to a Transform produces a new shifted transform.
Definition: Transform.h:424
void setToNaN()
Set every scalar in this Vec to NaN; this is the default initial value in Debug builds, but not in Release.
Definition: Vec.h:812
InverseTransform_< P > & updInvert()
Return a writable (lvalue) inverse of the current transform, simply by casting it to the InverseTrans...
Definition: Transform.h:170
const Rotation_< P >::ColType & y() const
Return a read-only reference to the y direction (unit vector) of the F frame, expressed in the B fram...
Definition: Transform.h:225
Transform_< P > operator-(const Transform_< P > &X_BF, const Vec< 3, P, S > &offset_B)
Subtracting a 3-vector from a Transform produces a new shifted transform.
Definition: Transform.h:435
This class represents the rotate-and-shift transform which gives the location and orientation of a ne...
Definition: Transform.h:43
Transform_< P > operator+(const Vec< 3, P, S > &offset_B, const Transform_< P > &X_BF)
Adding a 3-vector to a Transform produces a new shifted transform.
Definition: Transform.h:429
int ncol() const
Return the number of columns n in the logical shape of this matrix.
Definition: MatrixBase.h:138
Transform_ compose(const Transform_ &X_FY) const
Compose the current transform (X_BF) with the given one.
Definition: Transform.h:180
This file is the user-includeable header to be included in user programs to provide fixed-length Vec ...
Mat< 3, 4, P > toMat34() const
Less efficient version of asMat34(); copies into return variable.
Definition: Transform.h:271
const InverseRotation_< P > & RInv() const
Return a read-only reference to the inverse (transpose) of our contained rotation, that is R_FB.
Definition: Transform.h:232
This is the matrix class intended to appear in user code for large, variable size matrices...
Definition: BigMatrix.h:168
Rotation_< P > & updR()
Return a writable (lvalue) reference to the contained rotation R_BF.
Definition: Transform.h:218
const InverseRotation_< P >::ColType & x() const
Definition: Transform.h:363
const Transform_< P > & invert() const
Definition: Transform.h:332
Transform_()
Default constructor gives an identity transform.
Definition: Transform.h:111
Transform_ & operator+=(const Vec< 3, P, S > &offset_B)
Add an offset to the position vector in this Transform.
Definition: Transform.h:139
Vec< 3, P > & updP()
Return a writable (lvalue) reference to our translation vector p_BF.
Definition: Transform.h:243
InverseTransform_()
Default constructor produces an identity transform.
Definition: Transform.h:309
Vector_< E > operator*(const Transform_< P > &X, const VectorBase< E > &v)
Multiplying a matrix or vector by a Transform_.
Definition: Transform.h:475
Transform_ & operator=(const InverseTransform_< P > &X)
Assignment from InverseTransform.
Definition: Transform.h:566
const Mat< 3, 4, P > & asMat34() const
Recast this transform as a read-only 3x4 matrix.
Definition: Transform.h:268
This is a fixed-length row vector designed for no-overhead inline computation.
Definition: SimTKcommon/include/SimTKcommon/internal/common.h:619
const InverseRotation_< P >::ColType & z() const
Definition: Transform.h:365
Transform_ & setToZero()
By zero we mean "zero transform", i.e., an identity rotation and zero translation.
Definition: Transform.h:156
Vec< 3, P > pInv() const
Calculate the inverse of the translation vector in this transform.
Definition: Transform.h:254
Transform_< double > dTransform
Definition: Transform.h:48
int size() const
Definition: RowVectorBase.h:237
This is a dataless rehash of the MatrixBase class to specialize it for Vectors.
Definition: BigMatrix.h:164
const Vec< 3, P > & pInv() const
Definition: Transform.h:383
Transform_< P > & updInvert()
Definition: Transform.h:333
Represents a variable size row vector; much less common than the column vector type Vector_...
Definition: BigMatrix.h:174
int size() const
Definition: VectorBase.h:396
Vec< 3, P > xformFrameVecToBase(const Vec< 3, P > &vF) const
Definition: Transform.h:353
InverseTransform_ & operator=(const Transform_< P > &X)
Definition: Transform.h:322
This class represents a small matrix whose size is known at compile time, containing elements of any ...
Definition: SimTKcommon/include/SimTKcommon/internal/common.h:620
Transform_ & setToNaN()
This fills both the rotation and translation with NaNs.
Definition: Transform.h:162
This is the common base class for Simbody&#39;s Vector_ and Matrix_ classes for handling large...
Definition: BigMatrix.h:163
const InverseTransform_< P > & operator~() const
Overload transpose operator to mean inversion.
Definition: Transform.h:173
Mat< 4, 4, P > toMat44() const
Return the equivalent 4x4 transformation matrix.
Definition: Transform.h:391
Rotation_< P > & updRInv()
Definition: Transform.h:368
Vec< 4, P > operator*(const Transform_< P > &X_BF, const Vec< 4, P, S > &a_F)
If we multiply a transform or inverse transform by an augmented 4-vector, we use the 4th element to d...
Definition: Transform.h:445
Mat< 4, 4, P > toMat44() const
Return the equivalent 4x4 transformation matrix.
Definition: Transform.h:274
const Vec< 3, P > & p() const
Return a read-only reference to our translation vector p_BF.
Definition: Transform.h:239
Transform_< P > compose(const InverseTransform_< P > &X_FY) const
Definition: Transform.h:347
Transform_< float > fTransform
Definition: Transform.h:47
int nrow() const
Return the number of rows m in the logical shape of this matrix.
Definition: MatrixBase.h:136
InverseTransform_< P > & operator~()
Overload transpose operator to mean inversion.
Definition: Transform.h:176
Transform_< Real > Transform
Definition: Transform.h:44
Transform_< P > & setP(const Vec< 3, P > &p)
Assign a new value to our translation vector.
Definition: Transform.h:249
const Transform_< P > & operator~() const
Definition: Transform.h:336
Vec< 3, P > T() const
Definition: Transform.h:394
static const Vec & getAs(const ELT *p)
Recast an ordinary C++ array E[] to a const Vec<M,E,S>; assumes compatible length, stride, and packing.
Definition: Vec.h:904
Transform_< P > & operator~()
Definition: Transform.h:337
Transform_< P > operator*(const Transform_< P > &X1, const Transform_< P > &X2)
Composition of transforms.
Definition: Transform.h:583
void setPInv(const Vec< 3, P > &p)
Definition: Transform.h:384