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

Detailed Description

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
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/tree/rotational_inertia.h>

Public Member Functions

 RotationalInertia ()
 Constructs a rotational inertia that has all its moments/products of inertia equal to NaN (helps quickly detect uninitialized values). More...
 
 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. More...
 
 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. More...
 
 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). More...
 
int rows () const
 For consistency with Eigen's API, the rows() method returns 3. More...
 
int cols () const
 For consistency with Eigen's API, the cols() method returns 3. More...
 
Vector3< T > get_moments () const
 Returns 3-element vector with moments of inertia [Ixx, Iyy, Izz]. More...
 
Vector3< T > get_products () const
 Returns 3-element vector with products of inertia [Ixy, Ixz, Iyz]. More...
 
Trace () const
 Returns a rotational inertia's trace (i.e., Ixx + Iyy + Izz, the sum of the diagonal elements of the inertia matrix). More...
 
CalcMaximumPossibleMomentOfInertia () const
 Returns the maximum possible moment of inertia for this rotational inertia about-point P for any expressed-in frame E. More...
 
const T & operator() (int i, int j) const
 Const access to the (i, j) element of this rotational inertia. More...
 
Matrix3< T > CopyToFullMatrix3 () const
 Gets a full 3x3 matrix copy of this rotational inertia. More...
 
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). More...
 
RotationalInertia< T > & operator+= (const RotationalInertia< T > &I_BP_E)
 Adds a rotational inertia I_BP_E to this rotational inertia. More...
 
RotationalInertia< T > operator+ (const RotationalInertia< T > &I_BP_E) const
 Adds a rotational inertia I_BP_E to this rotational inertia. More...
 
RotationalInertia< T > & operator-= (const RotationalInertia< T > &I_BP_E)
 Subtracts a rotational inertia I_BP_E from this rotational inertia. More...
 
RotationalInertia< T > operator- (const RotationalInertia< T > &I_BP_E) const
 Subtracts a rotational inertia I_BP_E from this rotational inertia. More...
 
RotationalInertia< T > & operator *= (const T &nonnegative_scalar)
 Multiplies this rotational inertia by a nonnegative scalar (>= 0). More...
 
RotationalInertia< T > operator * (const T &nonnegative_scalar) const
 Multiplies this rotational inertia by a nonnegative scalar (>= 0). More...
 
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). More...
 
RotationalInertia< T > & operator/= (const T &positive_scalar)
 Divides this rotational inertia by a positive scalar (> 0). More...
 
RotationalInertia< T > operator/ (const T &positive_scalar) const
 Divides this rotational inertia by a positive scalar(> 0). More...
 
RotationalInertia< T > MultiplyByScalarSkipValidityCheck (const T &s) const
 (Internal use only) Multiplies a rotational inertia by a scalar. More...
 
void SetToNaN ()
 Sets this rotational inertia so all its elements are equal to NaN. More...
 
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). More...
 
boolean< T > IsNaN () const
 Returns true if any moment/product in this rotational inertia is NaN. More...
 
boolean< T > IsZero () const
 Returns true if all moments and products of inertia are exactly zero. More...
 
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. More...
 
Vector3< doubleCalcPrincipalMomentsOfInertia () const
 Forms the 3 principal moments of inertia for this rotational inertia. More...
 
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. More...
 
boolean< T > CouldBePhysicallyValid () const
 Performs several necessary checks to verify whether this rotational inertia could be physically valid, including: More...
 
RotationalInertia< T > & ReExpressInPlace (const math::RotationMatrix< T > &R_AE)
 Re-expresses this rotational inertia I_BP_E in place to I_BP_A. More...
 
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. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 RotationalInertia (const RotationalInertia &)=default
 
RotationalInertiaoperator= (const RotationalInertia &)=default
 
 RotationalInertia (RotationalInertia &&)=default
 
RotationalInertiaoperator= (RotationalInertia &&)=default
 
