Drake
UnitInertia< T > Class Template Reference

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

#include <multibody/multibody_tree/unit_inertia.h>

Inheritance diagram for UnitInertia< T >:
[legend]
Collaboration diagram for UnitInertia< T >:
[legend]

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...
 
UnitInertia< T > & ReExpressInPlace (const Matrix3< T > &R_FE)
 Re-express a unit inertia in a different frame, performing the operation in place and modifying the original object. More...
 
UnitInertia< T > ReExpress (const Matrix3< T > &R_FE) 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 F as G_BP_F = R_FE * G_BP_E * (R_FE)ᵀ. More...
 
UnitInertia< T > & ShiftFromCenterOfMassInPlace (const Vector3< T > &p_BcQ_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_BcQ_E) const __attribute__((warn_unused_result))
 Shifts this central unit inertia to a different point, and returns the result. More...
 
UnitInertia< T > & 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 __attribute__((warn_unused_result))
 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...
 
bool IsNearlyEqualTo (const RotationalInertia &other, double precision) const
 Compares this rotational inertia to other rotional 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...
 
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...
 
bool IsNaN () const
 Returns true if any moment/product in this rotational inertia is NaN. 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
 This method takes this rotational inertia about-point P, expressed-in- frame E, and computes its principal moments of inertia about-point P, but expressed-in a frame aligned with the principal axes. More...
 
bool CouldBePhysicallyValid () const
 Performs several necessary checks to verify whether this rotational inertia could be physically valid, including: More...
 
RotationalInertia< T > & ReExpressInPlace (const Matrix3< T > &R_AE)
 Re-expresses this rotational inertia I_BP_E to I_BP_A. More...
 
RotationalInertia< T > ReExpress (const Matrix3< T > &R_AE) const __attribute__((warn_unused_result))
 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
 
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 __attribute__((warn_unused_result))
 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 __attribute__((warn_unused_result))
 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 __attribute__((warn_unused_result))
 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 > 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 &r, const T &L)
 Computes the unit inertia for a unit-mass cylinder of uniform density oriented along the z-axis computed about its center. More...
 
static UnitInertia< T > SolidCylinderAboutEnd (const T &r, const T &L)
 Computes the unit inertia for a unit-mass cylinder of uniform density oriented along the z-axis computed about a point at the center of its base. More...
 
static UnitInertia< T > AxiallySymmetric (const T &J, const T &K, const Vector3< T > &b_E)
 Returns the unit inertia for a unit-mass body B for which there exists a line L passing through the body's center of mass Bcm having the property that the body's moment of inertia about all lines perpendicular to L are equal. More...
 
static UnitInertia< T > StraightLine (const T &K, const Vector3< T > &b_E)
 Computes the unit inertia for a body B of unit-mass uniformly distributed along a straight, finite, line L with direction b_E and with moment of inertia K about any axis perpendicular to this line. More...
 
static UnitInertia< T > ThinRod (const T &L, const Vector3< T > &b_E)
 Computes the unit inertia for a unit mass rod B of length L, about its center of mass, with its mass uniformly distributed along a line parallel to vector b_E. 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...
 

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

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.
Template Parameters
TThe underlying scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T's are provided:

  • double
  • AutoDiffXd

They are already available to link against in the containing library.

Constructor & Destructor Documentation

UnitInertia ( const UnitInertia< T > &  )
default
UnitInertia ( UnitInertia< T > &&  )
default
UnitInertia ( )
inline

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

Here is the caller graph for this function:

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

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::logic_error if unit inertia constructed from these arguments violates RotationalInertia::CouldBePhysicallyValid().

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

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

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

UnitInertia ( const RotationalInertia< T > &  I)
inlineexplicit

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. It is the responsibility of the user to pass a valid unit inertia.

Member Function Documentation

static UnitInertia<T> AxiallySymmetric ( const T &  J,
const T &  K,
const Vector3< T > &  b_E 
)
inlinestatic

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

Examples of bodies with an axially symmetric inertia include axisymmetric objects such as cylinders and cones. Other commonly occurring geometries with this property are, for instance, propellers with 3+ evenly spaced blades. Given a unit vector b defining the symmetry line L, the moment of inertia J about this line L and the moment of inertia K about any line perpendicular to L, the axially symmetric unit inertia G is computed as:

  G = K * Id + (J - K) * b ⊗ b

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

This method aborts if:

  • J is negative. J can be zero.
  • K is negative. K can be zero.
  • J ≤ 2 * K, this corresponds to the triangle inequality, see CouldBePhysicallyValid().
  • b_E is the zero vector. That is if ‖b_E‖₂ ≤ ε, where ε is the machine epsilon.
Note
J is a principal moment of inertia with principal axis equal to b. K is a principal moment with multiplicity of two. Any two axes perpendicular to b are principal axes with principal moment K.
Parameters
[in]JUnit inertia about axis b.
[in]KUnit inertia about any axis perpendicular to b.
[in]b_EVector defining the symmetry axis, expressed in a frame E. b_E can have a norm different from one; however, it will be normalized before using it. Therefore its norm is ignored and only its direction is used.
Return values
G_Bcm_EAn axially symmetric unit inertia about body B's center of mass, expressed in the same frame E as the input unit vector b_E.

