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

Momentum is mass/inertia multiplied by velocity. More...

#include <Momentum.hpp>

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

Public Member Functions

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)
 

Protected Member Functions

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
 

Detailed Description

Momentum is mass/inertia multiplied by velocity.

Definition at line 27 of file Momentum.hpp.

Constructor & Destructor Documentation

RobotDynamics::Math::Momentum::Momentum ( )
inline

Definition at line 30 of file Momentum.hpp.

RobotDynamics::Math::Momentum::Momentum ( const double  kx,
const double  ky,
const double  kz,
const double  lx,
const double  ly,
const double  lz 
)
inline

Definition at line 34 of file Momentum.hpp.

RobotDynamics::Math::Momentum::Momentum ( const Vector3d k,
const Vector3d  l 
)
inline

Definition at line 38 of file Momentum.hpp.

RobotDynamics::Math::Momentum::Momentum ( const Momentum momentum)
inline

Definition at line 42 of file Momentum.hpp.

RobotDynamics::Math::Momentum::Momentum ( const ForceVector forceVector)
inlineexplicit

Definition at line 46 of file Momentum.hpp.

RobotDynamics::Math::Momentum::Momentum ( const RigidBodyInertia inertia,
const MotionVector vector 
)
inline

Definition at line 50 of file Momentum.hpp.

Member Function Documentation

void RobotDynamics::Math::Momentum::computeMomentum ( const RigidBodyInertia I,
const MotionVector v 
)
inlineprotected

Computes momentum from inertia and velocity.

Parameters
I
v

Definition at line 181 of file Momentum.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::Momentum::kx ( )
inline

Definition at line 84 of file Momentum.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::Momentum::kx ( ) const
inline

Definition at line 99 of file Momentum.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::Momentum::ky ( )
inline

Definition at line 89 of file Momentum.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::Momentum::ky ( ) const
inline

Definition at line 104 of file Momentum.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::Momentum::kz ( )
inline

Definition at line 94 of file Momentum.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::Momentum::kz ( ) const
inline

Definition at line 109 of file Momentum.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::Momentum::lx ( )
inline

Definition at line 114 of file Momentum.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::Momentum::lx ( ) const
inline

Definition at line 129 of file Momentum.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::Momentum::ly ( )
inline

Definition at line 119 of file Momentum.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::Momentum::ly ( ) const
inline

Definition at line 134 of file Momentum.hpp.

EIGEN_STRONG_INLINE double& RobotDynamics::Math::Momentum::lz ( )
inline

Definition at line 124 of file Momentum.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::Momentum::lz ( ) const
inline

Definition at line 139 of file Momentum.hpp.

EIGEN_STRONG_INLINE double RobotDynamics::Math::Momentum::operator* ( const MotionVector vector)
inline

Operator for computing kinetic energy. With momentum, $ m $ and Math::MotionVector, $ v $ this performs performs $ \frac{m\cdot v}{2} $.

Parameters
vector
Returns
kinetic energy

Definition at line 170 of file Momentum.hpp.

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

Overloaded plus-equals operator.

Returns
$ f_2=f_2+f_1 $

Definition at line 148 of file Momentum.hpp.

Momentum RobotDynamics::Math::Momentum::operator-= ( const Momentum v)
inline

Overloaded plus-equals operator.

Returns
$ f_2=f_2-f_1 $

Definition at line 158 of file Momentum.hpp.

void RobotDynamics::Math::Momentum::set ( const RigidBodyInertia inertia,
const MotionVector vector 
)
inline

Set momentum by computing it from the inertia and velocity.

Parameters
inertia
vector

Definition at line 79 of file Momentum.hpp.

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

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 \]

.

Parameters
X
Returns
Copied, transformed ForceVector

Definition at line 67 of file Momentum.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