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

A SpatialMomentum is a Momentum expressed in a RobotDynamics::ReferenceFrame. The angular portion of the vector is referred to as $k$ and the linear portion as $l$. More...

#include <SpatialMomentum.hpp>

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

Public Member Functions

double operator* (const SpatialMotion &vector)
 Operator that returns the kinetic energy. Given a momentum, $m$ and motion vector $v$, the resulting kinetic energy is computed by $ E_k = 0.5 m \cdot v $. Frame checks will be performed. More...
 
void set (const SpatialInertia &inertia, const SpatialMotion &vector)
 Set a momentums value by computing a momentum from the supplied SpatialInertia and SpatialMotion. Frame checks will be performed. More...
 
void setIncludingFrame (ReferenceFramePtr referenceFrame, const RigidBodyInertia &inertia, const MotionVector &vector)
 Set a momentum by multiplying the supplied motion vector by the supplied inertia. Set the stored RobotDynamics::FrameObject::referenceFrame to the supplied ReferenceFrame pointer. No frame checks will be performed. More...
 
void setIncludingFrame (ReferenceFramePtr referenceFrame, const ForceVector &f)
 Constructor. More...
 
 SpatialMomentum ()
 Constructor. RobotDynamics::ReferenceFrame is initialized to nullptr. More...
 
 SpatialMomentum (ReferenceFramePtr referenceFrame, const double kx, const double ky, const double kz, const double lx, const double ly, const double lz)
 Costructor. More...
 
 SpatialMomentum (ReferenceFramePtr referenceFrame, const Vector3d &k, const Vector3d l)
 Constructor. More...
 
 SpatialMomentum (const SpatialMomentum &SpatialMomentum)
 Copy constructor. More...
 
 SpatialMomentum (ReferenceFramePtr referenceFrame, const ForceVector &forceVector)
 Constructor. More...
 
 SpatialMomentum (ReferenceFramePtr referenceFrame)
 Constructor. More...
 
 SpatialMomentum (const SpatialInertia &inertia, const SpatialMotion &vector)
 Constructor. Momentum is computed from SpatialInertia and SpatialMotion by $ p=I*m $. Frame checks are performed. More...
 
- Public Member Functions inherited from RobotDynamics::Math::Momentum
EIGEN_STRONG_INLINE double & kx ()
 
EIGEN_STRONG_INLINE double kx () const
 
EIGEN_STRONG_INLINE double & ky ()
 
EIGEN_STRONG_INLINE double ky () const
 
EIGEN_STRONG_INLINE double & kz ()
 
EIGEN_STRONG_INLINE double kz () const
 
EIGEN_STRONG_INLINE double & lx ()
 
EIGEN_STRONG_INLINE double lx () const
 
EIGEN_STRONG_INLINE double & ly ()
 
EIGEN_STRONG_INLINE double ly () const
 
EIGEN_STRONG_INLINE double & lz ()
 
EIGEN_STRONG_INLINE double lz () const
 
 Momentum ()
 
 Momentum (const double kx, const double ky, const double kz, const double lx, const double ly, const double lz)
 
 Momentum (const Vector3d &k, const Vector3d l)
 
 Momentum (const Momentum &momentum)
 
 Momentum (const ForceVector &forceVector)
 
 Momentum (const RigidBodyInertia &inertia, const MotionVector &vector)
 
EIGEN_STRONG_INLINE double operator* (const MotionVector &vector)
 Operator for computing kinetic energy. With momentum, $ m $ and Math::MotionVector, $ v $ this performs performs $ \frac{m\cdot v}{2} $. More...
 
Momentum operator+= (const Momentum &v)
 Overloaded plus-equals operator. More...
 
Momentum operator-= (const Momentum &v)
 Overloaded plus-equals operator. More...
 
void set (const RigidBodyInertia &inertia, const MotionVector &vector)
 Set momentum by computing it from the inertia and velocity. More...
 
