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

Detailed Description

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

This class is used to represent rotational inertias for unit mass bodies.

Therefore, unlike RotationalInertia whose units are kg⋅m², the units of a UnitInertia are those of length squared. A unit inertia is a useful concept to represent the geometric distribution of mass in a body regardless of the actual value of the body mass. The rotational inertia of a body can therefore be obtained by multiplying its unit inertia by its mass. Unit inertia matrices can also be called gyration matrices and therefore we choose to represent them in source code notation with the capital letter G. In contrast, the capital letter I is used to represent non-unit mass rotational inertias. This class restricts the set of allowed operations on a unit inertia to ensure the unit-mass invariant. For instance, multiplication by a scalar can only return a general RotationalInertia but not a UnitInertia.

Note
This class has no means to check at construction from user provided parameters whether it actually represents the unit inertia or gyration matrix of a unit-mass body. However, as previously noted, once a unit inertia is created, a number of operations are disallowed to ensure the unit-mass invariant. Also notice that once a unit inertia is created, it is the unit inertia of some body, perhaps with scaled geometry from the user's intention.
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 UnitInertia objects may contain invalid inertia data in cases where input checking is skipped.
See also
https://en.cppreference.com/w/cpp/language/exceptions
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 UnitInertia ()
 Default UnitInertia constructor sets all entries to NaN for quick detection of uninitialized values. More...
 
 UnitInertia (const T &Ixx, const T &Iyy, const T &Izz)
 Creates a unit inertia with moments of inertia Ixx, Iyy, Izz, and with each product of inertia set to zero. More...
 
 UnitInertia (const T &Ixx, const T &Iyy, const T &Izz, const T &Ixy, const T &Ixz, const T &Iyz)
 Creates a unit inertia with moments of inertia Ixx, Iyy, Izz, and with products of inertia Ixy, Ixz, Iyz. More...
 
 UnitInertia (const RotationalInertia< T > &I)
 Constructs a UnitInertia from a RotationalInertia. More...
 
template<typename Scalar >
UnitInertia< Scalar > cast () const
 Returns a new UnitInertia object templated on Scalar initialized from the value of this unit inertia. More...
 
UnitInertia< T > & SetFromRotationalInertia (const RotationalInertia< T > &I, const T &mass)
 Sets this unit inertia from a generally non-unit inertia I corresponding to a body with a given mass. More...
 
void ReExpressInPlace (const math::RotationMatrix< T > &R_AE)
 Re-express a unit inertia in a different frame, performing the operation in place and modifying the original object. More...
 
UnitInertia< T > ReExpress (const math::RotationMatrix< T > &R_AE) const
 Given this unit inertia G_BP_E of a body B about a point P and expressed in frame E, this method computes the same unit inertia re-expressed in another frame A as G_BP_A = R_AE * G_BP_E * (R_AE)ᵀ. More...
 
void ShiftFromCenterOfMassInPlace (const Vector3< T > &p_BcmQ_E)
 For a central unit inertia G_Bcm_E computed about a body's center of mass (or centroid) Bcm and expressed in a frame E, this method shifts this inertia using the parallel axis theorem to be computed about a point Q. More...
 
UnitInertia< T > ShiftFromCenterOfMass (const Vector3< T > &p_BcmQ_E) const
 Shifts this central unit inertia to a different point, and returns the result. More...
 
void ShiftToCenterOfMassInPlace (const Vector3< T > &p_QBcm_E)
 For the unit inertia G_BQ_E of a body or composite body B computed about a point Q and expressed in a frame E, this method shifts this inertia using the parallel axis theorem to be computed about the center of mass Bcm of B. More...
 
UnitInertia< T > ShiftToCenterOfMass (const Vector3< T > &p_QBcm_E) const
 For the unit inertia G_BQ_E of a body or composite body B computed about a point Q and expressed in a frame E, this method shifts this inertia using the parallel axis theorem to be computed about the center of mass Bcm of B. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 UnitInertia (const UnitInertia &)=default
 
UnitInertiaoperator= (const UnitInertia &)=default
 
 UnitInertia (UnitInertia &&)=default
 
UnitInertiaoperator= (UnitInertia &&)=default
 
Disable operators that may result in non-unit inertias.
UnitInertia< T > & operator+= (const RotationalInertia< T > &)=delete
 
UnitInertia< T > & operator-= (const RotationalInertia< T > &)=delete
 
UnitInertia< T > & operator *= (const T &)=delete
 
