Public Member Functions | Protected Attributes | List of all members
RobotDynamics::Math::SpatialMotion Class Reference

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. More...

#include <SpatialMotion.hpp>

Inheritance diagram for RobotDynamics::Math::SpatialMotion:
Inheritance graph
[legend]

Public Member Functions

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::TransformableGeometricObjectgetTransformableGeometricObject ()
 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( $\times$) operator times a MotionVector. In VDuindam the spatial vector cross operator is referred to as the adjoint of a twist, denoted $ad_T$. This method performs,

\[ m =(v\times) m = ad_{v}m = \begin{bmatrix} \omega\times & \mathbf{0} \\ v\times & \omega\times \end{bmatrix} m \]

The 3d vector $\times$ operator is equivalent to the $\sim$ 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...
 
SpatialMotionoperator= (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...
 
- Public Member Functions inherited from RobotDynamics::Math::MotionVector
MotionVector cross (const MotionVector &v)
 See V. Duindum thesis p.25 for an explanation of what $ad_T$ operator is. It is also in Featherstone p. 25 eq. 2.31 & 2.32. For featherstone notation, it is essentially the $\times$ operator for spatial vectors. Given two SpatialMotion vectors, $v_1$ and $v_2$, this method returns $ v_3 = (v_1\times) v_2 $. Expanded, it looks like,

\[ v_3 = (v_1 \times) v_2 = ad_{v_1} v_2 = \begin{bmatrix} \omega_{v_1} \times & \mathbf{0} \\ v_{v_1}\times & \omega_{v_1}\times \end{bmatrix} v_2 \]

The 3d vector $\times$ operator is equivalent to the $\sim$ 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 $\times *$ operator for spatial vectors. Given a SpatialMotion vector, $v_1$, and SpatialForceVector, $f_1$, this method returns $ f_2 = (v_1\times *) f_1 $. Expanded, it looks like,

\[ =(v_1\times *) f_1 = \begin{bmatrix} \omega_{v_1}\times & v_{v_1}\times \\ \mathbf{0} & \omega_{v_1}\times \end{bmatrix} f \]

The 3d vector $\times$ operator is equivalent to the $\sim$ operator. See Math::toTildeForm. More...

 
SpatialMatrix crossf ()
 Get the spatial force cross matrix. More...
 
SpatialMatrix crossm ()
 Get the spatial motion cross matrix,

\[ m\times = \begin{bmatrix} \omega\times & \mathbf{0} \\ v\times & \omega\times \end{bmatrix} \]

. 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 $\times$ operator for two motion vectors, i.e. $m_2=(m_1\times)m_2$. More...
 
ForceVector operator%= (const ForceVector &v)
 Operator for performing the RBDA $ \times * $ operator for a motion vector and a force vector, i.e. $ f=(m\times *)f $. More...
 
MotionVector operator+= (const MotionVector &v)
 Overloaded += operator for a MotionVector. More...
 
MotionVectoroperator= (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 $ v= X v $. More...
 
MotionVector transform_copy (const SpatialTransform &X) const
 Copies, transforms, and returns a MotionVector. Performs $ v_2=X v_1 $. 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...
 
- Public Member Functions inherited from RobotDynamics::Math::SpatialVector
EIGEN_STRONG_INLINE Vector3d getAngularPart () const
 
EIGEN_STRONG_INLINE Vector3d getLinearPart () const
 
template<typename OtherDerived >
SpatialVectoroperator= (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)
 
- Public Member Functions inherited from RobotDynamics::FrameObject
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...
 

Protected Attributes

ReferenceFramePtr baseFrame
 
ReferenceFramePtr bodyFrame
 
- Protected Attributes inherited from RobotDynamics::FrameObject
ReferenceFramePtr referenceFrame
 

Additional Inherited Members

- Public Types inherited from RobotDynamics::Math::SpatialVector
typedef Eigen::Matrix< double, 6, 1 > Base
 

Detailed Description

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.

Constructor & Destructor Documentation

RobotDynamics::Math::SpatialMotion::SpatialMotion ( )
inline

Constructor. SpatialMotion::bodyFrame, SpatialMotion::baseFrame, and RobotDynamics::FrameObject::referenceFrame initialized to nullptr.

Definition at line 42 of file SpatialMotion.hpp.

RobotDynamics::Math::SpatialMotion::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 
)
inline

Constructor.

Parameters
bodyFrameRobotDynamics::ReferenceFrame in motion
baseFrameRobotDynamics::ReferenceFrame the motion is relative to
expressedInFrameRobotDynamics::ReferenceFrame the motion vector is expressed in
wxx-Angular part
wyy-Angular part
wzz-Angular part
vxx-Linear part
vyy-Linear part
vzz-Linear part

Definition at line 60 of file SpatialMotion.hpp.

RobotDynamics::Math::SpatialMotion::SpatialMotion ( ReferenceFramePtr  bodyFrame,
ReferenceFramePtr  baseFrame,
ReferenceFramePtr  expressedInFrame,
const Vector3d w,
const Vector3d  v 
)
inline

Constructor.

Parameters
bodyFrameRobotDynamics::ReferenceFrame in motion
baseFrameRobotDynamics::ReferenceFrame the motion is relative to
expressedInFrameRobotDynamics::ReferenceFrame the motion vector is expressed in
wAngular part
vLinear part

Definition at line 76 of file SpatialMotion.hpp.

RobotDynamics::Math::SpatialMotion::SpatialMotion ( ReferenceFramePtr  bodyFrame,
ReferenceFramePtr  baseFrame,
ReferenceFramePtr  expressedInFrame,
const SpatialVector v 
)
inline

Constructor.

Parameters
bodyFrameRobotDynamics::ReferenceFrame in motion
baseFrameRobotDynamics::ReferenceFrame the motion is relative to
expressedInFrameRobotDynamics::ReferenceFrame the motion vector is expressed in
v

Definition at line 90 of file SpatialMotion.hpp.

RobotDynamics::Math::SpatialMotion::SpatialMotion ( const SpatialMotion spatialMotion)
inline

Copy constructor.

Parameters
spatialMotion

Definition at line 101 of file SpatialMotion.hpp.

Member Function Documentation

SpatialMotion RobotDynamics::Math::SpatialMotion::changeFrameAndCopy ( ReferenceFramePtr  referenceFrame) const
inline

Copy and change frame.

Parameters
referenceFrame
Returns
Copied spatial transform with frame changed

Definition at line 135 of file SpatialMotion.hpp.

ReferenceFramePtr RobotDynamics::Math::SpatialMotion::getBaseFrame ( ) const
inline

Get a SpatialMotions SpatialMotion::baseFrame.

Returns
The base frame, i.e. the frame the SpatialMotion is relative to

Definition at line 155 of file SpatialMotion.hpp.

ReferenceFramePtr RobotDynamics::Math::SpatialMotion::getBodyFrame ( ) const
inline

Get a SpatialMotions SpatialMotion::bodyFrame.

Returns
The body frame, i.e. the principal moving frame

Definition at line 146 of file SpatialMotion.hpp.

FrameVector RobotDynamics::Math::SpatialMotion::getFramedAngularPart ( ) const
inline

Get angular part of spatial motion as a frame vector.

Returns
FrameVector consisting of the reference frame and the angular portion

Definition at line 120 of file SpatialMotion.hpp.

FrameVector RobotDynamics::Math::SpatialMotion::getFramedLinearPart ( ) const
inline

Get linear part of spatial motion as a frame vector.

Returns
FrameVector consisting of the reference frame and the linear portion

Definition at line 111 of file SpatialMotion.hpp.

Math::TransformableGeometricObject* RobotDynamics::Math::SpatialMotion::getTransformableGeometricObject ( )
inlinevirtual

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.

Returns

Implements RobotDynamics::FrameObject.

Definition at line 125 of file SpatialMotion.hpp.

void RobotDynamics::Math::SpatialMotion::operator%= ( const SpatialMotion v)

This is an operator for performing what is referred to in Featherstone as the spatial vector cross( $\times$) operator times a MotionVector. In VDuindam the spatial vector cross operator is referred to as the adjoint of a twist, denoted $ad_T$. This method performs,

\[ m =(v\times) m = ad_{v}m = \begin{bmatrix} \omega\times & \mathbf{0} \\ v\times & \omega\times \end{bmatrix} m \]

The 3d vector $\times$ operator is equivalent to the $\sim$ operator. See Math::toTildeForm.

Parameters
v

Definition at line 56 of file SpatialMotion.cpp.

void RobotDynamics::Math::SpatialMotion::operator+= ( const SpatialMotion v)

Overloaded += operator. Frame checks are performed.

Parameters
v

Definition at line 14 of file SpatialMotion.cpp.

void RobotDynamics::Math::SpatialMotion::operator-= ( const SpatialMotion v)

Overloaded -= operator. Frame checks are performed.

Parameters
v

Definition at line 30 of file SpatialMotion.cpp.

SpatialMotion& RobotDynamics::Math::SpatialMotion::operator= ( const SpatialMotion other)
inline

Definition at line 181 of file SpatialMotion.hpp.

void RobotDynamics::Math::SpatialMotion::setBaseFrame ( ReferenceFramePtr  referenceFrame)
inline

Sets the base frame of a spatial motion.

Parameters
referenceFrame

Definition at line 233 of file SpatialMotion.hpp.

void RobotDynamics::Math::SpatialMotion::setBodyFrame ( ReferenceFramePtr  referenceFrame)
inline

Sets the body frame of a spatial motion.

Parameters
referenceFrame

Definition at line 224 of file SpatialMotion.hpp.

void RobotDynamics::Math::SpatialMotion::setIncludingFrame ( ReferenceFramePtr  referenceFrame,
const SpatialVector v 
)
inline

Definition at line 169 of file SpatialMotion.hpp.

void RobotDynamics::Math::SpatialMotion::setIncludingFrame ( ReferenceFramePtr  referenceFrame,
double  wx,
double  wy,
double  wz,
double  vx,
double  vy,
double  vz 
)
inline

Definition at line 175 of file SpatialMotion.hpp.

MotionVector RobotDynamics::Math::SpatialMotion::toMotionVector ( ) const
inline

Get a copy of this SpatialMotion as type MotionVector.

Returns
MotionVector that is a copy of a SpatialMotion

Definition at line 164 of file SpatialMotion.hpp.

Member Data Documentation

ReferenceFramePtr RobotDynamics::Math::SpatialMotion::baseFrame
protected

Definition at line 240 of file SpatialMotion.hpp.

ReferenceFramePtr RobotDynamics::Math::SpatialMotion::bodyFrame
protected

Definition at line 239 of file SpatialMotion.hpp.


The documentation for this class was generated from the following files:


rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:28