Drake
Drake C++ Documentation
SpatialMomentum< T > Class Template Reference

Detailed Description

template<typename T>
class drake::multibody::SpatialMomentum< T >

This class represents a spatial momentum L and has 6 elements with an angular (rotational) momentum 𝐡 (3-element vector) on top of a translational (linear) momentum 𝐥 (3-element vector).

A spatial momentum L stores the angular momentum 𝐡 and translational momentum 𝐥 of a system S about a point P, measured in a frame M, and expressed in a frame E. The system S may be a particle, a rigid or deformable body, or a set of particles and/or bodies. This class assumes that both the angular momentum 𝐡 and translational momentum 𝐥 are expressed in the same expressed-in frame E. This class only stores 6 elements (namely 𝐡 and 𝐥) and does not store the underlying system S, about-point P, measured-in frame M, or expressed-in frame E. The user is responsible for explicitly tracking the underlying system, about-point, and frames with monogram notation. For example, L_MSP_E denotes a system S's spatial momentum about point P, measured in frame M, and expressed in frame E. L_MSP_E contains h_MSP_E (S's angular momentum about point P, measured in M, expressed in E) and l_MS_E (S's translational momentum measured in M, expressed in E). A body B's spatial momentum about point Bo (B's origin), measured in frame M, expressed in frame E has explicit monogram notation L_MBBo_E which can be abbreviated L_MBo_E. Similarly L_MSScm_E is abbreviated L_MScm_E (Scm is S's center of mass). Details on spatial vectors and monogram notation are in sections Spatial Vectors and Multibody Quantities.

The typeset for L_MSP_E is \([^ML^{S/P}]_E\). For a set S of particles Qᵢ, L_MSP contains S's angular momentum 𝐡 about-point P, measured in frame M and S's translational momentum 𝐥 measured in frame M, defined as

  h_MSP = ∑ h_MQᵢP = ∑ p_PQᵢ x l_MQᵢ  where l_MQᵢ = mᵢ v_MQᵢ.
  l_MS  = ∑ l_MQᵢ  = ∑ mᵢ v_MQᵢ

where mᵢ is the mass of particle Qᵢ, v_MQᵢ is Qᵢ's translational velocity measured in frame M, l_MQᵢ = mᵢ v_MQQᵢ is Qᵢ's translational momentum measured in frame M, h_MQᵢP is Qᵢ's angular momentum about point P measured in frame M, and p_PQᵢ is the position vector from point P to Qᵢ. These definitions extend to a body (continuum of particles) by using the density ρ(r) of the body at each material location r as:

  h_MSP = ∫p_PQ(r) x v_MQ(r) ρ(r) d³r
  l_MS  = ∫v_MQ(r) ρ(r) d³r
Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/math/spatial_momentum.h>

Public Member Functions

 SpatialMomentum ()
 Default constructor. More...
 
 SpatialMomentum (const Eigen::Ref< const Vector3< T >> &h, const Eigen::Ref< const Vector3< T >> &l)
 Constructs a spatial momentum L from an angular momentum 𝐡 and a translational momentum 𝐥. More...
 
template<typename Derived >
 SpatialMomentum (const Eigen::MatrixBase< Derived > &L)
 Constructs a spatial momentum L from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular momentum 𝐡 and a 3-element translational momentum 𝐥. More...
 
void ShiftInPlace (const Vector3< T > &offset)
 In-place shift of a SpatialMomentum from an about-point P to an about-point Q. More...
 
SpatialMomentum< T > Shift (const Vector3< T > &offset) const
 Shifts a SpatialMomentum from an about-point P to an about-point Q. More...
 
dot (const SpatialVelocity< T > &velocity) const
 Calculates twice (2x) a body B's kinetic energy measured in a frame M. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 SpatialMomentum (const SpatialMomentum &)=default
 
SpatialMomentumoperator= (const SpatialMomentum &)=default
 
 SpatialMomentum (SpatialMomentum &&)=default
 
SpatialMomentumoperator= (SpatialMomentum &&)=default
 
- Public Member Functions inherited from SpatialVector< SpatialMomentum, T >
 SpatialVector ()
 Default constructor. More...
 
 SpatialVector (const Eigen::Ref< const Vector3< T >> &w, const Eigen::Ref< const Vector3< T >> &v)
 Constructs a spatial vector from a rotational component w and a translational component v. More...
 
 SpatialVector (const Eigen::MatrixBase< OtherDerived > &V)
 Constructs a spatial vector V from an Eigen expression that represents a 6-element vector (3-element rotational vector on top of a 3-element translational vector). More...
 
int size () const
 For 3D (three-dimensional) analysis, the total size of the concatenated rotational vector (3 elements) and translational vector (3 elements) is six (6), which is known at compile time. More...
 
const T & operator[] (int i) const
 Const access to the i-th element of this spatial vector. More...
 
T & operator[] (int i)
 Mutable access to the i-th element of this spatial vector. More...
 
const Vector3< T > & rotational () const
 Const access to the rotational component of this spatial vector. More...
 
Vector3< T > & rotational ()
 Mutable access to the rotational component of this spatial vector. More...
 
const Vector3< T > & translational () const
 Const access to the translational component of this spatial vector. More...
 
Vector3< T > & translational ()
 Mutable access to the translational component of this spatial vector. More...
 
const T * data () const
 Returns a (const) bare pointer to the underlying data. More...
 
T * mutable_data ()
 Returns a (mutable) bare pointer to the underlying data. More...
 
std::tuple< const T, const T > GetMaximumAbsoluteDifferences (const SpatialQuantity &other) const
 Returns the maximum absolute values of the differences in the rotational and translational components of this and other (i.e., the infinity norms of the difference in rotational and translational components). More...
 
decltype(T()< T()) IsNearlyEqualWithinAbsoluteTolerance (const SpatialQuantity &other, double rotational_tolerance, double translational_tolerance) const
 Compares the rotational and translational parts of this and other to check if they are the same to within specified absolute differences. More...
 
decltype(T()< T()) IsApprox (const SpatialQuantity &other, double tolerance=2 *std::numeric_limits< double >::epsilon()) const
 Determines whether all six corresponding elements of two spatial vectors are equal to each other to within a specified tolerance epsilon. More...
 
void SetNaN ()
 Sets all the elements in this SpatialVector to NaN. More...
 
SpatialQuantitySetZero ()
 Sets both the rotational and translational components of this SpatialVector to zero. More...
 
CoeffsEigenTypeget_coeffs ()
 Returns a mutable reference to the underlying storage. More...
 
const CoeffsEigenTypeget_coeffs () const
 Returns a constant reference to the underlying storage. More...
 
SpatialQuantity operator- () const
 Unary minus operator. More...
 
SpatialQuantityoperator+= (const SpatialQuantity &V)
 Addition assignment operator. More...
 
SpatialQuantityoperator-= (const SpatialQuantity &V)
 Subtraction assignment operator. More...
 
SpatialQuantityoperator *= (const T &s)
 Multiplication assignment operator. More...
 
 SpatialVector (const SpatialVector &)=default
 
 SpatialVector (SpatialVector &&)=default
 
SpatialVectoroperator= (const SpatialVector &)=default
 
SpatialVectoroperator= (SpatialVector &&)=default
 

Related Functions

(Note that these are not member functions.)

template<typename T >
SpatialMomentum< T > operator+ (const SpatialMomentum< T > &L1_E, const SpatialMomentum< T > &L2_E)
 Adds two spatial momenta by simply adding their 6 underlying elements. More...
 
template<typename T >
SpatialMomentum< T > operator- (const SpatialMomentum< T > &L1_E, const SpatialMomentum< T > &L2_E)
 Subtracts spatial momenta by simply subtracting their 6 underlying elements. More...
 

Additional Inherited Members

- Public Types inherited from SpatialVector< SpatialMomentum, T >
enum  
 Sizes for spatial quantities and its components in 3D (three dimensions). More...
 
using SpatialQuantity = SpatialMomentum< T >
 The more specialized spatial vector class templated on the scalar type T. More...
 
using CoeffsEigenType = Vector6< T >
 The type of the underlying in-memory representation using an Eigen vector. More...
 
- Static Public Member Functions inherited from SpatialVector< SpatialMomentum, T >
static SpatialQuantity Zero ()
 Factory to create a zero spatial vector, i.e., a SpatialVector whose rotational and translational components are both zero. More...
 

Constructor & Destructor Documentation

◆ SpatialMomentum() [1/5]

SpatialMomentum ( const SpatialMomentum< T > &  )
default

◆ SpatialMomentum() [2/5]

SpatialMomentum ( SpatialMomentum< T > &&  )
default

◆ SpatialMomentum() [3/5]

Default constructor.

In Release builds, all 6 elements of a newly constructed spatial momentum are uninitialized (for speed). In Debug builds, the 6 elements are set to NaN so that invalid operations on an uninitialized spatial momentum fail fast (fast bug detection).

◆ SpatialMomentum() [4/5]

SpatialMomentum ( const Eigen::Ref< const Vector3< T >> &  h,
const Eigen::Ref< const Vector3< T >> &  l 
)

Constructs a spatial momentum L from an angular momentum 𝐡 and a translational momentum 𝐥.

◆ SpatialMomentum() [5/5]

SpatialMomentum ( const Eigen::MatrixBase< Derived > &  L)
explicit

Constructs a spatial momentum L from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular momentum 𝐡 and a 3-element translational momentum 𝐥.

This constructor will assert the size of L is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

Member Function Documentation

◆ dot()

T dot ( const SpatialVelocity< T > &  velocity) const

Calculates twice (2x) a body B's kinetic energy measured in a frame M.

For any frame (e.g., an offset frame) Bp that is fixed to a rigid body B, calculates the dot-product of this = L_MBp_E (body B's spatial momentum measured in frame M, about Bp's origin, expressed in frame E) with V_MBp_E (frame Bp's spatial velocity measured in frame M, expressed in frame E).

Parameters
[in]velocitywhich is V_MBp_E, frame Bp's spatial velocity measured in frame M, and expressed in the same frame E as this = L_MBp_E.
Returns
2*K_MB, twice (2x) body B's kinetic energy measured in frame M.
Note
In general, kinetic energy calculations are only useful when frame M is a world frame (also called a Newtonian or inertial frame). Hence, it is unusual to use this method unless frame M is the world frame W.
Although the spatial vectors V_MBp_E and L_MBp_E must have the same expressed-in frame E, the resulting scalar K_MB is independent of frame E.
As shown below, K_MB can be calculated from any frame Bp fixed on B, including body B's center of mass frame Bcm. This is due to how spatial momentum and spatial velocity shift from Bcm to Bp. For more information, see SpatialMomentum::Shift() and SpatialVelocity::Shift().
  K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)

◆ operator=() [1/2]

SpatialMomentum& operator= ( SpatialMomentum< T > &&  )
default

◆ operator=() [2/2]

SpatialMomentum& operator= ( const SpatialMomentum< T > &  )
default

◆ Shift()

SpatialMomentum<T> Shift ( const Vector3< T > &  offset) const

Shifts a SpatialMomentum from an about-point P to an about-point Q.

Parameters
[in]offsetwhich is the position vector p_PQ_E from point P to point Q, expressed in frame E. p_PQ_E must have the same expressed-in frame E as this spatial momentum, where this is L_MSP_E (system S's spatial momentum about P, measured in frame M, expressed in frame E).
Return values
L_MSQ_Ewhich is system S's spatial momentum about point Q, measured in frame M, expressed in frame E.
Note
Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.
See also
ShiftInPlace() for more information and how L_MSQ_E is calculated.

◆ ShiftInPlace()

void ShiftInPlace ( const Vector3< T > &  offset)

In-place shift of a SpatialMomentum from an about-point P to an about-point Q.

On entry, this is L_MSP_E (system S's spatial momentum about point P, measured in a frame M and expressed in a frame E). On return this is modified to L_MSQ_E (S's spatial momentum about point Q, measured in frame M and expressed in frame E). The components of L_MSQ_E are:

  l_MS_E = l_MS_E         (translational momentum of `this` is unchanged).
 h_MSQ_E = h_MSP_E + p_QP_E x l_MS_E
         = h_MSP_E - p_PQ_E x l_MS_E
Parameters
[in]offsetwhich is the position vector p_PQ_E from point P to point Q, with the same expressed-in frame E as this spatial momentum.
Note
Spatial momenta shift similar to spatial force (see SpatialForce) and in a related/different way for spatial velocity (see SpatialVelocity).
See also
Shift() to shift spatial momentum without modifying this.

Friends And Related Function Documentation

◆ operator+()

SpatialMomentum< T > operator+ ( const SpatialMomentum< T > &  L1_E,
const SpatialMomentum< T > &  L2_E 
)
related

Adds two spatial momenta by simply adding their 6 underlying elements.

Parameters
[in]L1_Espatial momentum expressed in the same frame E as L2_E.
[in]L2_Espatial momentum expressed in the same frame E as L1_E.
Note
The general utility of this operator+() function seems limited to situations when L1 and L2 are associated with different systems (S1 and S2), but have the same about-point P, same measured-in frame M, and same expressed-in frame E.

◆ operator-()

SpatialMomentum< T > operator- ( const SpatialMomentum< T > &  L1_E,
const SpatialMomentum< T > &  L2_E 
)
related

Subtracts spatial momenta by simply subtracting their 6 underlying elements.

Parameters
[in]L1_Espatial momentum expressed in the same frame E as L2_E.
[in]L2_Espatial momentum expressed in the same frame E as L1_E.
Note
The general utility of this operator-() function is questionable and it should only be used if you are sure it makes sense.

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