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

Detailed Description

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

This class represents the physical concept of a Spatial Inertia.

A spatial inertia (or spatial mass matrix) encapsulates the mass, center of mass, and rotational inertia of the mass distribution of a body or composite body S, where with "composite body" we mean a collection of bodies welded together containing at least one body (throughout this documentation "body" is many times used instead of "composite body" but the same concepts apply to a collection of bodies as well.) A spatial inertia is an element of ℝ⁶ˣ⁶ that is symmetric, and positive semi-definite. It logically consists of 3x3 sub-matrices arranged like so, [Jain 2010]:

             Spatial mass matrix
          ------------ ------------
       0 |            |            |
       1 |    I_SP    | m p_PScm×  |
       2 |            |            |
          ------------ ------------
       3 |            |            |
       4 | -m p_PScm× |     m Id   |
       5 |            |            |
          ------------ ------------
               Symbol: M

where, with the monogram notation described in Spatial Mass Matrix (Spatial Inertia), I_SP is the rotational inertia of body or composite body S computed about a point P, m is the mass of this composite body, p_PScm is the position vector from point P to the center of mass Scm of the composite body S with p_PScm× denoting its skew-symmetric cross product matrix (defined such that a× b = a.cross(b)), and Id is the identity matrix in ℝ³ˣ³. See Section 2.1, p. 17 of [Jain 2010]. The logical arrangement as shown above is chosen to be consistent with our logical arrangement for spatial vectors as documented in Spatial Algebra for which the rotational component comes first followed by the translational component.

In typeset material we use the symbol \( [M^{S/P}]_E \) to represent the spatial inertia of a body or composite body S about point P, expressed in frame E. For this inertia, the monogram notation reads M_SP_E. If the point P is fixed to a body B, we write that point as \( B_P \) which appears in code and comments as Bp. So if the body or composite body is B and the about point is Bp, the monogram notation reads M_BBp_E, which can be abbreviated to M_Bp_E since the about point Bp also identifies the body. Common cases are that the about point is the origin Bo of the body, or it's the center of mass Bcm for which the rotational inertia in monogram notation would read as I_Bo_E and I_Bcm_E, respectively. Given M_BP_E ( \([M^{B/P}]_E\)), the rotational inertia of this spatial inertia is I_BP_E ( \([I^{B/P}]_E\)) and the position vector of the center of mass measured from point P and expressed in E is p_PBcm_E ( \([^Pp^{B_{cm}}]_E\)).

Note
This class does not implement any mechanism to track the frame E in which a spatial inertia is expressed or about what point is computed. Methods and operators on this class have no means to determine frame consistency through operations. It is therefore the responsibility of users of this class to keep track of frames in which operations are performed. We suggest doing that using disciplined notation, as described above.
Several methods in this class throw a std::exception for invalid rotational inertia operations in debug releases only. This provides speed in a release build while facilitating debugging in debug builds. In addition, these validity tests are only performed for scalar types for which drake::scalar_predicate<T>::is_bool is true. For instance, validity checks are not performed when T is symbolic::Expression.
The methods of this class satisfy the "basic exception guarantee": if an exception is thrown, the program will still be in a valid state. Specifically, no resources are leaked, and all objects' invariants are intact. Be aware that SpatialInertia objects may contain invalid inertia data in cases where input checking is skipped.
See also
https://en.cppreference.com/w/cpp/language/exceptions
To create a spatial inertia of a mesh, see CalcSpatialInertia(const geometry::TriangleSurfaceMesh<double>& mesh, double density).
To create spatial inertia from most of geometry::Shape, see CalcSpatialInertia(const geometry::Shape& shape, double density).
To create spatial inertia for a set of bodies, see MultibodyPlant::CalcSpatialInertia().
  • [Jain 2010] Jain, A., 2010. Robot and multibody dynamics: analysis and algorithms. Springer Science & Business Media.
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 SpatialInertia ()
 Default SpatialInertia constructor initializes mass, center of mass and rotational inertia to invalid NaN's for a quick detection of uninitialized values. More...
 
 SpatialInertia (const T &mass, const Vector3< T > &p_PScm_E, const UnitInertia< T > &G_SP_E, const bool skip_validity_check=false)
 Constructs a spatial inertia for a physical body or composite body S about a point P from a given mass, center of mass and rotational inertia. More...
 
template<typename Scalar >
SpatialInertia< Scalar > cast () const
 Returns a new SpatialInertia object templated on Scalar initialized from the value of this spatial inertia. More...
 
const T & get_mass () const
 Get a constant reference to the mass of this spatial inertia. More...
 
const Vector3< T > & get_com () const
 Get a constant reference to the position vector p_PScm_E from the about point P to the center of mass Scm of the body or composite body S, expressed in frame E. More...
 
Vector3< T > CalcComMoment () const
 Computes the center of mass moment vector mass * p_PScm_E given the position vector p_PScm_E from the about point P to the center of mass Scm of the body or composite body S, expressed in frame E. More...
 
const UnitInertia< T > & get_unit_inertia () const
 Get a constant reference to the unit inertia G_SP_E of this spatial inertia, computed about point P and expressed in frame E. More...
 
RotationalInertia< T > CalcRotationalInertia () const
 Computes the rotational inertia I_SP_E = mass * G_SP_E of this spatial inertia, computed about point P and expressed in frame E. More...
 
boolean< T > IsNaN () const
 Returns true if any of the elements in this spatial inertia is NaN and false otherwise. More...
 
boolean< T > IsPhysicallyValid () const
 Performs a number of checks to verify that this is a physically valid spatial inertia. More...
 