Shift methods

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
RotationalInertia< T > & 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. More...
 
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. More...
 
RotationalInertia< T > & 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). More...
 
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). More...
 
RotationalInertia< T > & 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). More...
 
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). More...
 

Static Public Member Functions

static RotationalInertia< T > TriaxiallySymmetric (const T &I_triaxial)
 Constructs a rotational inertia with equal moments of inertia along its diagonal and with each product of inertia set to zero. More...
 
static RotationalInertia< T > MakeFromMomentsAndProductsOfInertia (const T &Ixx, const T &Iyy, const T &Izz, const T &Ixy, const T &Ixz, const T &Iyz, bool skip_validity_check=false)
 (Internal use only) Creates a rotational inertia with moments of inertia Ixx, Iyy, Izz, and with products of inertia Ixy, Ixz, Iyz. More...
 

Protected Member Functions

RotationalInertia< T > & MinusEqualsUnchecked (const RotationalInertia< T > &I_BP_E)
 Subtracts a rotational inertia I_BP_E from this rotational inertia. More...
 

Friends

template<typename >
class RotationalInertia
 
RotationalInertia< T > operator * (const T &nonnegative_scalar, const RotationalInertia< T > &I_BP_E)
 Multiplies a nonnegative scalar (>= 0) by the rotational inertia I_BP_E. More...
 

Related Functions

(Note that these are not member functions.)

template<typename T >
std::ostream & operator<< (std::ostream &out, const RotationalInertia< T > &I)
 Writes an instance of RotationalInertia into a std::ostream. More...
 

Constructor & Destructor Documentation

◆ RotationalInertia() [1/6]

RotationalInertia ( const RotationalInertia< T > &  )
default

◆ RotationalInertia() [2/6]

RotationalInertia ( RotationalInertia< T > &&  )
default

◆ RotationalInertia() [3/6]

Constructs a rotational inertia that has all its moments/products of inertia equal to NaN (helps quickly detect uninitialized values).

◆ RotationalInertia() [4/6]

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.

Exceptions
std::exceptionfor Debug builds if not CouldBePhysicallyValid().

◆ RotationalInertia() [5/6]

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.

Exceptions
std::exceptionfor Debug builds if not CouldBePhysicallyValid().

◆ RotationalInertia() [6/6]

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).

This std::logic_error exception only occurs if mass < 0.

Parameters
massThe mass of particle Q.
p_PQ_EPosition from about-point P to Q, expressed-in frame E.
Return values
I_QP_E,Q'srotational inertia about-point P expressed-in frame E.
Remarks
Negating the position vector p_PQ_E has no affect on the result.
Exceptions
std::exceptionfor Debug builds if not CouldBePhysicallyValid().

Member Function Documentation

◆ CalcMaximumPossibleMomentOfInertia()

T CalcMaximumPossibleMomentOfInertia ( ) const

Returns the maximum possible moment of inertia for this rotational inertia about-point P for any expressed-in frame E.

Remarks
The maximum moment Imax has range: trace / 3 <= Imax <= trace / 2.
See also
Trace()

◆ CalcPrincipalMomentsAndAxesOfInertia()

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.

