|
SpatialMotion | changeFrameAndCopy (ReferenceFramePtr referenceFrame) const |
| Copy and change frame. More...
|
|
ReferenceFramePtr | getBaseFrame () const |
| Get a SpatialMotions SpatialMotion::baseFrame. More...
|
|
ReferenceFramePtr | getBodyFrame () const |
| Get a SpatialMotions SpatialMotion::bodyFrame. More...
|
|
FrameVector | getFramedAngularPart () const |
| Get angular part of spatial motion as a frame vector. More...
|
|
FrameVector | getFramedLinearPart () const |
| Get linear part of spatial motion as a frame vector. More...
|
|
Math::TransformableGeometricObject * | getTransformableGeometricObject () |
| Pure virtual method that FrameObjects are required to implement so the FrameObject::changeFrame method is able to access the TransformableGeometricObject which is required to implement the TransformableGeometricObject::transform method. More...
|
|
void | operator%= (const SpatialMotion &v) |
| This is an operator for performing what is referred to in Featherstone as the spatial vector cross( ) operator times a MotionVector. In VDuindam the spatial vector cross operator is referred to as the adjoint of a twist, denoted . This method performs,
The 3d vector operator is equivalent to the operator. See Math::toTildeForm. More...
|
|
void | operator+= (const SpatialMotion &v) |
| Overloaded += operator. Frame checks are performed. More...
|
|
void | operator-= (const SpatialMotion &v) |
| Overloaded -= operator. Frame checks are performed. More...
|
|
SpatialMotion & | operator= (const SpatialMotion &other) |
|
void | setBaseFrame (ReferenceFramePtr referenceFrame) |
| Sets the base frame of a spatial motion. More...
|
|
void | setBodyFrame (ReferenceFramePtr referenceFrame) |
| Sets the body frame of a spatial motion. More...
|
|
void | setIncludingFrame (ReferenceFramePtr referenceFrame, const SpatialVector &v) |
|
void | setIncludingFrame (ReferenceFramePtr referenceFrame, double wx, double wy, double wz, double vx, double vy, double vz) |
|
| SpatialMotion () |
| Constructor. SpatialMotion::bodyFrame, SpatialMotion::baseFrame, and RobotDynamics::FrameObject::referenceFrame initialized to nullptr. More...
|
|
| SpatialMotion (ReferenceFramePtr bodyFrame, ReferenceFramePtr baseFrame, ReferenceFramePtr expressedInFrame, const double wx, const double wy, const double wz, const double vx, const double vy, const double vz) |
| Constructor. More...
|
|
| SpatialMotion (ReferenceFramePtr bodyFrame, ReferenceFramePtr baseFrame, ReferenceFramePtr expressedInFrame, const Vector3d &w, const Vector3d v) |
| Constructor. More...
|
|
| SpatialMotion (ReferenceFramePtr bodyFrame, ReferenceFramePtr baseFrame, ReferenceFramePtr expressedInFrame, const SpatialVector &v) |
| Constructor. More...
|
|
| SpatialMotion (const SpatialMotion &spatialMotion) |
| Copy constructor. More...
|
|
MotionVector | toMotionVector () const |
| Get a copy of this SpatialMotion as type MotionVector. More...
|
|
MotionVector | cross (const MotionVector &v) |
| See V. Duindum thesis p.25 for an explanation of what operator is. It is also in Featherstone p. 25 eq. 2.31 & 2.32. For featherstone notation, it is essentially the operator for spatial vectors. Given two SpatialMotion vectors, and , this method returns . Expanded, it looks like,
The 3d vector operator is equivalent to the operator. See Math::toTildeForm. More...
|
|
ForceVector | cross (const ForceVector &v) |
| See Featherstone p. 25 eq. 2.31 & 2.32. For featherstone notation, it is essentially the operator for spatial vectors. Given a SpatialMotion vector, , and SpatialForceVector, , this method returns . Expanded, it looks like,
The 3d vector operator is equivalent to the operator. See Math::toTildeForm. More...
|
|
SpatialMatrix | crossf () |
| Get the spatial force cross matrix. More...
|
|
SpatialMatrix | crossm () |
| Get the spatial motion cross matrix,
. More...
|
|
template<typename OtherDerived > |
| MotionVector (const Eigen::MatrixBase< OtherDerived > &other) |
| Constructor. More...
|
|
EIGEN_STRONG_INLINE | MotionVector () |
| Empty constructor. More...
|
|
| MotionVector (const double v0, const double v1, const double v2, const double v3, const double v4, const double v5) |
| Constructor. More...
|
|
MotionVector | operator%= (const MotionVector &v) |
| Operator for performing the RBDA operator for two motion vectors, i.e. . More...
|
|
ForceVector | operator%= (const ForceVector &v) |
| Operator for performing the RBDA operator for a motion vector and a force vector, i.e. . More...
|
|
MotionVector | operator+= (const MotionVector &v) |
| Overloaded += operator for a MotionVector. More...
|
|
MotionVector & | operator= (const MotionVector &other) |
| Overload equal operator. More...
|
|
EIGEN_STRONG_INLINE void | set (const MotionVector &v) |
| Setter. More...
|
|
EIGEN_STRONG_INLINE SpatialVector | toSpatialVector () const |
| Get a copy of a MotionVector as a SpatialVector. More...
|
|
void | transform (const SpatialTransform &X) |
| Transforms a motion vector. Performs . More...
|
|
MotionVector | transform_copy (const SpatialTransform &X) const |
| Copies, transforms, and returns a MotionVector. Performs . More...
|
|
EIGEN_STRONG_INLINE double & | vx () |
| Get a reference to the linear-x component. More...
|
|
EIGEN_STRONG_INLINE double | vx () const |
| Get a copy of the linear-x component. More...
|
|
EIGEN_STRONG_INLINE double & | vy () |
| Get a reference to the linear-y component. More...
|
|
EIGEN_STRONG_INLINE double | vy () const |
| Get a copy of the linear-y component. More...
|
|
EIGEN_STRONG_INLINE double & | vz () |
| Get a reference to the linear-z component. More...
|
|
EIGEN_STRONG_INLINE double | vz () const |
| Get a copy of the linear-z component. More...
|
|
EIGEN_STRONG_INLINE double & | wx () |
| Get a reference to the angular-x component. More...
|
|
EIGEN_STRONG_INLINE double | wx () const |
| Get a copy of the angular-x component. More...
|
|
EIGEN_STRONG_INLINE double & | wy () |
| Get a reference to the angular-y component. More...
|
|
EIGEN_STRONG_INLINE double | wy () const |
| Get a copy of the angular-y component. More...
|
|
EIGEN_STRONG_INLINE double & | wz () |
| Get a reference to the angular-z component. More...
|
|
EIGEN_STRONG_INLINE double | wz () const |
| Get a copy of the angular-z component. More...
|
|
EIGEN_STRONG_INLINE Vector3d | getAngularPart () const |
|
EIGEN_STRONG_INLINE Vector3d | getLinearPart () const |
|
template<typename OtherDerived > |
SpatialVector & | operator= (const Eigen::MatrixBase< OtherDerived > &other) |
|
EIGEN_STRONG_INLINE void | set (const double &v0, const double &v1, const double &v2, const double &v3, const double &v4, const double &v5) |
|
EIGEN_STRONG_INLINE void | set (const Vector3d &angularPart, const Vector3d &linearPart) |
|
void | setAngularPart (const Vector3d &v) |
|
void | setLinearPart (const Vector3d &v) |
|
template<typename OtherDerived > |
| SpatialVector (const Eigen::MatrixBase< OtherDerived > &other) |
|
EIGEN_STRONG_INLINE | SpatialVector () |
|
EIGEN_STRONG_INLINE | SpatialVector (const double &v0, const double &v1, const double &v2, const double &v3, const double &v4, const double &v5) |
|
virtual void | changeFrame (ReferenceFramePtr desiredFrame) |
| Change the ReferenceFrame this FrameObject is expressed in. More...
|
|
void | checkReferenceFramesMatch (const FrameObject *frameObject) const |
| Check if two ReferenceFrameHolders hold the same ReferenceFrame. More...
|
|
void | checkReferenceFramesMatch (FrameObject *frameObject) const |
|
| FrameObject (ReferenceFramePtr referenceFrame) |
|
ReferenceFramePtr | getReferenceFrame () const |
| Get a pointer to the reference frame this FrameObject is expressed in. More...
|
|
void | setReferenceFrame (ReferenceFramePtr frame) |
| Set frame objects internal reference frame. More...
|
|
virtual | ~FrameObject () |
| Destructor. More...
|
|
A SpatialMotion vector is a MotionVector with a RobotDynamics::ReferenceFrame it is expressed in. This allows for runtime checks that frame rules are obeyed and makes it easy to change the frame the metion vector is expressed in. As with a SpatialAcceleration, a SpatialMotion vector is the spatial velocity of a SpatialMotion::bodyFrame relative to a SpatialMotion::baseFrame and is expressed in RobotDynamics::FrameObject::referenceFrame.
Definition at line 35 of file SpatialMotion.hpp.