Matrix6< T > CopyToFullMatrix6 () const
 Copy to a full 6x6 matrix representation. More...
 
void SetNaN ()
 Sets this spatial inertia to have NaN entries. More...
 
SpatialInertia< T > & operator+= (const SpatialInertia< T > &M_BP_E)
 Adds in a spatial inertia to this spatial inertia. More...
 
SpatialInertia< T > & ReExpressInPlace (const math::RotationMatrix< T > &R_AE)
 Given this spatial inertia M_SP_E for some body or composite body S, taken about a point P and expressed in frame E, this method computes the same inertia re-expressed in another frame A. More...
 
SpatialInertia< T > ReExpress (const math::RotationMatrix< T > &R_AE) const
 Given this spatial inertia M_SP_E for some body or composite body S, taken about a point P and expressed in frame E, this method computes the same inertia re-expressed in another frame A. More...
 
SpatialInertia< T > & ShiftInPlace (const Vector3< T > &p_PQ_E)
 Given this spatial inertia M_SP_E for some body or composite body S, computed about point P, and expressed in frame E, this method uses the Parallel Axis Theorem for spatial inertias to compute the same spatial inertia about a new point Q. More...
 
SpatialInertia< T > Shift (const Vector3< T > &p_PQ_E) const
 Given this spatial inertia M_SP_E for some body or composite body S, computed about point P, and expressed in frame E, this method uses the Parallel Axis Theorem for spatial inertias to compute the same spatial inertia about a new point Q. More...
 
SpatialForce< T > operator * (const SpatialAcceleration< T > &A_WB_E) const
 Multiplies this spatial inertia M_Bo_E of a body B about its frame origin Bo by the spatial acceleration of the body frame B in a frame W. More...
 
SpatialMomentum< T > operator * (const SpatialVelocity< T > &V_WBp_E) const
 Multiplies this spatial inertia M_BP_E of a body B about a point P by the spatial velocity V_WBp, in a frame W, of the body frame B shifted to point P. More...
 
template<typename Derived >
Eigen::Matrix< T, 6, Derived::ColsAtCompileTime, 0, 6, Derived::MaxColsAtCompileTime > operator * (const Eigen::MatrixBase< Derived > &Mmatrix) const
 Multiplies this spatial inertia by a set of spatial vectors in M⁶ stored as columns of input matrix Mmatrix. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 SpatialInertia (const SpatialInertia &)=default
 
SpatialInertiaoperator= (const SpatialInertia &)=default
 
 SpatialInertia (SpatialInertia &&)=default
 
SpatialInertiaoperator= (SpatialInertia &&)=default
 
Spatial inertia equivalent shapes

Calculates principal semi-diameters (half-lengths), principal axes orientations, and the position of a uniform-density object whose spatial inertia is equal to this spatial inertia. These functions are useful for visualization or physical interpretation of the geometric extents of this spatial inertia for a given shape. These functions return 3 principal semi-diameters (half-lengths) [a b c] sorted in descending order (a ≥ b ≥ c) which are measured from Scm (the center of mass of this spatial inertia). They also return the pose of the uniform density object that represents this spatial inertia.

Example: Consider an oddly-shaped rigid body B with a known spatial inertia M_BBo_B about B's origin Bo, expressed in frame B. These functions return an easily visualized simple shape whose spatial inertial is equal to M_BBo_B. The simple shape is defined by a frame A with origin Ao at Bcm (B's center of mass), has principal dimensions [a b c], and has unit vectors Ax, Ay, Az parallel to the simple shape's principal directions. When the simple shape is a uniform-density solid ellipsoid, proceed as follows to form [a b c], the rotation matrix R_BA describing Ax, Ay, Az, and the position vector p_BoAo_B from Bo to Ao (ellipsoid center of mass).

const SpatialInertia<double>& M_BBo_B = B.default_spatial_inertia();
auto [abc, X_BA] =
M_BBo_B.CalcPrincipalSemiDiametersAndPoseForSolidEllipsoid();
Exceptions
std::exceptionif the elements of this spatial inertia cannot be converted to a real finite double. For example, an exception is thrown if this contains an erroneous NaN or if scalar type T is symbolic.
See also
RotationalInertia::CalcPrincipalMomentsAndAxesOfInertia() to form principal moments of inertia and their associated principal directions.
std::pair< Vector3< double >, drake::math::RigidTransform< double > > CalcPrincipalSemiDiametersAndPoseForSolidEllipsoid () const
 Returns 3 principal semi-diameters [lmax lmed lmin] sorted in descending order (lmax ≥ lmed ≥ lmin), orientation, and position of a solid ellipsoid whose spatial inertia is equal to this spatial inertia. More...
 
std::pair< Vector3< double >, drake::math::RigidTransform< double > > CalcPrincipalHalfLengthsAndPoseForSolidBox () const
 Returns three ½-lengths [lmax lmed lmin] sorted in descending order (lmax ≥ lmed ≥ lmin), orientation, and position of a solid box whose spatial inertia is equal to this spatial inertia. More...
 
std::pair< Vector3< double >, drake::math::RigidTransform< double > > CalcPrincipalHalfLengthsAndPoseForMinimumBoundingBox () const
 Returns three ½-lengths [lmax lmed lmin] sorted in descending order (lmax ≥ lmed ≥ lmin), orientation, and position of a box whose mass is concentrated in 8 particles at the box's corners and whose spatial inertia is equal to this spatial inertia. More...
 