Momentum transform_copy (const SpatialTransform &X) const
 Copy then transform a ForceVector by

\[ f_2 = \begin{bmatrix} X.E & -X.E(X.r\times) \\ \mathbf{0} & X.E \end{bmatrix} f_1 \]

. More...

 
- Public Member Functions inherited from RobotDynamics::Math::ForceVector
template<typename OtherDerived >
 ForceVector (const Eigen::MatrixBase< OtherDerived > &other)
 Constructor. More...
 
EIGEN_STRONG_INLINE ForceVector ()
 Empty constructor. More...
 
 ForceVector (const double mx, const double my, const double mz, const double fx, const double fy, const double fz)
 Constructor. More...
 
EIGEN_STRONG_INLINE double & fx ()
 Get reference to x-linear component. More...
 
EIGEN_STRONG_INLINE double fx () const
 Get copy of x-linear component. More...
 
EIGEN_STRONG_INLINE double & fy ()
 Get reference to y-linear component. More...
 
EIGEN_STRONG_INLINE double fy () const
 Get copy of y-linear component. More...
 
EIGEN_STRONG_INLINE double & fz ()
 Get reference to z-linear component. More...
 
EIGEN_STRONG_INLINE double fz () const
 Get copy of z-linear component. More...
 
EIGEN_STRONG_INLINE double & mx ()
 Get reference to x-angular component. More...
 
EIGEN_STRONG_INLINE double mx () const
 Get copy of x-angular component. More...
 
EIGEN_STRONG_INLINE double & my ()
 Get reference to y-angular component. More...
 
EIGEN_STRONG_INLINE double my () const
 Get copy of y-angular component. More...
 
EIGEN_STRONG_INLINE double & mz ()
 Get reference to z-angular component. More...
 
EIGEN_STRONG_INLINE double mz () const
 Get copy of z-angular component. More...
 
ForceVector operator+= (const ForceVector &v)
 Overloaded plus-equals operator. More...
 
template<typename OtherDerived >
ForceVectoroperator= (const Eigen::MatrixBase< OtherDerived > &other)
 
EIGEN_STRONG_INLINE void set (const ForceVector &f)
 Setter. More...
 
EIGEN_STRONG_INLINE SpatialVector toSpatialVector () const
 Get a copy of a ForceVector as type SpatialVector. More...
 
void transform (const SpatialTransform &X)
 Performs the following in place transform

\[ f = \begin{bmatrix} X.E & -X.E(X.r\times) \\ \mathbf{0} & X.E \end{bmatrix} f \]

. More...

 
ForceVector transform_copy (const SpatialTransform &X) const
 Copy then transform a ForceVector by

\[ f_2 = \begin{bmatrix} X.E & -X.E(X.r\times) \\ \mathbf{0} & X.E \end{bmatrix} f_1 \]

. 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 Member Functions

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...
 
- Protected Member Functions inherited from RobotDynamics::Math::Momentum
void computeMomentum (const RigidBodyInertia &I, const MotionVector &v)
 Computes momentum from inertia and velocity. More...
 

Additional Inherited Members

- Public Types inherited from RobotDynamics::Math::SpatialVector
typedef Eigen::Matrix< double, 6, 1 > Base
 
- Protected Attributes inherited from RobotDynamics::FrameObject
ReferenceFramePtr referenceFrame
 

Detailed Description

A SpatialMomentum is a Momentum expressed in a RobotDynamics::ReferenceFrame. The angular portion of the vector is referred to as $k$ and the linear portion as $l$.

Definition at line 32 of file SpatialMomentum.hpp.

Constructor & Destructor Documentation

RobotDynamics::Math::SpatialMomentum::SpatialMomentum ( )
inline

Constructor. RobotDynamics::ReferenceFrame is initialized to nullptr.

Definition at line 38 of file SpatialMomentum.hpp.