Here is the caller graph for this function:

UnitInertia<Scalar> cast ( ) const
inline

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.
static UnitInertia<T> HollowSphere ( const T &  r)
inlinestatic

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.

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

Here is the caller graph for this function:

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

Here is the caller graph for this function:

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

Here is the caller graph for this function:

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

Here is the caller graph for this function:

UnitInertia& operator= ( UnitInertia< T > &&  )
default
UnitInertia& operator= ( const UnitInertia< T > &  )
default
static UnitInertia<T> PointMass ( const Vector3< T > &  p_FQ)
inlinestatic

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.

Here is the caller graph for this function:

UnitInertia<T> ReExpress ( const Matrix3< T > &  R_FE) const
inline

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 F as G_BP_F = R_FE * G_BP_E * (R_FE)ᵀ.

Parameters
[in]R_FERotation matrix from the basis of frame E to the basis of frame F.
Return values
G_BP_FThe same unit inertia for body B about point P but now re-expressed in frameF.
Warning
This method does not check whether the input matrix R_FE represents a valid rotation or not. It is the responsibility of users to provide valid rotation matrices.
UnitInertia<T>& ReExpressInPlace ( const Matrix3< T > &  R_FE)
inline

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

See also
ReExpress() for details.
UnitInertia<T>& SetFromRotationalInertia ( const RotationalInertia< T > &  I,
const T &  mass 
)
inline

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.

Here is the caller graph for this function:

UnitInertia<T> ShiftFromCenterOfMass ( const Vector3< T > &  p_BcQ_E) const
inline

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.
UnitInertia<T>& ShiftFromCenterOfMassInPlace ( const Vector3< T > &  p_BcQ_E)
inline

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.

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.
Returns
A reference to this unit inertia, which has now been taken about point Q so can be written as G_BQ_E.

Here is the caller graph for this function:

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

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.
UnitInertia<T>& ShiftToCenterOfMassInPlace ( const Vector3< T > &  p_QBcm_E)
inline

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.

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.
Returns
A reference to this unit inertia, which has now been taken about point Bcm so can be written as G_BBcm_E, or G_Bcm_E.
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.

Here is the caller graph for this function:

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

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.

Here is the caller graph for this function:

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

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.
static UnitInertia<T> SolidCylinder ( const T &  r,
const T &  L 
)
inlinestatic

Computes the unit inertia for a unit-mass cylinder of uniform density oriented along the z-axis computed about its center.

Parameters
[in]rThe radius of the cylinder.
[in]LThe length of the cylinder.
static UnitInertia<T> SolidCylinderAboutEnd ( const T &  r,
const T &  L 
)
inlinestatic

Computes the unit inertia for a unit-mass cylinder of uniform density oriented along the z-axis computed about a point at the center of its base.

Parameters
[in]rThe radius of the cylinder.
[in]LThe length of the cylinder.
static UnitInertia<T> SolidSphere ( const T &  r)
inlinestatic

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

static UnitInertia<T> StraightLine ( const T &  K,
const Vector3< T > &  b_E 
)
inlinestatic

Computes the unit inertia for a body B of unit-mass uniformly distributed along a straight, finite, line L with direction b_E and with moment of inertia K about any axis perpendicular to this line.

Since the mass of the body is uniformly distributed on this line L, its center of mass is located right at the center. As an example, consider the inertia of a thin rod for which its transversal dimensions can be neglected, see ThinRod().

This method aborts if K is not positive.

Note
This is the particular case for an axially symmetric unit inertia with zero moment about its axis, see AxiallySymmetric().
Parameters
[in]KUnit inertia about any axis perpendicular to the line.
[in]b_EVector defining the direction of the line, expressed in a frame E. b_E can have a norm different from one. Its norm is ignored and only its direction is needed.
Return values
G_Bcm_EThe unit inertia for a body B of unit mass uniformly distributed along a straight line L, about its center of mass Bcm which is located at the center of the line, expressed in the same frame E as the input unit vector b_E.

Here is the caller graph for this function:

static UnitInertia<T> ThinRod ( const T &  L,
const Vector3< T > &  b_E 
)
inlinestatic

Computes the unit inertia for a unit mass rod B of length L, about its center of mass, with its mass uniformly distributed along a line parallel to vector b_E.

This method aborts if L is not positive.

Parameters
[in]LThe length of the rod. It must be positive.
[in]b_EVector defining the axis of the rod, expressed in a frame E. b_E can have a norm different from one. Its norm is ignored and only its direction is needed.
Return values
G_Bcm_EThe unit inertia of the rod B about its center of mass Bcm, expressed in the same frame E as the input unit vector b_E.
static UnitInertia<T> TriaxiallySymmetric ( const T &  I_triaxial)
inlinestatic

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::logic_error if I_triaxial is negative/NaN.

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

Here is the caller graph for this function:


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