Returns
3 principal moments of inertia [Ixx Iyy Izz], sorted in ascending order (Ixx โ‰ค Iyy โ‰ค Izz) and a rotation matrix R_EA whose columns are the 3 associated principal directions that relate the expressed-in frame E to a frame A, where frame E is the expressed-in frame for this rotational inertia I_BP_E (body B's rotational inertia about-point P) and frame A contains right-handed orthonormal vectors Ax, Ay, Az. The 1หขแต— column of R_EA is Ax_E (Ax expressed in frame E) which is parallel to the principal axis associated with Ixx (the smallest principal moment of inertia). Similarly, the 2โฟแตˆ and 3สณแตˆ columns of R_EA are Ay_E and Az_E, which are parallel to principal axes associated with Iyy and Izz (the intermediate and largest principal moments of inertia). If all principal moments of inertia are equal (i.e., Ixx = Iyy = Izz), R_EA is the identity matrix.
Exceptions
std::exceptionif the elements of this rotational inertia cannot be converted to a real finite double. For example, an exception is thrown if this contains an erroneous NaN or if scalar type T is symbolic.
See also
CalcPrincipalMomentsOfInertia() to calculate the principal moments of inertia [Ixx Iyy Izz], without calculating the principal directions.

◆ CalcPrincipalMomentsOfInertia()

Vector3<double> CalcPrincipalMomentsOfInertia ( ) const

Forms the 3 principal moments of inertia for this rotational inertia.

Return values
The3 principal moments of inertia [Imin Imed Imax], sorted in ascending order (Imin โ‰ค Imed โ‰ค Imax).
Exceptions
std::exceptionif the elements of this rotational inertia cannot be converted to a real finite double. For example, an exception is thrown if this contains an erroneous NaN or if scalar type T is symbolic.
See also
CalcPrincipalMomentsAndAxesOfInertia() to also calculate principal moment of inertia directions associated with this rotational inertia.

◆ cast()

RotationalInertia<Scalar> cast ( ) const

Returns a new RotationalInertia object templated on Scalar initialized from the values of this rotational inertia's entries.

Template Parameters
ScalarThe scalar type on which the new rotational inertia will be templated.
Note
RotationalInertia<From>::cast<To>() creates a new RotationalInertia<To> from a RotationalInertia<From> but only if type To is constructible from type From. This cast method works in accordance with Eigen's cast method for Eigen's Matrix3 that underlies this RotationalInertia. For example, Eigen currently allows cast from type double to AutoDiffXd, but not vice-versa.

◆ cols()

int cols ( ) const

For consistency with Eigen's API, the cols() method returns 3.

◆ CopyToFullMatrix3()

Matrix3<T> CopyToFullMatrix3 ( ) const

Gets a full 3x3 matrix copy of this rotational inertia.

The returned copy is symmetric and includes both lower and upper parts of the matrix.

◆ CouldBePhysicallyValid()

boolean<T> CouldBePhysicallyValid ( ) const

Performs several necessary checks to verify whether this rotational inertia could be physically valid, including:

  • No NaN moments or products of inertia.
  • Ixx, Iyy, Izz and principal moments are all non-negative.
  • Ixx, Iyy Izz and principal moments satisfy the triangle inequality:
    • Ixx + Iyy >= Izz
    • Ixx + Izz >= Iyy
    • Iyy + Izz >= Ixx
Warning
These checks are necessary (but NOT sufficient) conditions for a rotational inertia to be physically valid. The sufficient condition requires a rotational inertia to satisfy the above checks after this is shifted to the center of mass, i.e., the sufficient condition requires calling CouldBePhysicallyValid() when the about-point is Bcm (the body's center of mass). Note: this class does not know its about-point or its center of mass location.
Returns
true for a plausible rotational inertia passing the above necessary but insufficient checks and false otherwise.
Exceptions
std::exceptionif principal moments of inertia cannot be calculated (eigenvalue solver) or if scalar type T cannot be converted to a double.

◆ get_moments()

Vector3<T> get_moments ( ) const

Returns 3-element vector with moments of inertia [Ixx, Iyy, Izz].

◆ get_products()

Vector3<T> get_products ( ) const

Returns 3-element vector with products of inertia [Ixy, Ixz, Iyz].

◆ IsNaN()

boolean<T> IsNaN ( ) const

Returns true if any moment/product in this rotational inertia is NaN.

Otherwise returns false.

◆ IsNearlyEqualTo()

boolean<T> IsNearlyEqualTo ( const RotationalInertia< T > &  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).

Denoting I_maxA as the largest element value that can appear in a valid this rotational inertia (independent of the expressed-in frame E) and denoting I_maxB as the largest element value that can appear in a valid other rotational inertia (independent of the expressed-in frame E), this and other are considered nearly equal to each other, if: โ€–this - otherโ€–โˆž < precision * min(I_maxA, I_maxB)

Parameters
otherRotational inertia to compare with this rotational inertia.
precisionis a dimensionless real positive number that is usually based on two factors, namely expected accuracy of moments/products of inertia (e.g., from end-user or CAD) and/or machine-precision.
Returns
true if the absolute value of each moment/product of inertia in this is within epsilon of the corresponding moment/ product absolute value in other. Otherwise returns false.
Note
: This method only works if all moments of inertia with scalar type T in this and other can be converted to a double (discarding supplemental scalar data such as derivatives of an AutoDiffXd). It fails at runtime if type T cannot be converted to double.

◆ IsZero()

boolean<T> IsZero ( ) const

Returns true if all moments and products of inertia are exactly zero.

◆ MakeFromMomentsAndProductsOfInertia()

static RotationalInertia<T> MakeFromMomentsAndProductsOfInertia ( const T &  Ixx,
const T &  Iyy,
const T &  Izz,
const T &  Ixy,
const T &  Ixz,
const T &  Iyz,
bool  skip_validity_check = false 
)
static

(Internal use only) Creates a rotational inertia with moments of inertia Ixx, Iyy, Izz, and with products of inertia Ixy, Ixz, Iyz.

Parameters
[in]Ixx,Iyy,IzzMoments of inertia.
[in]Ixy,Ixz,IyzProducts of inertia.
[in]skip_validity_checkIf set to false, the rotational inertia is checked via CouldBePhysicallyValid() to ensure it is physically valid. If set to true (not generally recommended), the check is skipped (which reduces some computational cost). The default value is false.
Exceptions
std::exceptionif skip_validity_check is false and CouldBePhysicallyValid() fails.

◆ MinusEqualsUnchecked()

RotationalInertia<T>& MinusEqualsUnchecked ( const RotationalInertia< T > &  I_BP_E)
protected

Subtracts a rotational inertia I_BP_E from this rotational inertia.

No check is done to determine if the result is physically valid.

Parameters
I_BP_ERotational inertia of a body (or composite body) B to be subtracted from this rotational inertia.
Returns
A reference to this rotational inertia. this changes since rotational inertia I_BP_E has been subtracted from it.
See also
operator-().
Warning
This operator may produce an invalid rotational inertia. Use operator-=() to perform necessary (but insufficient) checks on the physical validity of the resulting rotational inertia.
Note
: Although this method is mathematically useful, it may result in a rotational inertia that is physically invalid. This method helps perform intermediate calculations which do not necessarily represent a real rotational inertia. For example, an efficient way to shift a rotational inertia from an arbitrary point P to an arbitrary point Q is mathematical equivalent to a + (b - c). Although a must be physically valid and the result a + (b - c) must be physically valid, the intermediate quantity (b - c) is not necessarily physically valid. This method allows (b - c) to be calculated without requiring (b - c) to be physically valid.
See also
operator-=().

◆ MultiplyByScalarSkipValidityCheck()

RotationalInertia<T> MultiplyByScalarSkipValidityCheck ( const T &  s) const

(Internal use only) Multiplies a rotational inertia by a scalar.

Parameters
[in]sScalar which multiplies this.
Returns
this rotational inertia multiplied by s.
See also
operator*(const T&, const RotationalInertia<T>&).
Note
This method works even if s is negative or this is invalid. This method is useful for error messages associated with an invalid inertia.

◆ operator *() [1/2]

RotationalInertia<T> operator * ( const T &  nonnegative_scalar) const

Multiplies this rotational inertia by a nonnegative scalar (>= 0).

In debug builds, throws std::exception if nonnegative_scalar < 0.

Parameters
nonnegative_scalarNonnegative scalar which multiplies this.
Returns
this rotational inertia multiplied by nonnegative_scalar.
See also
operator*=(), operator*(const T&, const RotationalInertia<T>&)

◆ operator *() [2/2]

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).

Note
This calculation is equivalent to regarding this rotational inertia as an inertia dyadic and dot-multiplying it by w_E.
Parameters
w_EVector to post-multiply with this rotational inertia.
Returns
The Vector that results from multiplying this by w_E.

◆ operator *=()

RotationalInertia<T>& operator *= ( const T &  nonnegative_scalar)

Multiplies this rotational inertia by a nonnegative scalar (>= 0).

In debug builds, throws std::exception if nonnegative_scalar < 0.

Parameters
nonnegative_scalarNonnegative scalar which multiplies this.
Returns
A reference to this rotational inertia. this changes since this has been multiplied by nonnegative_scalar.
See also
operator*(), operator*(const T&, const RotationalInertia<T>&).

◆ operator()()

const T& operator() ( int  i,
int  j 
) const

Const access to the (i, j) element of this rotational inertia.

Remarks
A mutable version of operator() is intentionally absent so as to prevent an end-user from directly setting elements. This prevents the creation of a non-physical (or non-symmetric) rotational inertia.

◆ operator+()

RotationalInertia<T> operator+ ( const RotationalInertia< T > &  I_BP_E) const

Adds a rotational inertia I_BP_E to this rotational inertia.

This method requires both rotational inertias (I_BP_E and this) to have the same about-point P and the same expressed-in frame E.

Parameters
I_BP_ERotational inertia of a body (or composite body) B to be added to this rotational inertia. I_BP_E and this must have the same about-point P and expressed-in frame E.
Returns
The sum of this rotational inertia and I_BP_E.
See also
operator+=().

◆ operator+=()

RotationalInertia<T>& operator+= ( const RotationalInertia< T > &  I_BP_E)

Adds a rotational inertia I_BP_E to this rotational inertia.

This method requires both rotational inertias (I_BP_E and this) to have the same about-point P and the same expressed-in frame E. The += operator updates this so I_BP_E is added to this.

Parameters
I_BP_ERotational inertia of a body (or composite body) B to be added to this rotational inertia. I_BP_E and this must have the same about-point P and expressed-in frame E.
Returns
A reference to this rotational inertia. this changes since rotational inertia I_BP_E has been added to it.
See also
operator+().

◆ operator-()

RotationalInertia<T> operator- ( const RotationalInertia< T > &  I_BP_E) const

Subtracts a rotational inertia I_BP_E from this rotational inertia.

This method requires both rotational inertias (I_BP_E and this) to have the same about-point P and the same expressed-in frame E.

Parameters
I_BP_ERotational inertia of a body (or composite body) B to be subtracted from this rotational inertia. I_BP_E and this must have the same about-point P and expressed-in frame E.
Returns
The subtraction of I_BP_E from this rotational inertia.
Exceptions
std::exceptionfor Debug builds if not CouldBePhysicallyValid().
See also
operator-=().
Warning
See warning and documentation for operator-=().

◆ operator-=()

RotationalInertia<T>& operator-= ( const RotationalInertia< T > &  I_BP_E)

Subtracts a rotational inertia I_BP_E from this rotational inertia.

This method requires both rotational inertias (I_BP_E and this) to have the same about-point P and the same expressed-in frame E. The -= operator updates this so I_BP_E is subtracted from this.

Parameters
I_BP_ERotational inertia of a body (or composite body) B to be subtracted from this rotational inertia. I_BP_E and this must have the same about-point P and expressed-in frame E.
Returns
A reference to this rotational inertia. this changes since rotational inertia I_BP_E has been subtracted from it.
Exceptions
std::exceptionfor Debug builds if not CouldBePhysicallyValid().
See also
operator-().
Note
This subtract operator is useful for computing rotational inertia of a body with a hole. First the rotational inertia of a fully solid body S (without the hole) is calculated, then the rotational inertia of the hole (treated as a massive solid body B) is calculated. The rotational inertia of a composite body C (comprised of S and -B) is computed by subtracting B's rotational inertia from S's rotational inertia.

◆ operator/()

RotationalInertia<T> operator/ ( const T &  positive_scalar) const

Divides this rotational inertia by a positive scalar(> 0).

In debug builds, throws std::exception if positive_scalar <= 0.

Parameters
positive_scalarPositive scalar (> 0) which divides this.
Returns
this rotational inertia divided by positive_scalar.
See also
operator/=().

◆ operator/=()

RotationalInertia<T>& operator/= ( const T &  positive_scalar)

Divides this rotational inertia by a positive scalar (> 0).

In debug builds, throws std::exception if positive_scalar <= 0.

Parameters
positive_scalarPositive scalar (> 0) which divides this.
Returns
A reference to this rotational inertia. this changes since this has been divided by positive_scalar.
See also
operator/().

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ ReExpress()

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.

Parameters
[in]R_AERotationMatrix relating frames A and E.
Return values
I_BP_ARotational inertia of B about-point P expressed-in frame A.
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is re-expressed-in frame A violates CouldBePhysicallyValid().
See also
ReExpressInPlace()

◆ ReExpressInPlace()

RotationalInertia< T > & ReExpressInPlace ( const math::RotationMatrix< T > &  R_AE)

Re-expresses this rotational inertia I_BP_E in place to I_BP_A.

In other words, starts with this rotational inertia of a body (or composite body) B about-point P expressed-in frame E and re-expresses to B's rotational inertia about-point P expressed-in frame A. More concisely, we compute I_BP_A = R_AE * I_BP_E * (R_AE)แต€.

Parameters
[in]R_AERotationMatrix relating frames A and E.
Returns
A reference to this rotational inertia about-point P, but with this now expressed in frame A (instead of frame E).
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is re-expressed-in frame A violates CouldBePhysicallyValid().
See also
ReExpress().

◆ rows()

int rows ( ) const

For consistency with Eigen's API, the rows() method returns 3.

◆ SetToNaN()

void SetToNaN ( )

Sets this rotational inertia so all its elements are equal to NaN.

This helps quickly detect uninitialized moments/products of inertia.

◆ SetZero()

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).

