Ravelin
MovingTransform3.h
1 /****************************************************************************
2  * Copyright 2014 Evan Drumwright
3  * This library is distributed under the terms of the Apache V2.0
4  * License (obtainable from http://www.apache.org/licenses/LICENSE-2.0).
5  ****************************************************************************/
6 
7 #ifndef MOVINGTRANSFORM3
8 #error This class is not to be included by the user directly. Use MovingTransform3d.h or MovingTransform3f.h instead.
9 #endif
10 
11 class POSE3;
12 
15 {
16  public:
18  SACCEL transform(const SACCEL& a) const;
19 /*
20  POSE3 transform(const POSE3& p) const;
21  POSE3 inverse_transform(const POSE3& p) const;
22  SACCEL inverse_transform(const SACCEL& t) const;
23  TRANSFORM3& invert();
24  TRANSFORM3 inverse() const { return invert(*this); }
25  static TRANSFORM3 invert(const TRANSFORM3& m);
26 */
28  static MOVINGTRANSFORM3 calc_transform(boost::shared_ptr<const POSE3> source, boost::shared_ptr<const POSE3> target, const SVELOCITY& vs, const SVELOCITY& vt);
29 
32 
35 
38 
41 
44 
46  boost::shared_ptr<const POSE3> source;
47 
49  boost::shared_ptr<const POSE3> target;
50 
51  private:
52  void transform_spatial(const SVECTOR6& w, SVECTOR6& result) const;
53  void inverse_transform_spatial(const SVECTOR6& w, SVECTOR6& result) const;
54 }; // end class
55 
56 std::ostream& operator<<(std::ostream& out, const MOVINGTRANSFORM3& m);
57 
MOVINGTRANSFORM3 & operator=(const MOVINGTRANSFORM3 &source)
Copies a moving transform to another.
Definition: MovingTransform3.cpp:22
SVELOCITY v
the velocity of the original frame
Definition: MovingTransform3.h:31
SACCEL transform(const SACCEL &a) const
Transforms a spatial acceleration (defined relative to the source frame's relative pose) to a spatial...
Definition: MovingTransform3.cpp:38
ORIGIN3 rdot
the time derivative of the r vector
Definition: MovingTransform3.h:37
A spatial velocity (a twist)
Definition: SVelocity.h:15
A rigid body pose.
Definition: Pose3.h:15
A 6-dimensional floating-point vector for use with spatial algebra.
Definition: SVector6.h:22
A transformation between two rigid body poses.
Definition: MovingTransform3.h:14
MOVINGTRANSFORM3()
Sets up a default moving transform.
Definition: MovingTransform3.cpp:10
A spatial (six dimensional) acceleration.
Definition: SAccel.h:14
boost::shared_ptr< const POSE3 > target
the "target" pose
Definition: MovingTransform3.h:49
static MOVINGTRANSFORM3 calc_transform(boost::shared_ptr< const POSE3 > source, boost::shared_ptr< const POSE3 > target, const SVELOCITY &vs, const SVELOCITY &vt)
Computes the relative transformation between two moving poses.
Definition: MovingTransform3.cpp:93
A three-dimensional floating point vector used for representing points and vectors in 3D and without ...
Definition: Origin3.h:16
MATRIX3 Edot
the time derivative of the E matrix
Definition: MovingTransform3.h:43
ORIGIN3 r
the r vector
Definition: MovingTransform3.h:34
MATRIX3 E
the E matrix
Definition: MovingTransform3.h:40
boost::shared_ptr< const POSE3 > source
the "source" pose
Definition: MovingTransform3.h:46
A 3x3 matrix that may be used for orientation, inertia tensors, etc.
Definition: Matrix3.h:20