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
-
|
| | SpatialMomentum () |
| | Default constructor.
|
| | 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 𝐥.
|
| 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 𝐥.
|
| void | ShiftInPlace (const Vector3< T > &offset) |
| | In-place shift of a SpatialMomentum from an about-point P to an about-point Q.
|
| SpatialMomentum< T > | Shift (const Vector3< T > &offset) const |
| | Shifts a SpatialMomentum from an about-point P to an about-point Q.
|
| T | dot (const SpatialVelocity< T > &velocity) const |
| | Calculates twice (2x) a body B's kinetic energy measured in a frame M.
|
| | SpatialMomentum (const SpatialMomentum &)=default |
| SpatialMomentum & | operator= (const SpatialMomentum &)=default |
| | SpatialMomentum (SpatialMomentum &&)=default |
| SpatialMomentum & | operator= (SpatialMomentum &&)=default |
| Public Member Functions inherited from SpatialVector< SpatialMomentum, T > |
| 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.
|
| const T & | operator[] (int i) const |
| | Const access to the i-th element of this spatial vector.
|
| const Vector3< T > & | rotational () const |
| | Const access to the rotational component of this spatial vector.
|
| const Vector3< T > & | translational () const |
| | Const access to the translational component of this spatial vector.
|
| const T * | data () const |
| | Returns a (const) bare pointer to the underlying data.
|
| T * | mutable_data () |
| | Returns a (mutable) bare pointer to the underlying data.
|
| 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).
|
| 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.
|
| 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.
|
| void | SetNaN () |
| | Sets all the elements in this SpatialVector to NaN.
|
| SpatialQuantity & | SetZero () |
| | Sets both the rotational and translational components of this SpatialVector to zero.
|
| CoeffsEigenType & | get_coeffs () |
| | Returns a mutable reference to the underlying storage.
|
| SpatialQuantity | operator- () const |
| | Unary minus operator.
|
| SpatialQuantity & | operator+= (const SpatialQuantity &V) |
| | Addition assignment operator.
|
| SpatialQuantity & | operator-= (const SpatialQuantity &V) |
| | Subtraction assignment operator.
|
| SpatialQuantity & | operator*= (const T &s) |
| | Multiplication assignment operator.
|
| | SpatialVector (const SpatialVector &)=default |
| SpatialVector & | operator= (const SpatialVector &)=default |