Note: Real 3D massive physical objects have non-zero moments of inertia.

◆ ShiftFromCenterOfMass()

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.

I.e., shifts I_BBcm_E to I_BQ_E (both are expressed-in frame E).

Parameters
massThe mass of body (or composite body) B.
p_BcmQ_EPosition vector from Bcm to Q, expressed-in frame E.
Return values
I_BQ_EB's rotational inertia about-point Q expressed-in frame E.
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid().
Remarks
Negating the position vector p_BcmQ_E has no affect on the result.

◆ ShiftFromCenterOfMassInPlace()

RotationalInertia<T>& 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.

I.e., shifts I_BBcm_E to I_BQ_E (both are expressed-in frame E).

Parameters
massThe mass of body (or composite body) B.
p_BcmQ_EPosition vector from Bcm to Q, expressed-in frame E.
Returns
A reference to this rotational inertia expressed-in frame E, but with this shifted from about-point Bcm to about-point Q. i.e., returns I_BQ_E, B's rotational inertia about-point Bcm expressed-in frame E.
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid().
Remarks
Negating the position vector p_BcmQ_E has no affect on the result.

◆ ShiftToCenterOfMass()

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).

I.e., shifts I_BQ_E to I_BBcm_E (both are expressed-in frame E).

Parameters
massThe mass of body (or composite body) B.
p_QBcm_EPosition vector from Q to Bcm, expressed-in frame E.
Return values
I_BBcm_EB's rotational inertia about-point Bcm expressed-in frame E.
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is shifted to about-point Bcm violates CouldBePhysicallyValid().
Remarks
Negating the position vector p_QBcm_E has no affect on the result.

