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
-
|
| 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...
|
|
|
| UnitInertia (const UnitInertia &)=default |
|
UnitInertia & | operator= (const UnitInertia &)=default |
|
| UnitInertia (UnitInertia &&)=default |
|
UnitInertia & | operator= (UnitInertia &&)=default |
|
|
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...
|
|
T | Trace () const |
| Returns a rotational inertia's trace (i.e., Ixx + Iyy + Izz, the sum of the diagonal elements of the inertia matrix). More...
|
|
T | CalcMaximumPossibleMomentOfInertia () const |
| Returns the maximum possible moment of inertia for this rotational inertia about-point P for any expressed-in frame E. More...
|
|
const T & | operator() (int i, int j) const |
| Const access to the (i, j) element of this rotational inertia. More...
|
|
Matrix3< T > | CopyToFullMatrix3 () const |
| Gets a full 3x3 matrix copy of this rotational inertia. More...
|
|
boolean< T > | IsNearlyEqualTo (const RotationalInertia &other, double precision) const |
| Compares this rotational inertia to other rotational inertia within the specified precision (which is a dimensionless number specifying the relative precision to which the comparison is performed). More...
|
|
RotationalInertia< T > & | operator+= (const RotationalInertia< T > &I_BP_E) |
| Adds a rotational inertia I_BP_E to this rotational inertia. More...
|
|
RotationalInertia< T > | operator+ (const RotationalInertia< T > &I_BP_E) const |
| Adds a rotational inertia I_BP_E to this rotational inertia. More...
|
|
RotationalInertia< T > & | operator-= (const RotationalInertia< T > &I_BP_E) |
| Subtracts a rotational inertia I_BP_E from this rotational inertia. More...
|
|
RotationalInertia< T > | operator- (const RotationalInertia< T > &I_BP_E) const |
| Subtracts a rotational inertia I_BP_E from this rotational inertia. More...
|
|
RotationalInertia< T > & | operator *= (const T &nonnegative_scalar) |
| Multiplies this rotational inertia by a nonnegative scalar (>= 0). More...
|
|
RotationalInertia< T > | operator * (const T &nonnegative_scalar) const |
| Multiplies this rotational inertia by a nonnegative scalar (>= 0). More...
|
|
Vector3< T > | operator * (const Vector3< T > &w_E) const |
| Multiplies this rotational inertia about-point P, expressed-in frame E by the vector w_E (which must also have the same expressed-in frame E). More...
|
|
RotationalInertia< T > & | operator/= (const T &positive_scalar) |
| Divides this rotational inertia by a positive scalar (> 0). More...
|
|
RotationalInertia< T > | operator/ (const T &positive_scalar) const |
| Divides this rotational inertia by a positive scalar(> 0). More...
|
|
RotationalInertia< T > | MultiplyByScalarSkipValidityCheck (const T &s) const |
| (Internal use only) Multiplies a rotational inertia by a scalar. More...
|
|
void | SetToNaN () |
| Sets this rotational inertia so all its elements are equal to NaN. More...
|
|
void | SetZero () |
| Sets this rotational inertia so all its moments/products of inertia are zero, e.g., for convenient initialization before a computation or for inertia calculations involving a particle (point-mass). More...
|
|
boolean< T > | IsNaN () const |
| Returns true if any moment/product in this rotational inertia is NaN. More...
|
|
boolean< T > | IsZero () const |
| Returns true if all moments and products of inertia are exactly zero. More...
|
|
template<typename Scalar > |
RotationalInertia< Scalar > | cast () const |
| Returns a new RotationalInertia object templated on Scalar initialized from the values of this rotational inertia's entries. More...
|
|
Vector3< double > | CalcPrincipalMomentsOfInertia () const |
| Forms the 3 principal moments of inertia for this rotational inertia. More...
|
|
std::pair< Vector3< double >, math::RotationMatrix< double > > | CalcPrincipalMomentsAndAxesOfInertia () const |
| Forms the 3 principal moments of inertia and their 3 associated principal directions for this rotational inertia. More...
|
|
boolean< T > | CouldBePhysicallyValid () const |
| Performs several necessary checks to verify whether this rotational inertia could be physically valid, including: More...
|
|
void | ReExpressInPlace (const math::RotationMatrix< T > &R_AE) |
| Re-expresses this rotational inertia I_BP_E in place to I_BP_A . More...
|
|
RotationalInertia< T > | ReExpress (const math::RotationMatrix< T > &R_AE) const |
| Re-expresses this rotational inertia I_BP_E to I_BP_A i.e., re-expresses body B's rotational inertia from frame E to frame A. More...
|
|
| RotationalInertia (const RotationalInertia &)=default |
|
RotationalInertia & | operator= (const RotationalInertia &)=default |
|
| RotationalInertia (RotationalInertia &&)=default |
|
RotationalInertia & | operator= (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...
|
|
|
|
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...
|
|