UnitInertia< T > & operator/= (const T &)=delete
 
- Public Member Functions inherited from RotationalInertia< T >
 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...
 
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...
 
 RotationalInertia (const RotationalInertia &)=default
 
RotationalInertiaoperator= (const RotationalInertia &)=default
 
 RotationalInertia (RotationalInertia &&)=default
 
RotationalInertiaoperator= (RotationalInertia &&)=default
 
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

Unit inertia for common 3D objects

The following methods assist in the construction of UnitInertia instances for common 3D objects such as boxes, spheres, rods and others.

This method computes a UnitInertia for body with unit mass, typically around its centroid, and in a frame aligned with its principal axes. To construct general UnitInertia objects use these methods along with ShiftFromCenterOfMassInPlace() to move the point about which the inertia is computed and use ReExpress() to express in a different frame. A non-unit RotationalInertia is obtained by multiplying the generated UnitInertia by a non-unit mass value.

static UnitInertia< T > PointMass (const Vector3< T > &p_FQ)
 Construct a unit inertia for a point mass of unit mass located at point Q, whose location in a frame F is given by the position vector p_FQ (that is, p_FoQ_F). More...
 
static UnitInertia< T > SolidEllipsoid (const T &a, const T &b, const T &c)
 Computes the unit inertia for a unit-mass solid ellipsoid of uniform density taken about its center. More...
 
static UnitInertia< T > SolidSphere (const T &r)
 Computes the unit inertia for a unit-mass solid sphere of uniform density and radius r taken about its center. More...
 
static UnitInertia< T > HollowSphere (const T &r)
 Computes the unit inertia for a unit-mass hollow sphere of radius r consisting of an infinitesimally thin shell of uniform density. More...
 
static UnitInertia< T > SolidBox (const T &Lx, const T &Ly, const T &Lz)
 Computes the unit inertia for a unit-mass solid box of uniform density taken about its geometric center. More...
 
static UnitInertia< T > SolidCube (const T &L)
 Computes the unit inertia for a unit-mass solid cube (a box with equal-sized sides) of uniform density taken about its geometric center. More...
 