◆ ShiftToCenterOfMassInPlace()

RotationalInertia<T>& 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).

I.e., shifts I_BQ_E to I_BBcm_E (both are expressed-in frame E).

Parameters
massThe mass of body (or composite body) B.
p_QBcm_EPosition vector from Q to Bcm, expressed-in frame E.
Returns
A reference to this rotational inertia expressed-in frame E, but with this shifted from about-point Q to about-point Bcm, i.e., returns I_BBcm_E, B's rotational inertia about-point Bcm expressed-in frame E.
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is shifted to about-point Bcm violates CouldBePhysicallyValid().
Remarks
Negating the position vector p_QBcm_E has no affect on the result.

◆ ShiftToThenAwayFromCenterOfMass()

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).

I.e., shifts I_BP_E to I_BQ_E (both are expressed-in frame E).

Parameters
massThe mass of body (or composite body) B.
p_PBcm_EPosition vector from P to Bcm, expressed-in frame E.
p_QBcm_EPosition vector from Q to Bcm, expressed-in frame E.
Return values
I_BQ_E,B'srotational inertia about-point Q expressed-in frame E.
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid().
Remarks
Negating either (or both) position vectors p_PBcm_E and p_QBcm_E has no affect on the result.

◆ ShiftToThenAwayFromCenterOfMassInPlace()

