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).
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.๐โ = 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
true
. For instance, validity checks are not performed when T is symbolic::Expression.Various methods in this class require numerical (not symbolic) data types.
T | The 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... | |||||||||
T | Trace () const | ||||||||
Returns a rotational inertia's trace (i.e., Ixx + Iyy + Izz, the sum of the diagonal elements of the inertia matrix). More... | |||||||||
T | 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< double > | CalcPrincipalMomentsOfInertia () 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... | |||||||||
void | 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 | |||||||||
RotationalInertia & | operator= (const RotationalInertia &)=default | ||||||||
RotationalInertia (RotationalInertia &&)=default | |||||||||
RotationalInertia & | operator= (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.
| |||||||||
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. 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... | |||||||||
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). 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... | |||||||||
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). 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... | |
|
default |
|
default |
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.
std::exception | for Debug builds if not CouldBePhysicallyValid(). |
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
.
std::exception | for Debug builds if not CouldBePhysicallyValid(). |
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.
mass | The mass of particle Q. |
p_PQ_E | Position from about-point P to Q, expressed-in frame E. |
I_QP_E,Q's | rotational inertia about-point P expressed-in frame E. |
std::exception | for Debug builds if not CouldBePhysicallyValid(). |
T CalcMaximumPossibleMomentOfInertia | ( | ) | const |
Returns the maximum possible moment of inertia for this
rotational inertia about-point P for any expressed-in frame E.
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.
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. std::exception | if 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. |
Forms the 3 principal moments of inertia for this
rotational inertia.
The | 3 principal moments of inertia [Imin Imed Imax], sorted in ascending order (Imin โค Imed โค Imax). |
std::exception | if 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. |
this
rotational inertia. RotationalInertia<Scalar> cast | ( | ) | const |
Returns a new RotationalInertia object templated on Scalar
initialized from the values of this
rotational inertia's entries.
Scalar | The scalar type on which the new rotational inertia will be templated. |
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. 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.
boolean<T> CouldBePhysicallyValid | ( | ) | const |
Performs several necessary checks to verify whether this
rotational inertia could be physically valid, including:
Ixx + Iyy >= Izz
Ixx + Izz >= Iyy
Iyy + Izz >= Ixx
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.true
for a plausible rotational inertia passing the above necessary but insufficient checks and false
otherwise. std::exception | if principal moments of inertia cannot be calculated (eigenvalue solver) or if scalar type T cannot be converted to a double. |
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].
boolean<T> IsNaN | ( | ) | const |
Returns true
if any moment/product in this
rotational inertia is NaN.
Otherwise returns false
.
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)
other | Rotational inertia to compare with this rotational inertia. |
precision | is 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. |
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
. 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
. boolean<T> IsZero | ( | ) | const |
Returns true
if all moments and products of inertia are exactly zero.
|
static |
(Internal use only) Creates a rotational inertia with moments of inertia Ixx, Iyy, Izz, and with products of inertia Ixy, Ixz, Iyz.
[in] | Ixx,Iyy,Izz | Moments of inertia. |
[in] | Ixy,Ixz,Iyz | Products of inertia. |
[in] | skip_validity_check | If 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. |
std::exception | if skip_validity_check is false and CouldBePhysicallyValid() fails. |
|
protected |
Subtracts a rotational inertia I_BP_E
from this
rotational inertia.
No check is done to determine if the result is physically valid.
I_BP_E | Rotational inertia of a body (or composite body) B to be subtracted from this rotational inertia. |
this
rotational inertia. this
changes since rotational inertia I_BP_E
has been subtracted from it. 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. RotationalInertia<T> MultiplyByScalarSkipValidityCheck | ( | const T & | s | ) | const |
(Internal use only) Multiplies a rotational inertia by a scalar.
[in] | s | Scalar which multiplies this . |
this
rotational inertia multiplied by s
. s
is negative or this
is invalid. This method is useful for error messages associated with an invalid inertia. 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.
nonnegative_scalar | Nonnegative scalar which multiplies this . |
this
rotational inertia multiplied by nonnegative_scalar
. 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).
this
rotational inertia as an inertia dyadic and dot-multiplying it by w_E. w_E | Vector to post-multiply with this rotational inertia. |
this
by w_E
. 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.
nonnegative_scalar | Nonnegative scalar which multiplies this . |
this
rotational inertia. this
changes since this
has been multiplied by nonnegative_scalar
. Const access to the (i, j)
element of this rotational inertia.
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.
I_BP_E | Rotational 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. |
this
rotational inertia and I_BP_E
. 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
.
I_BP_E | Rotational 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. |
this
rotational inertia. this
changes since rotational inertia I_BP_E
has been added to it. 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.
I_BP_E | Rotational 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. |
I_BP_E
from this
rotational inertia. std::exception | for Debug builds if not CouldBePhysicallyValid(). |
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
.
I_BP_E | Rotational 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. |
this
rotational inertia. this
changes since rotational inertia I_BP_E
has been subtracted from it. std::exception | for Debug builds if not CouldBePhysicallyValid(). |
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.
positive_scalar | Positive scalar (> 0) which divides this . |
this
rotational inertia divided by positive_scalar
. 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.
positive_scalar | Positive scalar (> 0) which divides this . |
this
rotational inertia. this
changes since this
has been divided by positive_scalar
.
|
default |
|
default |
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.
[in] | R_AE | RotationMatrix relating frames A and E. |
I_BP_A | Rotational inertia of B about-point P expressed-in frame A. |
std::exception | for Debug builds if the rotational inertia that is re-expressed-in frame A violates CouldBePhysicallyValid(). |
void 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)แต
.
[in] | R_AE | RotationMatrix relating frames A and E. |
std::exception | for Debug builds if the rotational inertia that is re-expressed-in frame A violates CouldBePhysicallyValid(). |
void SetToNaN | ( | ) |
Sets this
rotational inertia so all its elements are equal to NaN.
This helps quickly detect uninitialized moments/products of inertia.
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.
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).
mass | The mass of body (or composite body) B. |
p_BcmQ_E | Position vector from Bcm to Q, expressed-in frame E. |
I_BQ_E | B's rotational inertia about-point Q expressed-in frame E. |
std::exception | for Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid(). |
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.
I.e., shifts I_BBcm_E
to I_BQ_E
(both are expressed-in frame E). On return, this
is modified to be shifted from about-point Bcm to about-point Q.
mass | The mass of body (or composite body) B. |
p_BcmQ_E | Position vector from Bcm to Q, expressed-in frame E. |
std::exception | for Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid(). |
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).
mass | The mass of body (or composite body) B. |
p_QBcm_E | Position vector from Q to Bcm , expressed-in frame E. |
I_BBcm_E | B's rotational inertia about-point Bcm expressed-in frame E. |
std::exception | for Debug builds if the rotational inertia that is shifted to about-point Bcm violates CouldBePhysicallyValid(). |
p_QBcm_E
has no affect on the result. 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).
I.e., shifts I_BQ_E
to I_BBcm_E
(both are expressed-in frame E). On return, this
is shifted from about-point Q to about-point Bcm
.
mass | The mass of body (or composite body) B. |
p_QBcm_E | Position vector from Q to Bcm , expressed-in frame E. |
std::exception | for Debug builds if the rotational inertia that is shifted to about-point Bcm violates CouldBePhysicallyValid(). |
p_QBcm_E
has no affect on the result. 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).
mass | The mass of body (or composite body) B. |
p_PBcm_E | Position vector from P to Bcm, expressed-in frame E. |
p_QBcm_E | Position vector from Q to Bcm, expressed-in frame E. |
I_BQ_E,B's | rotational inertia about-point Q expressed-in frame E. |
std::exception | for Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid(). |
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).
I.e., shifts I_BP_E
to I_BQ_E
(both are expressed-in frame E). On return, this
is modified to be shifted from about-point P to about-point Q.
mass | The mass of body (or composite body) B. |
p_PBcm_E | Position vector from P to Bcm, expressed-in frame E. |
p_QBcm_E | Position vector from Q to Bcm, expressed-in frame E. |
std::exception | for Debug builds if the rotational inertia that is shifted to about-point Q violates CouldBePhysicallyValid(). |
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.
|
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.
|
friend |
Multiplies a nonnegative scalar (>= 0) by the rotational inertia I_BP_E
.
In debug builds, throws std::exception if nonnegative_scalar
< 0.
nonnegative_scalar | Nonnegative scalar which multiplies I_BP_E . |
nonnegative_scalar
multiplied by rotational inertia I_BP_E
. Multiplication of a scalar with a rotational matrix is commutative.
|
related |
Writes an instance of RotationalInertia into a std::ostream.
|
friend |