template<typename T>
class drake::multibody::RotationalInertia< T >
This class describes the mass distribution (inertia properties) of a body or composite body about a particular point.
Herein, "composite body" means one body or a collection of bodies that are welded together. In this documentation, "body" and "composite body" are used interchangeably.
A rigid body's mass distribution is described by three quantities: the body's mass; the body's center of mass; and the body's rotational inertia about a particular point. The term rotational inertia is used here and by [Jain 2010] to distinguish from a body's spatial inertia. In this class, a 3x3 inertia matrix I represents a body's rotational inertia about a point and expressed in a frame. More specifically, I_BP_E is the inertia matrix of a body B about-point P and expressed-in frame E (herein frame E's orthogonal unit vectors Ex, Ey, Ez are denoted ๐ฑฬ, ๐ฒฬ, ๐ณฬ).
| Ixx Ixy Ixz |
I = | Ixy Iyy Iyz |
| Ixz Iyz Izz |
The moments of inertia Ixx, Iyy, Izz and products of inertia Ixy, Ixz, Iyz are defined in terms of the mass dm of a differential volume of the body. The position of dm from about-point P is xxฬ + yyฬ + zzฬ = [x, y, z]_E.
Ixx = โซ (yยฒ + zยฒ) dm
Iyy = โซ (xยฒ + zยฒ) dm
Izz = โซ (xยฒ + yยฒ) dm
Ixy = - โซ x y dm
Ixz = - โซ x z dm
Iyz = - โซ y z dm
We use the negated convention for products of inertia, so that I serves to relate angular velocity ฯ and angular momentum h via h = I โ
ฯ. Ensure your products of inertia follow this negative sign convention.
The 3x3 inertia matrix is symmetric and its diagonal elements (moments of inertia) and off-diagonal elements (products of inertia) are associated with a body (or composite body) S, an about-point P, and an expressed-in frame E (๐ฑฬ, ๐ฒฬ, ๐ณฬฬ). A rotational inertia is ill-defined unless there is a body S, about-point P, and expressed-in frame E. The user of this class is responsible for tracking the body S, about-point P and expressed-in frame E (none of these are stored in this class).
- Note
- This class does not store the about-point nor the expressed-in frame, nor does this class help enforce consistency of the about-point or expressed-in frame. To help users of this class track the about-point and expressed-in frame, we strongly recommend the following notation.
-
In typeset material, use the symbol \( [I^{S/P}]_E \) to represent the rotational inertia (inertia matrix) of a body (or composite body) S about-point P, expressed in frame E. In code and comments, use the monogram notation I_SP_E (e.g., as described in Spatial Mass Matrix (Spatial Inertia)). If the about-point P is fixed to a body B, the point is named \( B_P \) and this appears in code/comments as Bp. Examples: I_BBp_E is rigid body B's rotational inertia about-point Bp expressed-in frame E; I_BBo_E is B's rotational inertia about-point Bo (body B's origin) expressed-in frame E; and I_BBcm_E is B's inertia matrix about-point Bcm (B's center of mass) expressed-in frame E.
-
The rotational inertia (inertia matrix) can be re-expressed in terms of a special frame whose orthogonal unit vectors are parallel to principal axes of inertia so that the inertia matrix is diagonalized with elements called principal moments of inertia.
-
The formal definition of the inertia matrix \( I^{S/P} \) of a system S about a point P follows the definition of the inertia dyadic ๐ of S about P, which begins by modeling S with n particles Sโ ... Sโ (e.g., 12 grams of carbon can be modeled with n = 6.02 * 10ยฒยณ molecules/particles). The inertia dyadic ๐โ of one particle Sโ about point P is defined [Kane, 1985] in terms of mโ (mass of Sโ), แดพ๐ฉหขยน (position vector from P to Sโ), and the unit dyadic ๐ which is defined by the property ๐ โ
๐ฏ = ๐ฏ where ๐ฏ is is any vector (this definition of ๐ is analogous to defining the identity matrix by the property ๐ฐ๐
๐๐๐๐๐๐๐ด๐๐๐๐๐ * ๐๐๐๐ด๐๐๐๐๐ = ๐๐๐๐ด๐๐๐๐๐).
๐โ = mโ * [๐ * (แดพ๐ฉหขยน โ
แดพ๐ฉหขยน) - แดพ๐ฉหขยน * แดพ๐ฉหขยน]
Note: The vector dot-product (โ
) above produces a scalar whereas the vector multiply (*) produces a dyadic which is a 2nd-order tensor (แดพ๐ฉหขยน * แดพ๐ฉหขยน is similar to the matrix outer-product of a 3x1 matrix multiplied by a 1x3 matrix). An example inertia dyadic for a single particle is shown further below. The inertia dyadic ๐ of the entire system S is defined by summing the inertia dyadic of each particle Sแตข about P (i = 1, ... n), i.e.,
๐ = ๐โ + ๐โ + ... ๐โ
The elements of the inertia matrix \( [I^{S/P}]_E \) expressed in frame E (in terms of orthogonal unit vectors ๐ฑฬ, ๐ฒฬ, ๐ณฬฬ) are found by pre-dot multiplying and post-dot multiplying ๐ with appropriate unit vectors.
Ixx = ๐ฑฬ โ
๐ โ
๐ฑฬ Ixy = ๐ฑฬ โ
๐ โ
๐ฒฬ Ixz = ๐ฑฬ โ
๐ โ
๐ณฬฬ
Iyx = ๐ฒฬ โ
๐ โ
๐ฑฬ Iyy = ๐ฒฬ โ
๐ โ
๐ฒฬ Iyz = ๐ฒฬ โ
๐ โ
๐ณฬฬ
Izx = ๐ณฬฬ โ
๐ โ
๐ฑฬ Izy = ๐ณฬฬ โ
๐ โ
๐ฒฬ Izz = ๐ณฬฬ โ
๐ โ
๐ณฬฬ
The inertia dyadic ๐แดฎ of a rigid body B about Bcm (B's center of mass) is related to various dynamic quantities. For example, B's angular momentum ๐ about Bcm in a frame N and B's kinetic energy KE in N relate to ๐แดฎ by
๐ = ๐แดฎ โ
๐
KE = 1/2 ๐ โ
๐แดฎ โ
๐ + 1/2 mแดฎ ๐ฏ โ
๐ฏ
where ๐ is B's angular velocity in N, ๐ฏ is Bcm's translational velocity in N, and mแดฎ is B's mass. When frame N happens to be a Newtonian frame (also called an inertial frame or non-rotating/non-accelerating frame), the moment ๐ of all forces on B about Bcm relates to ๐แดฎ and ๐ (B's angular acceleration in N) by Euler's rigid body equation as
๐ = ๐แดฎ โ
๐ + ๐ ร ๐แดฎ โ
๐
Example: For a particle Q of mass m whose position vector from a point O is written in terms of right-handed orthogonal unit vectors ๐ฑฬ, ๐ฒฬ, ๐ณฬ (below), the inertia dyadic ๐ of particle Q about point O is defined and calculated
๐ฉ = x ๐ฑฬ + y ๐ฒฬ (given)
๐ = m * [๐ * (๐ฉ โ
๐ฉ) - ๐ฉ * ๐ฉ] (definition)
= m * [๐ * (xยฒ + yยฒ) - (x๐ฑฬ + y๐ฒฬฬ) * (x๐ฑฬ + y๐ฒฬ)
= m * [(๐ฑฬ๐ฑฬ + ๐ฒฬ๐ฒฬ + ๐ณฬ๐ณฬ) * (xยฒ + yยฒ) - (xยฒ๐ฑฬ๐ฑฬ + xy๐ฑฬ๐ฒฬฬ + xy๐ฒฬฬ๐ฑฬ + yยฒ๐ฒฬฬ๐ฒฬฬ)]
= m * [yยฒ๐ฑฬ๐ฑฬ + xยฒ๐ฒฬ๐ฒฬ + (xยฒ + yยฒ)๐ณฬ๐ณฬ - xy๐ฑฬ๐ฒฬฬ - xy๐ฒฬฬ๐ฑฬ]
which means the inertia matrix for particle Q about point O for ๐ฑฬ, ๐ฒฬ, ๐ณฬ is
| m yยฒ -m x y 0 |
I = | -m x y m xยฒ 0 |
| 0 0 m (xยฒ + yยฒ) |
[Kane, 1985] pg. 68. "Dynamics: Theory and Applications," McGraw-Hill Co., New York, 1985 (with D. A. Levinson). Available for free .pdf download: https://ecommons.cornell.edu/handle/1813/637
-
Several methods in this class throw a std::exception for invalid rotational inertia operations in debug releases only. This provides speed in a release build while facilitating debugging in debug builds. In addition, these validity tests are only performed for scalar types for which drake::scalar_predicate<T>::is_bool is true. For instance, validity checks are not performed when T is symbolic::Expression.
-
The methods of this class satisfy the "basic exception guarantee": if an exception is thrown, the program will still be in a valid state. Specifically, no resources are leaked, and all objects' invariants are intact. Be aware that RotationalInertia objects may contain invalid inertia data in cases where input checking is skipped.
- See also
- https://en.cppreference.com/w/cpp/language/exceptions
Various methods in this class require numerical (not symbolic) data types.
- Template Parameters
-
|
| | RotationalInertia () |
| | Constructs a rotational inertia that has all its moments/products of inertia equal to NaN (helps quickly detect uninitialized values).
|
| | RotationalInertia (const T &Ixx, const T &Iyy, const T &Izz) |
| | Creates a rotational inertia with moments of inertia Ixx, Iyy, Izz, and with each product of inertia set to zero.
|
| | RotationalInertia (const T &Ixx, const T &Iyy, const T &Izz, const T &Ixy, const T &Ixz, const T &Iyz) |
| | Creates a rotational inertia with moments of inertia Ixx, Iyy, Izz, and with products of inertia Ixy, Ixz, Iyz.
|
| | RotationalInertia (const T &mass, const Vector3< T > &p_PQ_E) |
| | Constructs a rotational inertia for a particle Q of mass mass, whose position vector from about-point P is p_PQ_E (E is expressed-in frame).
|
| int | rows () const |
| | For consistency with Eigen's API, the rows() method returns 3.
|
| int | cols () const |
| | For consistency with Eigen's API, the cols() method returns 3.
|
| Vector3< T > | get_moments () const |
| | Returns 3-element vector with moments of inertia [Ixx, Iyy, Izz].
|
| Vector3< T > | get_products () const |
| | Returns 3-element vector with products of inertia [Ixy, Ixz, Iyz].
|
| T | Trace () const |
| | Returns a rotational inertia's trace (i.e., Ixx + Iyy + Izz, the sum of the diagonal elements of the inertia matrix).
|
| T | CalcMaximumPossibleMomentOfInertia () const |
| | Returns the maximum possible moment of inertia for this rotational inertia about-point P for any expressed-in frame E.
|
| const T & | operator() (int i, int j) const |
| | Const access to the (i, j) element of this rotational inertia.
|
| Matrix3< T > | CopyToFullMatrix3 () const |
| | Gets a full 3x3 matrix copy of this rotational inertia.
|
| boolean< T > | IsNearlyEqualTo (const RotationalInertia &other, double precision) const |
| | Compares this rotational inertia to other rotational inertia within the specified precision (which is a dimensionless number specifying the relative precision to which the comparison is performed).
|
| RotationalInertia< T > & | operator+= (const RotationalInertia< T > &I_BP_E) |
| | Adds a rotational inertia I_BP_E to this rotational inertia.
|
| RotationalInertia< T > | operator+ (const RotationalInertia< T > &I_BP_E) const |
| | Adds a rotational inertia I_BP_E to this rotational inertia.
|
| RotationalInertia< T > & | operator-= (const RotationalInertia< T > &I_BP_E) |
| | Subtracts a rotational inertia I_BP_E from this rotational inertia.
|
| RotationalInertia< T > | operator- (const RotationalInertia< T > &I_BP_E) const |
| | Subtracts a rotational inertia I_BP_E from this rotational inertia.
|
| RotationalInertia< T > & | operator*= (const T &nonnegative_scalar) |
| | Multiplies this rotational inertia by a nonnegative scalar (>= 0).
|
| RotationalInertia< T > | operator* (const T &nonnegative_scalar) const |
| | Multiplies this rotational inertia by a nonnegative scalar (>= 0).
|
| Vector3< T > | operator* (const Vector3< T > &w_E) const |
| | Multiplies this rotational inertia about-point P, expressed-in frame E by the vector w_E (which must also have the same expressed-in frame E).
|
| RotationalInertia< T > & | operator/= (const T &positive_scalar) |
| | Divides this rotational inertia by a positive scalar (> 0).
|
| RotationalInertia< T > | operator/ (const T &positive_scalar) const |
| | Divides this rotational inertia by a positive scalar(> 0).
|
| RotationalInertia< T > | MultiplyByScalarSkipValidityCheck (const T &s) const |
| | (Internal use only) Multiplies a rotational inertia by a scalar.
|
| void | SetToNaN () |
| | Sets this rotational inertia so all its elements are equal to NaN.
|
| void | SetZero () |
| | Sets this rotational inertia so all its moments/products of inertia are zero, e.g., for convenient initialization before a computation or for inertia calculations involving a particle (point-mass).
|
| boolean< T > | IsFinite () const |
| | Returns true if all moments and products in this rotational inertia are finite (e.g., no NaNs or infinities), otherwise returns false.
|
| boolean< T > | IsNaN () const |
| | Returns true if any moment/product in this rotational inertia is NaN.
|
| boolean< T > | IsZero () const |
| | Returns true if all moments and products of inertia are exactly zero.
|
| template<typename Scalar> |
| RotationalInertia< Scalar > | cast () const |
| | Returns a new RotationalInertia object templated on Scalar initialized from the values of this rotational inertia's entries.
|
| Vector3< double > | CalcPrincipalMomentsOfInertia () const |
| | Forms the 3 principal moments of inertia for this rotational inertia.
|
| std::pair< Vector3< double >, math::RotationMatrix< double > > | CalcPrincipalMomentsAndAxesOfInertia () const |
| | Forms the 3 principal moments of inertia and their 3 associated principal directions for this rotational inertia.
|
| boolean< T > | CouldBePhysicallyValid () const |
| | Performs several checks to verify whether this rotational inertia could be physically valid, including:
|
| void | ReExpressInPlace (const math::RotationMatrix< T > &R_AE) |
| | Re-expresses this rotational inertia I_BP_E in place to I_BP_A.
|
| RotationalInertia< T > | ReExpress (const math::RotationMatrix< T > &R_AE) const |
| | Re-expresses this rotational inertia I_BP_E to I_BP_A i.e., re-expresses body B's rotational inertia from frame E to frame A.
|
| | RotationalInertia (const RotationalInertia &)=default |
| RotationalInertia & | operator= (const RotationalInertia &)=default |
| | RotationalInertia (RotationalInertia &&)=default |
| RotationalInertia & | operator= (RotationalInertia &&)=default |
Each shift method shifts a body's rotational inertia from one about-point to another about-point.
The expressed-in frame is unchanged.
| In-place methods (this changes) | Const methods |
| ShiftFromCenterOfMassInPlace | ShiftFromCenterOfMass |
| ShiftToCenterOfMassInPlace | ShiftToCenterOfMass |
| ShiftToThenAwayFromCenterOfMassInPlace | ShiftToThenAwayFromCenterOfMass |
|
| void | ShiftFromCenterOfMassInPlace (const T &mass, const Vector3< T > &p_BcmQ_E) |
| | Shifts this rotational inertia for a body (or composite body) B from about-point Bcm (B's center of mass) to about-point Q.
|
| RotationalInertia< T > | ShiftFromCenterOfMass (const T &mass, const Vector3< T > &p_BcmQ_E) const |
| | Calculates the rotational inertia that results from shifting this rotational inertia for a body (or composite body) B from about-point Bcm (B's center of mass) to about-point Q.
|
| void | ShiftToCenterOfMassInPlace (const T &mass, const Vector3< T > &p_QBcm_E) |
| | Shifts this rotational inertia for a body (or composite body) B from about-point Q to about-point Bcm (B's center of mass).
|
| RotationalInertia< T > | ShiftToCenterOfMass (const T &mass, const Vector3< T > &p_QBcm_E) const |
| | Calculates the rotational inertia that results from shifting this rotational inertia for a body (or composite body) B from about-point Q to about-point Bcm (B's center of mass).
|
| void | ShiftToThenAwayFromCenterOfMassInPlace (const T &mass, const Vector3< T > &p_PBcm_E, const Vector3< T > &p_QBcm_E) |
| | Shifts this rotational inertia for a body (or composite body) B from about-point P to about-point Q via Bcm (B's center of mass).
|
| RotationalInertia< T > | ShiftToThenAwayFromCenterOfMass (const T &mass, const Vector3< T > &p_PBcm_E, const Vector3< T > &p_QBcm_E) const |
| | Calculates the rotational inertia that results from shifting this rotational inertia for a body (or composite body) B from about-point P to about-point Q via Bcm (B's center of mass).
|