RotationalInertia<T>& 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).

I.e., shifts I_BP_E to I_BQ_E (both are expressed-in frame E).

Parameters
massThe mass of body (or composite body) B.
p_PBcm_EPosition vector from P to Bcm, expressed-in frame E.
p_QBcm_EPosition vector from Q to Bcm, expressed-in frame E.
Returns
A reference to this rotational inertia expressed-in frame E, but with this shifted from about-point P to about-point Q, i.e., returns I_BQ_E, B's rotational inertia about-point Q expressed-in frame E.
Exceptions
std::exceptionfor Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid().
Remarks
Negating either (or both) position vectors p_PBcm_E and p_QBcm_E has no affect on the result.
This method is more efficient (by 6 multiplications) than first shifting to the center of mass, then shifting away, e.g., as (ShiftToCenterOfMassInPlace()).ShiftFromCenterOfMassInPlace();

◆ Trace()

T Trace ( ) const

Returns a rotational inertia's trace (i.e., Ixx + Iyy + Izz, the sum of the diagonal elements of the inertia matrix).

The trace happens to be invariant to its expressed-in frame (i.e., the trace does not depend on the frame in which it is expressed). The trace is useful because the largest moment of inertia Imax has range: trace / 3 <= Imax <= trace / 2, and the largest possible product of inertia must be <= Imax / 2. Hence, trace / 3 and trace / 2 give a lower and upper bound on the largest possible element that can be in a valid rotational inertia.

◆ TriaxiallySymmetric()

static RotationalInertia<T> TriaxiallySymmetric ( const T &  I_triaxial)
static

Constructs a rotational inertia with equal moments of inertia along its diagonal and with each product of inertia set to zero.

This factory is useful for the rotational inertia of a uniform-density sphere or cube. In debug builds, throws std::exception if I_triaxial is negative/NaN.

Friends And Related Function Documentation

◆ operator *

RotationalInertia<T> operator * ( const T &  nonnegative_scalar,
const RotationalInertia< T > &  I_BP_E 
)
friend

Multiplies a nonnegative scalar (>= 0) by the rotational inertia I_BP_E.

In debug builds, throws std::exception if nonnegative_scalar < 0.

Parameters
nonnegative_scalarNonnegative scalar which multiplies I_BP_E.
Returns
nonnegative_scalar multiplied by rotational inertia I_BP_E.
See also
operator*=(), operator*()

Multiplication of a scalar with a rotational matrix is commutative.

◆ operator<<()

std::ostream & operator<< ( std::ostream &  out,
const RotationalInertia< T > &  I 
)
related

Writes an instance of RotationalInertia into a std::ostream.

◆ RotationalInertia

friend class RotationalInertia
friend

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