CalcMinimumPhysicalLength () const
 Returns the minimum possible length for the physical extent of the massive object that underlies this spatial inertia. More...
 

Static Public Member Functions

static SpatialInertia< T > MakeFromCentralInertia (const T &mass, const Vector3< T > &p_PScm_E, const RotationalInertia< T > &I_SScm_E)
 Creates a spatial inertia for a physical body or composite body S about a point P from a given mass, center of mass, and central rotational inertia. More...
 
static SpatialInertia< T > MakeUnitary ()
 (Internal use only) Creates a spatial inertia whose mass is 1, position vector to center of mass is zero, and whose rotational inertia has moments of inertia of 1 and products of inertia of 0. More...
 
static SpatialInertia< T > PointMass (const T &mass, const Vector3< T > &position)
 Creates the spatial inertia for a particle Q of mass m about a point P. More...
 
static SpatialInertia< T > SolidBoxWithDensity (const T &density, const T &lx, const T &ly, const T &lz)
 Creates a spatial inertia for a uniform density solid box B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidBoxWithMass (const T &mass, const T &lx, const T &ly, const T &lz)
 Creates a spatial inertia for a uniform density solid box B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidCubeWithDensity (const T &density, const T &length)
 Creates a spatial inertia for a uniform density solid cube B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidCubeWithMass (const T &mass, const T &length)
 Creates a spatial inertia for a uniform density solid cube B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidCapsuleWithDensity (const T &density, const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial inertia for a uniform density solid capsule B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidCapsuleWithMass (const T &mass, const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial inertia for a uniform density solid capsule B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidCylinderWithDensity (const T &density, const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial inertia for a uniform density solid cylinder B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidCylinderWithMass (const T &mass, const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial inertia for a uniform density solid cylinder B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidCylinderWithDensityAboutEnd (const T &density, const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial 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 SpatialInertia< T > SolidCylinderWithMassAboutEnd (const T &mass, const T &radius, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial 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 SpatialInertia< T > ThinRodWithMass (const T &mass, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial inertia for a uniform-density thin rod B about its center of mass Bcm. More...
 
static SpatialInertia< T > ThinRodWithMassAboutEnd (const T &mass, const T &length, const Vector3< T > &unit_vector)
 Creates a spatial inertia for a uniform-density thin rod B about one of its ends. More...
 
static SpatialInertia< T > SolidEllipsoidWithDensity (const T &density, const T &a, const T &b, const T &c)
 Creates a spatial inertia for a uniform density solid ellipsoid B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidEllipsoidWithMass (const T &mass, const T &a, const T &b, const T &c)
 Creates a spatial inertia for a uniform density solid ellipsoid B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidSphereWithDensity (const T &density, const T &radius)
 Creates a spatial inertia for a uniform density solid sphere B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidSphereWithMass (const T &mass, const T &radius)
 Creates a spatial inertia for a uniform density solid sphere B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > HollowSphereWithDensity (const T &area_density, const T &radius)
 Creates a spatial inertia for a uniform density thin hollow sphere B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > HollowSphereWithMass (const T &mass, const T &radius)
 Creates a spatial inertia for a uniform density hollow sphere B about its geometric center Bo (which is coincident with B's center of mass Bcm). More...
 
static SpatialInertia< T > SolidTetrahedronAboutPointWithDensity (const T &density, const Vector3< T > &p0, const Vector3< T > &p1, const Vector3< T > &p2, const Vector3< T > &p3)
 Creates a spatial inertia for a 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 SpatialInertia< T > SolidTetrahedronAboutVertexWithDensity (const T &density, const Vector3< T > &p1, const Vector3< T > &p2, const Vector3< T > &p3)
 (Advanced) Creates a spatial inertia for a uniform density solid tetrahedron B about its vertex B0, from which position vectors to B's other 3 vertices B1, B2, B3 are measured (position vectors are all expressed in a common frame E). More...
 

Related Functions

(Note that these are not member functions.)

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

Constructor & Destructor Documentation

◆ SpatialInertia() [1/4]

SpatialInertia ( const SpatialInertia< T > &  )
default

◆ SpatialInertia() [2/4]

SpatialInertia ( SpatialInertia< T > &&  )
default

◆ SpatialInertia() [3/4]

Default SpatialInertia constructor initializes mass, center of mass and rotational inertia to invalid NaN's for a quick detection of uninitialized values.

◆ SpatialInertia() [4/4]

SpatialInertia ( const T &  mass,
const Vector3< T > &  p_PScm_E,
const UnitInertia< T > &  G_SP_E,
const bool  skip_validity_check = false 
)

Constructs a spatial inertia for a physical body or composite body S about a point P from a given mass, center of mass and rotational inertia.

The center of mass is specified by the position vector p_PScm_E from point P to the center of mass point Scm, expressed in a frame E. The rotational inertia is provided as the UnitInertia G_SP_E of the body or composite body S computed about point P and expressed in frame E.

Note
The third argument of this constructor is unusual in that it is an UnitInertia (not a traditional RotationalInertia) and its inertia is about the arbitrary point P (not Scm – S's center of mass).
See also
MakeFromCentralInertia a factory method with traditional utility.

This constructor checks for the physical validity of the resulting SpatialInertia with IsPhysicallyValid() and throws a std::runtime_error exception in the event the provided input parameters lead to non-physically viable spatial inertia. Since this check has non-negligable runtime costs, it can be disabled by setting the optional argument skip_validity_check to true.

Parameters
[in]massThe mass of the body or composite body S.
[in]p_PScm_EThe position vector from point P to the center of mass of body or composite body S expressed in frame E.
[in]G_SP_EUnitInertia of the body or composite body S computed about origin point P and expressed in frame E.
[in]skip_validity_checkIf true, skips the validity check described above. Defaults to false.

Member Function Documentation

◆ CalcComMoment()

Vector3<T> CalcComMoment ( ) const

Computes the center of mass moment vector mass * p_PScm_E given the position vector p_PScm_E from the about point P to the center of mass Scm of the body or composite body S, expressed in frame E.

See the documentation of this class for details.

◆ CalcMinimumPhysicalLength()

T CalcMinimumPhysicalLength ( ) const

Returns the minimum possible length for the physical extent of the massive object that underlies this spatial inertia.

In other words, the underlying physical object must have at least two particles whose distance between each other is greater than or equal to the minimum possible length.

Note
The minimum possible length is equal to the space-diagonal of the minimum bounding box for this spatial inertia, which happens to be equal to √(2 * trace of the central unit inertia associated with this).
Minimum possible length can be used to detect erroneous inertias associated with absurdly large objects or to detect errors when the minimum possible length is larger than the real physical geometry that underlies this spatial inertia (maybe due to inertia conversion errors, e.g., factor of 10⁷ from kg m² to g cm² or 10⁹ from kg m² to g mm²). To assess whether the minimum possible length is reasonable, it helps to have comparable sizes, e.g., the world's largest aircraft carrier has a space-diagonal ≈ 355 m (length ≈ 337 m, width ≈ 78 m, height ≈ 76 m), the largest land vehicle (Bagger bucket-wheel excavator) is ≈ 224 m long, the largest human object in space (International Space Station) is 109 m long and 75 m wide, the USA space shuttle is ≈ 37 m long and can carry a 15.2 m Canadarm, the world's largest humanoid robot (Mononofu) is ≈ 8.5 m tall. Also, minimum possible length can be compared to known physical geometry (e.g., realistic collision geometry, visual geometry, or physical extents associated with body connectivity data and topology), and this comparison can be used to warn that a spatial inertia may be physically impossible (e.g., underlying geometry is smaller than the minimum possible length).

◆ CalcPrincipalHalfLengthsAndPoseForMinimumBoundingBox()

std::pair<Vector3<double>, drake::math::RigidTransform<double> > CalcPrincipalHalfLengthsAndPoseForMinimumBoundingBox ( ) const

Returns three ½-lengths [lmax lmed lmin] sorted in descending order (lmax ≥ lmed ≥ lmin), orientation, and position of a box whose mass is concentrated in 8 particles at the box's corners and whose spatial inertia is equal to this spatial inertia.

The physical geometry of the actual underlying object must be larger than this box, as this box is the minimum bounding box for the actual geometry. See Spatial inertia equivalent shapes for more details.

Exceptions
std::exceptionif the elements of this spatial 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.

◆ CalcPrincipalHalfLengthsAndPoseForSolidBox()

std::pair<Vector3<double>, drake::math::RigidTransform<double> > CalcPrincipalHalfLengthsAndPoseForSolidBox ( ) const

Returns three ½-lengths [lmax lmed lmin] sorted in descending order (lmax ≥ lmed ≥ lmin), orientation, and position of a solid box whose spatial inertia is equal to this spatial inertia.

See Spatial inertia equivalent shapes for more details.

Exceptions
std::exceptionif the elements of this spatial 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.

◆ CalcPrincipalSemiDiametersAndPoseForSolidEllipsoid()

std::pair<Vector3<double>, drake::math::RigidTransform<double> > CalcPrincipalSemiDiametersAndPoseForSolidEllipsoid ( ) const

Returns 3 principal semi-diameters [lmax lmed lmin] sorted in descending order (lmax ≥ lmed ≥ lmin), orientation, and position of a solid ellipsoid whose spatial inertia is equal to this spatial inertia.

See Spatial inertia equivalent shapes for more details.

Exceptions
std::exceptionif the elements of this spatial 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.

◆ CalcRotationalInertia()

RotationalInertia<T> CalcRotationalInertia ( ) const

Computes the rotational inertia I_SP_E = mass * G_SP_E of this spatial inertia, computed about point P and expressed in frame E.

See the documentation of this class for details.

◆ cast()

SpatialInertia<Scalar> cast ( ) const

Returns a new SpatialInertia object templated on Scalar initialized from the value of this spatial inertia.

Template Parameters
ScalarThe scalar type on which the new spatial inertia will be templated.
Note
SpatialInertia<From>::cast<To>() creates a new SpatialInertia<To> from a SpatialInertia<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 objects that underlie this SpatialInertia. For example, Eigen currently allows cast from type double to AutoDiffXd, but not vice-versa.

◆ CopyToFullMatrix6()

Matrix6<T> CopyToFullMatrix6 ( ) const

Copy to a full 6x6 matrix representation.

◆ get_com()

const Vector3<T>& get_com ( ) const

Get a constant reference to the position vector p_PScm_E from the about point P to the center of mass Scm of the body or composite body S, expressed in frame E.

See the documentation of this class for details.

◆ get_mass()

const T& get_mass ( ) const

Get a constant reference to the mass of this spatial inertia.

◆ get_unit_inertia()

const UnitInertia<T>& get_unit_inertia ( ) const

Get a constant reference to the unit inertia G_SP_E of this spatial inertia, computed about point P and expressed in frame E.

See the documentation of this class for details.

◆ HollowSphereWithDensity()

static SpatialInertia<T> HollowSphereWithDensity ( const T &  area_density,
const T &  radius 
)
static

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

Parameters
[in]area_densitymass per unit area (kg/m²).
[in]radiussphere's radius in meters (the hollow sphere is regarded as an infinitesimally thin shell of uniform density).
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B. Since B's rotational inertia is triaxially symmetric, M_BBo_B = M_BBo_E, i.e., M_BBo expressed in frame B is equal to M_BBo expressed in an arbitrary frame E.
Note
B's rotational inertia about Bo is triaxially symmetric, meaning B has an equal moment of inertia about any line passing through Bo.
Exceptions
std::exceptionif area_density or radius is not positive and finite.

◆ HollowSphereWithMass()

static SpatialInertia<T> HollowSphereWithMass ( const T &  mass,
const T &  radius 
)
static

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

Parameters
[in]massmass of the hollow sphere (kg).
[in]radiussphere's radius in meters (the hollow sphere is regarded as an infinitesimally thin shell of uniform density).
Return values
M_BBoB's spatial inertia about Bo. Since B's rotational inertia is triaxially symmetric, M_BBo_B = M_BBo_E, i.e., M_BBo expressed in frame B is equal to M_BBo expressed in an arbitrary frame E.
Note
B's rotational inertia about Bo is triaxially symmetric, meaning B has an equal moment of inertia about any line passing through Bo.
Exceptions
std::exceptionif mass or radius is not positive and finite.

◆ IsNaN()

boolean<T> IsNaN ( ) const

Returns true if any of the elements in this spatial inertia is NaN and false otherwise.

◆ IsPhysicallyValid()

boolean<T> IsPhysicallyValid ( ) const

Performs a number of checks to verify that this is a physically valid spatial inertia.

The checks performed are:

  • No NaN entries.
  • Non-negative mass.
  • Non-negative principal moments about the center of mass.
  • Principal moments about the center of mass must satisfy the triangle inequality:
    • Ixx + Iyy >= Izz
    • Ixx + Izz >= Iyy
    • Iyy + Izz >= Ixx

These are the tests performed by RotationalInertia::CouldBePhysicallyValid() which become a sufficient condition when performed on a rotational inertia about a body's center of mass.

See also
RotationalInertia::CouldBePhysicallyValid().

◆ MakeFromCentralInertia()

static SpatialInertia<T> MakeFromCentralInertia ( const T &  mass,
const Vector3< T > &  p_PScm_E,
const RotationalInertia< T > &  I_SScm_E 
)
static

Creates a spatial inertia for a physical body or composite body S about a point P from a given mass, center of mass, and central rotational inertia.

For example, this method creates a body's SpatialInertia about its body origin Bo from the body's mass, position vector from Bo to the body's center of mass, and rotational inertia about the body's center of mass.

This method checks for the physical validity of the resulting SpatialInertia with IsPhysicallyValid() and throws a std::runtime_error exception in the event the provided input parameters lead to a non-physically viable spatial inertia.

Parameters
[in]massThe mass of the body or composite body S.
[in]p_PScm_EThe position vector from point P to point Scm (S's center of mass), expressed in a frame E.
[in]I_SScm_ES's RotationalInertia about Scm, expressed in frame E.
Return values
M_SP_ES's spatial inertia about point P, expressed in frame E.

◆ MakeUnitary()

static SpatialInertia<T> MakeUnitary ( )
static

(Internal use only) Creates a spatial inertia whose mass is 1, position vector to center of mass is zero, and whose rotational inertia has moments of inertia of 1 and products of inertia of 0.

◆ operator *() [1/3]

SpatialForce<T> operator * ( const SpatialAcceleration< T > &  A_WB_E) const

Multiplies this spatial inertia M_Bo_E of a body B about its frame origin Bo by the spatial acceleration of the body frame B in a frame W.

Mathematically:

  F_Bo_E = M_Bo_E * A_WB_E

or, in terms of its rotational and translational components (see this class's documentation for the block form of a rotational inertia):

  t_Bo = I_Bo * alpha_WB + m * p_BoBcm x a_WBo
  f_Bo = -m * p_BoBcm x alpha_WB + m * a_WBo

where alpha_WB and a_WBo are the rotational and translational components of the spatial acceleration A_WB, respectively.

Note
The term F_Bo_E computed by this operator appears in the equations of motion for a rigid body which, when written about the origin Bo of the body frame B (which does not necessarily need to coincide with the body's center of mass), read as:
  Ftot_BBo = M_Bo_W * A_WB + b_Bo
where Ftot_BBo is the total spatial force applied on body B at Bo that corresponds to the body spatial acceleration A_WB and b_Bo contains the velocity dependent gyroscopic terms (see Eq. 2.26, p. 27, in A. Jain's book).

◆ operator *() [2/3]

SpatialMomentum<T> operator * ( const SpatialVelocity< T > &  V_WBp_E) const

Multiplies this spatial inertia M_BP_E of a body B about a point P by the spatial velocity V_WBp, in a frame W, of the body frame B shifted to point P.

Mathematically:

  L_WBp_E = M_BP_E * V_WBp_E

or, in terms of its rotational and translational components (see this class's documentation for the block form of a rotational inertia):

  h_WB  = I_Bp * w_WB + m * p_BoBcm x v_WP
  l_WBp = -m * p_BoBcm x w_WB + m * v_WP

where w_WB and v_WP are the rotational and translational components of the spatial velocity V_WBp, respectively and, h_WB and l_WBp are the angular and linear components of the spatial momentum L_WBp, respectively.

Note
It is possible to show that M_BP_E.Shift(p_PQ_E) * V_WBp_E.Shift(p_PQ_E) exactly equals L_WBp_E.Shift(p_PQ_E).

◆ operator *() [3/3]

Eigen::Matrix<T, 6, Derived::ColsAtCompileTime, 0, 6, Derived::MaxColsAtCompileTime> operator * ( const Eigen::MatrixBase< Derived > &  Mmatrix) const

Multiplies this spatial inertia by a set of spatial vectors in M⁶ stored as columns of input matrix Mmatrix.

The top three rows of Mmatrix are expected to store the rotational components while the bottom three rows are expected to store the translational components. The output matrix is of the same size as Mmatrix and each j-th column stores the spatial vector in F⁶ result of multiplying this spatial inertia with the j-th column of Mmatrix.

◆ operator+=()

SpatialInertia<T>& operator+= ( const SpatialInertia< T > &  M_BP_E)

Adds in a spatial inertia to this spatial inertia.

Parameters
[in]M_BP_EA spatial inertia of some body B to be added to this spatial inertia. It must be defined about the same point P as this inertia, and expressed in the same frame E.
Returns
A reference to this spatial inertia, which has been updated to include the given spatial inertia M_BP_E.
Note
Given that the composition of spatial inertias is not well defined for massless bodies, this composition of the spatial inertias performs the arithmetic average of the center of mass position vector (get_com()) and unit inertia (get_unit_inertia()) when the two spatial inertias have zero mass (get_mass()). This is only valid in the limit to zero mass for two bodies with the same mass. This special case allows the composition of spatial inertias in the common case of a kinematic chain of massless bodies.
Warning
This operation is only valid if both spatial inertias are computed about the same point P and expressed in the same frame E. Considering this spatial inertia to be M_SP_E for some body or composite body S, about some point P, the supplied spatial inertia M_BP_E must be for some other body or composite body B about the same point P; B's inertia is then included in S.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ PointMass()

static SpatialInertia<T> PointMass ( const T &  mass,
const Vector3< T > &  position 
)
static

Creates the spatial inertia for a particle Q of mass m about a point P.

Parameters
[in]massmass of the single particle (units of kg).
[in]positionvector from point P to Q, expressed in a frame B.
Return values
M_QP_Bparticle Q's spatial inertia about P, expressed in frame B.
Exceptions
std::exceptionif mass is not positive and finite.

◆ ReExpress()

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

Given this spatial inertia M_SP_E for some body or composite body S, taken about a point P and expressed in frame E, this method computes the same inertia re-expressed in another frame A.

Parameters
[in]R_AERotationMatrix relating frames A and E.
Return values
M_SP_AThe same spatial inertia of S about P but now re-expressed in frame A.
See also
ReExpressInPlace() for details.

◆ ReExpressInPlace()

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

Given this spatial inertia M_SP_E for some body or composite body S, taken about a point P and expressed in frame E, this method computes the same inertia re-expressed in another frame A.

This operation is performed in-place modifying the original object.

Parameters
[in]R_AERotation matrix from frame E to frame A.
Returns
A reference to this rotational inertia about the same point P but now re-expressed in frame A, that is, M_SP_A.

◆ SetNaN()

void SetNaN ( )

Sets this spatial inertia to have NaN entries.

Typically used for quick detection of uninitialized values.

◆ Shift()

SpatialInertia<T> Shift ( const Vector3< T > &  p_PQ_E) const

Given this spatial inertia M_SP_E for some body or composite body S, computed about point P, and expressed in frame E, this method uses the Parallel Axis Theorem for spatial inertias to compute the same spatial inertia about a new point Q.

The result still is expressed in frame E.

See also
ShiftInPlace() for more details.
Parameters
[in]p_PQ_EVector from the original about point P to the new about point Q, expressed in the same frame E this spatial inertia is expressed in.
Return values
M_SQ_EThis same spatial inertia for body or composite body S but computed about a new point Q.

◆ ShiftInPlace()

SpatialInertia<T>& ShiftInPlace ( const Vector3< T > &  p_PQ_E)

Given this spatial inertia M_SP_E for some body or composite body S, computed about point P, and expressed in frame E, this method uses the Parallel Axis Theorem for spatial inertias to compute the same spatial inertia about a new point Q.

The result still is expressed in frame E. This operation is performed in-place modifying the original object.

See also
Shift() which does not modify this object.

For details see Section 2.1.2, p. 20 of [Jain 2010].

Parameters
[in]p_PQ_Eposition vector from the original about-point P to the new about-point Q, expressed in the same frame E that this spatial inertia is expressed in.
Returns
A reference to this spatial inertia for body or composite body S but now computed about a new point Q.

◆ SolidBoxWithDensity()

static SpatialInertia<T> SolidBoxWithDensity ( const T &  density,
const T &  lx,
const T &  ly,
const T &  lz 
)
static

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

Parameters
[in]densitymass per volume (kg/m³).
[in]lxlength of the box in the Bx direction (meters).
[in]lylength of the box in the By direction (meters).
[in]lzlength of the box in the Bz direction (meters).
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Exceptions
std::exceptionif density, lx, ly, or lz is not positive and finite.

◆ SolidBoxWithMass()

static SpatialInertia<T> SolidBoxWithMass ( const T &  mass,
const T &  lx,
const T &  ly,
const T &  lz 
)
static

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

Parameters
[in]massmass of the solid box (kg).
[in]lxlength of the box in the Bx direction (meters).
[in]lylength of the box in the By direction (meters).
[in]lzlength of the box in the Bz direction (meters).
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Exceptions
std::exceptionif mass, lx, ly, or lz is not positive and finite.

◆ SolidCapsuleWithDensity()

static SpatialInertia<T> SolidCapsuleWithDensity ( const T &  density,
const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

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

Parameters
[in]densitymass per volume (kg/m³).
[in]radiusradius of the cylinder/half-sphere parts of the capsule.
[in]lengthlength of the cylindrical part of the capsule.
[in]unit_vectorunit vector defining the axial direction of the cylindrical part of the capsule, expressed in B.
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Note
B's rotational inertia about Bo is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bo and is perpendicular to unit_vector.
Exceptions
std::exceptionif density, radius, or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.

◆ SolidCapsuleWithMass()

static SpatialInertia<T> SolidCapsuleWithMass ( const T &  mass,
const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

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

Parameters
[in]massmass of the solid capsule (kg).
[in]radiusradius of the cylinder/half-sphere parts of the capsule.
[in]lengthlength of the cylindrical part of the capsule.
[in]unit_vectorunit vector defining the axial direction of the cylindrical part of the capsule, expressed in B.
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Note
B's rotational inertia about Bo is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bo and is perpendicular to unit_vector.
Exceptions
std::exceptionif mass, radius, or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.

◆ SolidCubeWithDensity()

static SpatialInertia<T> SolidCubeWithDensity ( const T &  density,
const T &  length 
)
static

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

Parameters
[in]densitymass per volume (kg/m³).
[in]lengthThe length of each of the cube's sides (meters).
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B. Since B's rotational inertia is triaxially symmetric, M_BBo_B = M_BBo_E, i.e., M_BBo expressed in frame B is equal to M_BBo expressed in an arbitrary frame E.
Note
B's rotational inertia about Bo is triaxially symmetric, meaning B has an equal moment of inertia about any line passing through Bo.
Exceptions
std::exceptionif density or length is not positive and finite.

◆ SolidCubeWithMass()

static SpatialInertia<T> SolidCubeWithMass ( const T &  mass,
const T &  length 
)
static

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

Parameters
[in]massmass of the solid cube (kg).
[in]lengthThe length of each of the cube's sides (meters).
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B. Since B's rotational inertia is triaxially symmetric, M_BBo_B = M_BBo_E, i.e., M_BBo expressed in frame B is equal to M_BBo expressed in an arbitrary frame E.
Note
B's rotational inertia about Bo is triaxially symmetric, meaning B has an equal moment of inertia about any line passing through Bo.
Exceptions
std::exceptionif mass or length is not positive and finite.

◆ SolidCylinderWithDensity()

static SpatialInertia<T> SolidCylinderWithDensity ( const T &  density,
const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

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

Parameters
[in]densitymass per volume (kg/m³).
[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 B.
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Note
B's rotational inertia about Bo is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bo and is perpendicular to unit_vector.
Exceptions
std::exceptionif density, radius, or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
See also
SolidCylinderWithDensityAboutEnd() to calculate M_BBp_B, B's spatial inertia about Bp (at the center of one of the cylinder's circular ends).

◆ SolidCylinderWithDensityAboutEnd()

static SpatialInertia<T> SolidCylinderWithDensityAboutEnd ( const T &  density,
const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a spatial 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]densitymass per volume (kg/m³).
[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 B.
Return values
M_BBp_BB's spatial inertia about Bp, expressed in B.
Note
The position from Bp to Bcm is p_BpBcm = length / 2 * unit_vector.
B's rotational 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 density, radius, or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
See also
SolidCylinderWithDensity() to calculate M_BBcm_B, B's spatial inertia about Bcm (B's center of mass).

◆ SolidCylinderWithMass()

static SpatialInertia<T> SolidCylinderWithMass ( const T &  mass,
const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

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

Parameters
[in]massmass of the solid cylinder (kg).
[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 B.
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Note
B's rotational inertia about Bo is axially symmetric, meaning B has an equal moment of inertia about any line that both passes through Bo and is perpendicular to unit_vector.
Exceptions
std::exceptionif mass, radius, or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
See also
SolidCylinderWithMassAboutEnd() to calculate M_BBp_B, B's spatial inertia about Bp (at the center of one of the cylinder's circular ends).

◆ SolidCylinderWithMassAboutEnd()

static SpatialInertia<T> SolidCylinderWithMassAboutEnd ( const T &  mass,
const T &  radius,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a spatial 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]massmass of the solid cylinder (kg).
[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 B.
Return values
M_BBp_BB's spatial inertia about Bp, expressed in B.
Note
The position from Bp to Bcm is p_BpBcm = length / 2 * unit_vector.
B's rotational 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 density, radius, or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
See also
SolidCylinderWithMass() to calculate M_BBcm_B, B's spatial inertia about Bcm (B's center of mass).

◆ SolidEllipsoidWithDensity()

static SpatialInertia<T> SolidEllipsoidWithDensity ( const T &  density,
const T &  a,
const T &  b,
const T &  c 
)
static

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

Parameters
[in]densitymass per volume (kg/m³).
[in]alength of ellipsoid semi-axis in the ellipsoid Bx direction.
[in]blength of ellipsoid semi-axis in the ellipsoid By direction.
[in]clength of ellipsoid semi-axis in the ellipsoid Bz direction.
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Exceptions
std::exceptionif density, a, b, or c is not positive and finite.

◆ SolidEllipsoidWithMass()

static SpatialInertia<T> SolidEllipsoidWithMass ( const T &  mass,
const T &  a,
const T &  b,
const T &  c 
)
static

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

Parameters
[in]massmass of the solid ellipsoid (kg).
[in]alength of ellipsoid semi-axis in the ellipsoid Bx direction.
[in]blength of ellipsoid semi-axis in the ellipsoid By direction.
[in]clength of ellipsoid semi-axis in the ellipsoid Bz direction.
Return values
M_BBo_BB's spatial inertia about Bo, expressed in B.
Exceptions
std::exceptionif mass, a, b, or c is not positive and finite.

◆ SolidSphereWithDensity()

static SpatialInertia<T> SolidSphereWithDensity ( const T &  density,
const T &  radius 
)
static

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

Parameters
[in]densitymass per volume (kg/m³).
[in]radiussphere's radius (meters).
Return values
M_BBoB's spatial inertia about Bo. Since B's rotational inertia is triaxially symmetric, M_BBo_B = M_BBo_E, i.e., M_BBo expressed in frame B is equal to M_BBo expressed in an arbitrary frame E.
Note
B's rotational inertia about Bo is triaxially symmetric, meaning B has an equal moment of inertia about any line passing through Bo.
Exceptions
std::exceptionif density or radius is not positive and finite.

◆ SolidSphereWithMass()

static SpatialInertia<T> SolidSphereWithMass ( const T &  mass,
const T &  radius 
)
static

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

Parameters
[in]massmass of the solid sphere (kg).
[in]radiussphere's radius (meters).
Return values
M_BBoB's spatial inertia about Bo. Since B's rotational inertia is triaxially symmetric, M_BBo_B = M_BBo_E, i.e., M_BBo expressed in frame B is equal to M_BBo expressed in an arbitrary frame E.
Note
B's rotational inertia about Bo is triaxially symmetric, meaning B has an equal moment of inertia about any line passing through Bo.
Exceptions
std::exceptionif mass or radius is not positive and finite.

◆ SolidTetrahedronAboutPointWithDensity()

static SpatialInertia<T> SolidTetrahedronAboutPointWithDensity ( const T &  density,
const Vector3< T > &  p0,
const Vector3< T > &  p1,
const Vector3< T > &  p2,
const Vector3< T > &  p3 
)
static

Creates a spatial inertia for a 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
M_BA_EB's spatial inertia about point A, expressed in E.
Note
In the common case, point A is Eo (the origin of the expressed-in frame E). The example below has point A as Wo (origin of world frame W).
Exceptions
std::exceptionif density is not positive and finite.
double density = 1000;
Vector3<double> p_WoB0_W(1, 0, 0);
Vector3<double> p_WoB1_W(2, 0, 0);
Vector3<double> p_WoB2_W(1, 1, 0);
Vector3<double> p_WoB3_W(1, 0, 1);
SpatialInertia<double> M_BWo_W =
density, p_WoB0_W, p_WoB1_W, p_WoB2_W, p_WoB3_W);
See also
SolidTetrahedronAboutVertexWithDensity() to efficiently calculate a spatial inertia about a vertex of B.

◆ SolidTetrahedronAboutVertexWithDensity()

static SpatialInertia<T> SolidTetrahedronAboutVertexWithDensity ( const T &  density,
const Vector3< T > &  p1,
const Vector3< T > &  p2,
const Vector3< T > &  p3 
)
static

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

Parameters
[in]densitymass per volume (kg/m³).
[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
M_BB0_EB's spatial inertia about its vertex B0, expressed in E.
Exceptions
std::exceptionif density is not positive and finite.
See also
SolidTetrahedronAboutPointWithDensity() to calculate a spatial inertia about an arbitrary point.

◆ ThinRodWithMass()

static SpatialInertia<T> ThinRodWithMass ( const T &  mass,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a spatial inertia for a uniform-density thin rod B about its center of mass Bcm.

Parameters
[in]massmass of the rod (units of kg).
[in]lengthlength of the rod (units of meters).
[in]unit_vectorunit vector defining the rod's axial direction, expressed in B.
Return values
M_BBcm_BB's spatial inertia about Bcm, expressed in B.
Note
B's rotational 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. B has no (zero) rotational inertia about the line that passes through Bcm and is parallel to unit_vector.
Exceptions
std::exceptionif mass or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
See also
ThinRodWithMassAboutEnd() to calculate M_BBp_B, B's spatial inertia about Bp (one of the ends of rod B).

◆ ThinRodWithMassAboutEnd()

static SpatialInertia<T> ThinRodWithMassAboutEnd ( const T &  mass,
const T &  length,
const Vector3< T > &  unit_vector 
)
static

Creates a spatial inertia for a uniform-density thin rod B about one of its ends.

Parameters
[in]massmass of the rod (units of kg).
[in]lengthlength of the rod (units of meters).
[in]unit_vectorunit vector defining the rod's axial direction, expressed in B.
Return values
M_BBp_BB's spatial inertia about Bp, expressed in B.
Note
The position from Bp to Bcm is length / 2 * unit_vector.
B's rotational 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. B has no (zero) rotational inertia about the line that passes through Bp and is parallel to unit_vector.
Exceptions
std::exceptionif mass or length is not positive and finite or if ‖unit_vector‖ is not within 1.0E-14 of 1.0.
See also
ThinRodWithMass() to calculate M_BBcm_B, B's spatial inertia about Bcm (B's center of mass).

Friends And Related Function Documentation

◆ operator<<()

std::ostream & operator<< ( std::ostream &  out,
const SpatialInertia< T > &  M 
)
related

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


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