static UnitInertia< T > SolidCylinder (const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a unit inertia for a uniform density solid cylinder B about its center of mass Bcm (which is coincident with B's geometric center Bo). More...
 
static UnitInertia< T > SolidCapsule (const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a unit inertia for a uniform density solid capsule B about its center of mass Bcm (which is coincident with B's geometric center Bo). More...
 
static UnitInertia< T > SolidCylinderAboutEnd (const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a unit inertia for a uniform-density solid cylinder B about an end-point Bp of the cylinder's axis (see below for more about Bp). More...
 
static UnitInertia< T > SolidTetrahedronAboutPoint (const Vector3< T > &p0, const Vector3< T > &p1, const Vector3< T > &p2, const Vector3< T > &p3)
 Creates a unit inertia for a unit-mass uniform density solid tetrahedron B about a point A, from which position vectors to B's 4 vertices B0, B1, B2, B3 are measured (position vectors are all expressed in a common frame E). More...
 
static UnitInertia< T > SolidTetrahedronAboutVertex (const Vector3< T > &p1, const Vector3< T > &p2, const Vector3< T > &p3)
 (Advanced) Creates a unit inertia for a unit-mass uniform density solid tetrahedron B about its vertex B0, from which position vectors to B's other 3 vertices B1, B2, B3 are measured (vectors are all expressed in a common frame E). More...
 
static UnitInertia< T > AxiallySymmetric (const T &moment_parallel, const T &moment_perpendicular, const Vector3< T > &unit_vector)
 Returns the unit inertia for a body B for which there exists an axis L passing through the body's center of mass Bcm having the property that B's moment of inertia about all lines perpendicular to L are equal. More...
 
static UnitInertia< T > StraightLine (const T &moment_perpendicular, const Vector3< T > &unit_vector)
 Creates a unit inertia for a straight line segment B about a point Bp on the line segment. More...
 
static UnitInertia< T > ThinRod (const T &length, const Vector3< T > &unit_vector)
 Creates a unit inertia for a uniform density thin rod B about its center of mass Bcm (which is coincident with B's geometric center Bo). More...
 
static UnitInertia< T > TriaxiallySymmetric (const T &I_triaxial)
 Constructs a unit inertia with equal moments of inertia along its diagonal and with each product of inertia set to zero. More...
 
- Static Public Member Functions inherited from RotationalInertia< T >
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...
 

Additional Inherited Members

- Protected Member Functions inherited from RotationalInertia< T >
RotationalInertia< T > & MinusEqualsUnchecked (const RotationalInertia< T > &I_BP_E)
 Subtracts a rotational inertia I_BP_E from this rotational inertia. More...
 

Constructor & Destructor Documentation

◆ UnitInertia() [1/6]

UnitInertia ( const UnitInertia< T > &  )
default

◆ UnitInertia() [2/6]

UnitInertia ( UnitInertia< T > &&  )
default

◆ UnitInertia() [3/6]

Default UnitInertia constructor sets all entries to NaN for quick detection of uninitialized values.

◆ UnitInertia() [4/6]

UnitInertia ( const T &  Ixx,
const T &  Iyy,
const T &  Izz 
)

Creates a unit inertia with moments of inertia Ixx, Iyy, Izz, and with each product of inertia set to zero.

In debug builds, throws std::exception if unit inertia constructed from these arguments violates RotationalInertia::CouldBePhysicallyValid().

◆ UnitInertia() [5/6]

UnitInertia ( const T &  Ixx,
const T &  Iyy,
const T &  Izz,
const T &  Ixy,
const T &  Ixz,
const T &  Iyz 
)

Creates a unit inertia with moments of inertia Ixx, Iyy, Izz, and with products of inertia Ixy, Ixz, Iyz.

In debug builds, throws std::exception if unit inertia constructed from these arguments violates RotationalInertia::CouldBePhysicallyValid().

◆ UnitInertia() [6/6]

UnitInertia ( const RotationalInertia< T > &  I)
explicit

Constructs a UnitInertia from a RotationalInertia.

This constructor has no way to verify that the input rotational inertia actually is a unit inertia. But the construction will nevertheless succeed, and the values of the input rotational inertia will henceforth be considered a valid unit inertia.

Precondition
The user is responsible for passing a valid rotational inertia.

Member Function Documentation

◆ AxiallySymmetric()

static UnitInertia<T> AxiallySymmetric ( const T &  moment_parallel,
const T &  moment_perpendicular,
const Vector3< T > &  unit_vector 
)
static

Returns the unit inertia for a body B for which there exists an axis L passing through the body's center of mass Bcm having the property that B's moment of inertia about all lines perpendicular to L are equal.

Bodies with this "axially symmetric inertia" property include axisymmetric cylinders or cones and propellers with 3⁺ evenly spaced blades. For a body B with axially symmetric inertia, B's unit inertia about a point Bp on axis L can be written in terms of a unit_vector parallel to L; the parallel moment of inertia J about L; and the perpendicular moment of inertia K about any line perpendicular to axis L; as:

  G = K * Identity + (J - K) * unit_vector ⊗ unit_vector

where Identity is the identity matrix and ⊗ denotes the tensor product operator. See Mitiguy, P., 2016. Advanced Dynamics & Motion Simulation.

Parameters
[in]moment_parallel(J) B's unit moment of inertia about axis L.
[in]moment_perpendicular(K) B's unit moment of inertia about Bp for any line perpendicular to unit_vector.
[in]unit_vectorunit vector parallel to axis L, expressed in a frame E.
Return values
G_BBp_EB's unit inertia about point Bp on B's symmetry axis, expressed in the same frame E as the unit_vector is expressed.
Precondition
Points Bp and Bcm are both on B's symmetry axis. The actual location of these points is not known by this function. However, the value of moment_perpendicular (K) is associated with point Bp.
Note
B's unit inertia about Bp is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bp and is perpendicular to unit_vector.
Exceptions
std::exceptionif moment_parallel (J) or moment_perpendicular (K) is negative or if J > 2 K (violates the triangle inequality, see CouldBePhysicallyValid()) or ‖unit_vector‖ is not within 1.0E-14 of 1.0.

◆ cast()

UnitInertia<Scalar> cast ( ) const

Returns a new UnitInertia object templated on Scalar initialized from the value of this unit inertia.

Template Parameters
ScalarThe scalar type on which the new unit inertia will be templated.
Note
UnitInertia<From>::cast<To>() creates a new UnitInertia<To> from a UnitInertia<From> but only if type To is constructible from type From. As an example of this, UnitInertia<double>::cast<AutoDiffXd>() is valid since AutoDiffXd a(1.0) is valid. However, UnitInertia<AutoDiffXd>::cast<double>() is not.

◆ HollowSphere()

static UnitInertia<T> HollowSphere ( const T &  r)
static

Computes the unit inertia for a unit-mass hollow sphere of radius r consisting of an infinitesimally thin shell of uniform density.

The unit inertia is taken about the center of the sphere.

◆ operator *=()

UnitInertia<T>& operator *= ( const T &  )
delete

◆ operator+=()

UnitInertia<T>& operator+= ( const RotationalInertia< T > &  )
delete

◆ operator-=()

UnitInertia<T>& operator-= ( const RotationalInertia< T > &  )
delete

◆ operator/=()

UnitInertia<T>& operator/= ( const T &  )
delete

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ PointMass()

static UnitInertia<T> PointMass ( const Vector3< T > &  p_FQ)
static

Construct a unit inertia for a point mass of unit mass located at point Q, whose location in a frame F is given by the position vector p_FQ (that is, p_FoQ_F).

The unit inertia G_QFo_F of point mass Q about the origin Fo of frame F and expressed in F for this unit mass point equals the square of the cross product matrix of p_FQ. In coordinate-free form:

\[ G^{Q/F_o} = (^Fp^Q_\times)^2 = (^Fp^Q_\times)^T \, ^Fp^Q_\times = -^Fp^Q_\times \, ^Fp^Q_\times \]

where \( ^Fp^Q_\times \) is the cross product matrix of vector \( ^Fp^Q \). In source code the above expression is written as:

  G_QFo_F = px_FQ² = px_FQᵀ * px_FQ = -px_FQ * px_FQ

where px_FQ denotes the cross product matrix of the position vector p_FQ (expressed in F) such that the cross product with another vector a can be obtained as px.cross(a) = px * a. The cross product matrix px is skew-symmetric. The square of the cross product matrix is a symmetric matrix with non-negative diagonals and obeys the triangle inequality. Matrix px² can be used to compute the triple vector product as -p x (p x a) = -p.cross(p.cross(a)) = px² * a.

◆ ReExpress()

UnitInertia<T> ReExpress ( const math::RotationMatrix< T > &  R_AE) const

Given this unit inertia G_BP_E of a body B about a point P and expressed in frame E, this method computes the same unit inertia re-expressed in another frame A as G_BP_A = R_AE * G_BP_E * (R_AE)ᵀ.

Parameters
[in]R_AERotationMatrix relating frames A and E.
Return values
G_BP_AThe same unit inertia for body B about point P but now re-expressed in frame A.

◆ ReExpressInPlace()

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

Re-express a unit inertia in a different frame, performing the operation in place and modifying the original object.

See also
ReExpress() for details.

◆ SetFromRotationalInertia()

UnitInertia<T>& SetFromRotationalInertia ( const RotationalInertia< T > &  I,
const T &  mass 
)

Sets this unit inertia from a generally non-unit inertia I corresponding to a body with a given mass.

Note
In Debug builds, this operation aborts if the provided mass is not strictly positive.

◆ ShiftFromCenterOfMass()

UnitInertia<T> ShiftFromCenterOfMass ( const Vector3< T > &  p_BcmQ_E) const

Shifts this central unit inertia to a different point, and returns the result.

See ShiftFromCenterOfMassInPlace() for details.

Parameters
[in]p_BcmQ_EA vector from the body's centroid Bcm to point Q expressed in the same frame E in which this inertia is expressed.
Return values
G_BQ_EThis same unit inertia taken about a point Q instead of the centroid Bcm.

◆ ShiftFromCenterOfMassInPlace()

void ShiftFromCenterOfMassInPlace ( const Vector3< T > &  p_BcmQ_E)

For a central unit inertia G_Bcm_E computed about a body's center of mass (or centroid) Bcm and expressed in a frame E, this method shifts this inertia using the parallel axis theorem to be computed about a point Q.

This operation is performed in place, modifying the original object which is no longer a central inertia. On return, this is modified to be taken about point Q so can be written as G_BQ_E.

Parameters
[in]p_BcmQ_EA vector from the body's centroid Bcm to point Q expressed in the same frame E in which this inertia is expressed.

◆ ShiftToCenterOfMass()

UnitInertia<T> ShiftToCenterOfMass ( const Vector3< T > &  p_QBcm_E) const

For the unit inertia G_BQ_E of a body or composite body B computed about a point Q and expressed in a frame E, this method shifts this inertia using the parallel axis theorem to be computed about the center of mass Bcm of B.

See ShiftToCenterOfMassInPlace() for details.

Parameters
[in]p_QBcm_EA position vector from the about point Q to the body's centroid Bcm expressed in the same frame E in which this inertia is expressed.
Return values
G_Bcm_EThis same unit which has now been taken about point Bcm so that it can be written as G_BBcm_E, or G_Bcm_E.
Warning
This operation could result in a non-physical rotational inertia. Use with care. See ShiftToCenterOfMassInPlace() for details.

◆ ShiftToCenterOfMassInPlace()

void ShiftToCenterOfMassInPlace ( const Vector3< T > &  p_QBcm_E)

For the unit inertia G_BQ_E of a body or composite body B computed about a point Q and expressed in a frame E, this method shifts this inertia using the parallel axis theorem to be computed about the center of mass Bcm of B.

This operation is performed in place, modifying the original object. On return, this is modified to be taken about point Bcm so can be written as G_BBcm_E, or G_Bcm_E.

Parameters
[in]p_QBcm_EA position vector from the about point Q to the body's centroid Bcm expressed in the same frame E in which this inertia is expressed.
Warning
This operation could result in a non-physical rotational inertia. The shifted inertia is obtained by subtracting the point mass unit inertia of point Bcm about point Q as: G_Bcm_E = G_BQ_E - G_BcmQ_E = G_BQ_E - px_QBcm_E² Therefore the resulting inertia could have negative moments of inertia if the unit inertia of the unit mass at point Bcm is larger than G_BQ_E. Use with care.

◆ SolidBox()

static UnitInertia<T> SolidBox ( const T &  Lx,
const T &  Ly,
const T &  Lz 
)
static

Computes the unit inertia for a unit-mass solid box of uniform density taken about its geometric center.

If one length is zero the inertia corresponds to that of a thin rectangular sheet. If two lengths are zero the inertia corresponds to that of a thin rod in the remaining direction.

Parameters
[in]LxThe length of the box edge in the principal x-axis.
[in]LyThe length of the box edge in the principal y-axis.
[in]LzThe length of the box edge in the principal z-axis.
Exceptions
std::exceptionif any of Lx, Ly, Lz are negative.

◆ SolidCapsule()

static UnitInertia<T> SolidCapsule ( const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a unit inertia for a uniform density solid capsule B about its center of mass Bcm (which is coincident with B's geometric center Bo).

Parameters
[in]radiusradius of the cylinder/half-sphere parts of the capsule.
[in]lengthlength of cylindrical part of the capsule.
[in]unit_vectorunit vector defining the axial direction of the cylindrical part of the capsule, expressed in a frame E.
Return values
G_BBcm_EB's unit inertia about Bcm expressed in the same frame E as the unit_vector is expressed.
Note
B's unit inertia about Bcm is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bcm and is perpendicular to unit_vector.
Exceptions
std::exceptionif radius or length is negative or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.

◆ SolidCube()

static UnitInertia<T> SolidCube ( const T &  L)
static

Computes the unit inertia for a unit-mass solid cube (a box with equal-sized sides) of uniform density taken about its geometric center.

Parameters
[in]LThe length of each of the cube's sides.

◆ SolidCylinder()

static UnitInertia<T> SolidCylinder ( const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a unit inertia for a uniform density solid cylinder B about its center of mass Bcm (which is coincident with B's geometric center Bo).

Parameters
[in]radiusradius of the cylinder (meters).
[in]lengthlength of cylinder in unit_vector direction (meters).
[in]unit_vectorunit vector defining the axial direction of the cylinder, expressed in a frame E.
Return values
G_BBcm_EB's unit inertia about Bcm expressed in the same frame E as the unit_vector is expressed.
Note
B's unit inertia about Bcm is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bcm and is perpendicular to unit_vector.
Exceptions
std::exceptionif radius or length is negative or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
See also
SolidCylinderAboutEnd() to calculate G_BBp_E, B's unit inertia about point Bp (Bp is at the center of one of the cylinder's circular ends).

◆ SolidCylinderAboutEnd()

static UnitInertia<T> SolidCylinderAboutEnd ( const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a unit inertia for a uniform-density solid cylinder B about an end-point Bp of the cylinder's axis (see below for more about Bp).

Parameters
[in]radiusradius of cylinder (meters).
[in]lengthlength of cylinder in unit_vector direction (meters).
[in]unit_vectorunit vector parallel to the axis of the cylinder and directed from Bp to Bcm (B's center of mass), expressed in a frame E.
Return values
G_BBp_EB's unit inertia about Bp expressed in the same frame E as the unit_vector is expressed.
Note
The position from Bp to Bcm is p_BpBcm = length / 2 * unit_vector.
B's unit inertia about Bp is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bp and is perpendicular to unit_vector.
Exceptions
std::exceptionif radius or length is negative or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.

◆ SolidEllipsoid()

static UnitInertia<T> SolidEllipsoid ( const T &  a,
const T &  b,
const T &  c 
)
static

Computes the unit inertia for a unit-mass solid ellipsoid of uniform density taken about its center.

The lengths of the semi-axes of the ellipsoid in the principal x,y,z-axes are a, b, and c respectively.

◆ SolidSphere()

static UnitInertia<T> SolidSphere ( const T &  r)
static

Computes the unit inertia for a unit-mass solid sphere of uniform density and radius r taken about its center.

◆ SolidTetrahedronAboutPoint()

static UnitInertia<T> SolidTetrahedronAboutPoint ( const Vector3< T > &  p0,
const Vector3< T > &  p1,
const Vector3< T > &  p2,
const Vector3< T > &  p3 
)
static

Creates a unit inertia for a unit-mass uniform density solid tetrahedron B about a point A, from which position vectors to B's 4 vertices B0, B1, B2, B3 are measured (position vectors are all expressed in a common frame E).

Parameters
[in]densitymass per volume (kg/m³).
[in]p0position vector p_AB0_E from point A to B0, expressed in E.
[in]p1position vector p_AB1_E from point A to B1, expressed in E.
[in]p2position vector p_AB2_E from point A to B2, expressed in E.
[in]p3position vector p_AB3_E from point A to B3, expressed in E.
Return values
G_BA_EB's unit inertia about point A, expressed in E.
See also
SolidTetrahedronAboutVertex() to efficiently calculate a unit inertia about a vertex of B.

◆ SolidTetrahedronAboutVertex()

static UnitInertia<T> SolidTetrahedronAboutVertex ( const Vector3< T > &  p1,
const Vector3< T > &  p2,
const Vector3< T > &  p3 
)
static

(Advanced) Creates a unit inertia for a unit-mass uniform density solid tetrahedron B about its vertex B0, from which position vectors to B's other 3 vertices B1, B2, B3 are measured (vectors are all expressed in a common frame E).

Parameters
[in]p1position vector p_B0B1_E from B0 to B1, expressed in E.
[in]p2position vector p_B0B2_E from B0 to B2, expressed in E.
[in]p3position vector p_B0B3_E from B0 to B3, expressed in E.
Return values
G_BB0_EB's unit inertia about its vertex B0, expressed in E.
See also
SolidTetrahedronAboutPoint() to calculate a unit inertia about an arbitrary point.

◆ StraightLine()

static UnitInertia<T> StraightLine ( const T &  moment_perpendicular,
const Vector3< T > &  unit_vector 
)
static

Creates a unit inertia for a straight line segment B about a point Bp on the line segment.

Parameters
[in]moment_perpendicularUnit moment of inertia about any axis that passes through Bp and is perpendicular to the line segment.
[in]unit_vectorunit vector defining the line segment's direction, expressed in a frame E.
Return values
G_BBp_EB's unit inertia about Bp, expressed in the same frame E that the unit_vector is expressed.
Note
B's unit inertia about Bp is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bp and is perpendicular to unit_vector.
Exceptions
std::exceptionif moment_perpendicular is not positive or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
Note
B's axial moment of inertia (along the line segment) is zero.
See also
ThinRod() is an example of an object that is axially symmetric and that has a zero moment of inertia about Bp in the unit_vector direction.

◆ ThinRod()

static UnitInertia<T> ThinRod ( const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a unit inertia for a uniform density thin rod B about its center of mass Bcm (which is coincident with B's geometric center Bo).

Parameters
[in]lengthlength of rod in unit_vector direction (meters).
[in]unit_vectorunit vector defining the rod's axial direction, expressed in a frame E.
Return values
G_BBcm_EB's unit inertia about Bcm expressed in the same frame E that the unit_vector is expressed.
Note
B's unit inertia about Bcm is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bcm and is perpendicular to unit_vector.
Exceptions
std::exceptionif length is not positive or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
Note
B's axial moment of inertia (along the rod) is zero..

◆ TriaxiallySymmetric()

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

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

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

See also
UnitInertia::SolidSphere() and UnitInertia::SolidCube() for examples.

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