Public Member Functions | List of all members
RobotDynamics::Math::MotionVector Class Reference

#include <MotionVector.hpp>

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

Public Member Functions

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)
 

Additional Inherited Members

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

Detailed Description

Definition at line 24 of file MotionVector.hpp.

Constructor & Destructor Documentation

template<typename OtherDerived >
RobotDynamics::Math::MotionVector::MotionVector ( const Eigen::MatrixBase< OtherDerived > &  other)
inline

Constructor.

Parameters
other

Definition at line 33 of file MotionVector.hpp.

EIGEN_STRONG_INLINE RobotDynamics::Math::MotionVector::MotionVector ( )
inline

Empty constructor.

Definition at line 51 of file MotionVector.hpp.

RobotDynamics::Math::MotionVector::MotionVector ( const double  v0,
const double  v1,
const double  v2,
const double  v3,
const double  v4,
const double  v5 
)
inline

Constructor.

Parameters
v0x-angular
v1y-angular
v2z-angular
v3x-linear
v4y-linear
v5z-linear

Definition at line 64 of file MotionVector.hpp.

Member Function Documentation

MotionVector RobotDynamics::Math::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.

Definition at line 14 of file MotionVector.cpp.

ForceVector RobotDynamics::Math::MotionVector::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.

Definition at line 36 of file MotionVector.cpp.

SpatialMatrix RobotDynamics::Math::MotionVector::crossf ( )
inline

Get the spatial force cross matrix.

Returns
$ v\times* $

Definition at line 277 of file MotionVector.hpp.

SpatialMatrix RobotDynamics::Math::MotionVector::crossm ( )
inline

Get the spatial motion cross matrix,

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

.

Returns
$ v\times $

Definition at line 266 of file MotionVector.hpp.

MotionVector RobotDynamics::Math::MotionVector::operator%= ( const MotionVector v)
inline

Operator for performing the RBDA $\times$ operator for two motion vectors, i.e. $m_2=(m_1\times)m_2$.

Parameters
v
Returns
A MotionVector

Definition at line 290 of file MotionVector.hpp.

ForceVector RobotDynamics::Math::MotionVector::operator%= ( const ForceVector v)
inline

Operator for performing the RBDA $ \times * $ operator for a motion vector and a force vector, i.e. $ f=(m\times *)f $.

Parameters
v
Returns
A ForceVector

Definition at line 301 of file MotionVector.hpp.

MotionVector RobotDynamics::Math::MotionVector::operator+= ( const MotionVector v)
inline

Overloaded += operator for a MotionVector.

Returns
MotionVector

Definition at line 310 of file MotionVector.hpp.

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

Overload equal operator.

Parameters
other
Returns
A motion vector

Definition at line 42 of file MotionVector.hpp.

EIGEN_STRONG_INLINE void RobotDynamics::Math::MotionVector::set ( const MotionVector v)
inline

Setter.

Parameters
vSets the values equal to those stored in v

Definition at line 84 of file MotionVector.hpp.

EIGEN_STRONG_INLINE SpatialVector RobotDynamics::Math::MotionVector::toSpatialVector ( ) const
inline

Get a copy of a MotionVector as a SpatialVector.

Returns
SpatialVector copy of a MotionVectors

Definition at line 75 of file MotionVector.hpp.

void RobotDynamics::Math::MotionVector::transform ( const SpatialTransform X)
inlinevirtual

Transforms a motion vector. Performs $ v= X v $.

Parameters
X

Implements RobotDynamics::Math::TransformableGeometricObject.

Definition at line 201 of file MotionVector.hpp.

MotionVector RobotDynamics::Math::MotionVector::transform_copy ( const SpatialTransform X) const
inline

Copies, transforms, and returns a MotionVector. Performs $ v_2=X v_1 $.

Parameters
X
Returns
Copied, transformed MotionVector

Definition at line 217 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::MotionVector::vx ( )
inline

Get a reference to the linear-x component.

Returns
A reference to the linear x-component

Definition at line 147 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::MotionVector::vx ( ) const
inline

Get a copy of the linear-x component.

Returns
A copy of the linear x-component

Definition at line 174 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::MotionVector::vy ( )
inline

Get a reference to the linear-y component.

Returns
A reference to the linear y-component

Definition at line 156 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::MotionVector::vy ( ) const
inline

Get a copy of the linear-y component.

Returns
A copy of the linear y-component

Definition at line 183 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::MotionVector::vz ( )
inline

Get a reference to the linear-z component.

Returns
A reference to the linear z-component

Definition at line 165 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::MotionVector::vz ( ) const
inline

Get a copy of the linear-z component.

Returns
A copy of the linear z-component

Definition at line 192 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::MotionVector::wx ( )
inline

Get a reference to the angular-x component.

Returns
A reference to the angular x-component

Definition at line 93 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::MotionVector::wx ( ) const
inline

Get a copy of the angular-x component.

Returns
A copy of the angular x-component

Definition at line 120 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::MotionVector::wy ( )
inline

Get a reference to the angular-y component.

Returns
A reference to the angular y-component

Definition at line 102 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::MotionVector::wy ( ) const
inline

Get a copy of the angular-y component.

Returns
A copy of the angular y-component

Definition at line 129 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::MotionVector::wz ( )
inline

Get a reference to the angular-z component.

Returns
A copy reference to the angular z-component

Definition at line 111 of file MotionVector.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::MotionVector::wz ( ) const
inline

Get a copy of the angular-z component.

Returns
A copy of the angular z-component

Definition at line 138 of file MotionVector.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