RobotDynamics::Math::SpatialMomentum::SpatialMomentum ( ReferenceFramePtr  referenceFrame,
const double  kx,
const double  ky,
const double  kz,
const double  lx,
const double  ly,
const double  lz 
)
inline

Costructor.

Parameters
referenceFrameRobotDynamics::ReferenceFrame the momentum is expressed in
kxx-Angular
kyy-Angular
kzz-Angular
lxx-Linear
lyy-Linear
lzz-Linear

Definition at line 52 of file SpatialMomentum.hpp.

RobotDynamics::Math::SpatialMomentum::SpatialMomentum ( ReferenceFramePtr  referenceFrame,
const Vector3d k,
const Vector3d  l 
)
inline

Constructor.

Parameters
referenceFrameRobotDynamics::ReferenceFrame the momentum is expressed in
kAngular part
lLinear part

Definition at line 63 of file SpatialMomentum.hpp.

RobotDynamics::Math::SpatialMomentum::SpatialMomentum ( const SpatialMomentum SpatialMomentum)
inline

Copy constructor.

Parameters
SpatialMomentum

Definition at line 72 of file SpatialMomentum.hpp.

RobotDynamics::Math::SpatialMomentum::SpatialMomentum ( ReferenceFramePtr  referenceFrame,
const ForceVector forceVector 
)
inline

Constructor.

Parameters
referenceFrameRobotDynamics::ReferenceFrame the momentum is expressed in
forceVector

Definition at line 81 of file SpatialMomentum.hpp.

RobotDynamics::Math::SpatialMomentum::SpatialMomentum ( ReferenceFramePtr  referenceFrame)
inlineexplicit

Constructor.

Parameters
referenceFrameRobotDynamics::ReferenceFrame the momentum is expressed in

Definition at line 89 of file SpatialMomentum.hpp.

RobotDynamics::Math::SpatialMomentum::SpatialMomentum ( const SpatialInertia inertia,
const SpatialMotion vector 
)
inline

Constructor. Momentum is computed from SpatialInertia and SpatialMotion by $ p=I*m $. Frame checks are performed.

Parameters
inertia
vector

Definition at line 99 of file SpatialMomentum.hpp.

Member Function Documentation

TransformableGeometricObject* RobotDynamics::Math::SpatialMomentum::getTransformableGeometricObject ( )
inlineprotectedvirtual

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 154 of file SpatialMomentum.hpp.

double RobotDynamics::Math::SpatialMomentum::operator* ( const SpatialMotion vector)
inline

Operator that returns the kinetic energy. Given a momentum, $m$ and motion vector $v$, the resulting kinetic energy is computed by $ E_k = 0.5 m \cdot v $. Frame checks will be performed.

Returns
double The kinetic energy

Definition at line 147 of file SpatialMomentum.hpp.

void RobotDynamics::Math::SpatialMomentum::set ( const SpatialInertia inertia,
const SpatialMotion vector 
)
inline

Set a momentums value by computing a momentum from the supplied SpatialInertia and SpatialMotion. Frame checks will be performed.

Parameters
inertia
vector

Definition at line 110 of file SpatialMomentum.hpp.

void RobotDynamics::Math::SpatialMomentum::setIncludingFrame ( ReferenceFramePtr  referenceFrame,
const RigidBodyInertia inertia,
const MotionVector vector 
)
inline

Set a momentum by multiplying the supplied motion vector by the supplied inertia. Set the stored RobotDynamics::FrameObject::referenceFrame to the supplied ReferenceFrame pointer. No frame checks will be performed.

Parameters
referenceFrame
inertia
vector

Definition at line 125 of file SpatialMomentum.hpp.

void RobotDynamics::Math::SpatialMomentum::setIncludingFrame ( ReferenceFramePtr  referenceFrame,
const ForceVector f 
)
inline

Constructor.

Parameters
referenceFrame
f

Definition at line 136 of file SpatialMomentum.hpp.


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


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