Simbody  3.6
SimTK::UnitInertia_< P > Class Template Reference

A UnitInertia matrix is a unit-mass inertia matrix; you can convert it to an Inertia by multiplying it by the actual body mass. More...

+ Inheritance diagram for SimTK::UnitInertia_< P >:

Public Member Functions

 UnitInertia_ ()
 Default is a NaN-ed out mess to avoid accidents, even in Release mode. More...
 
 UnitInertia_ (const RealP &moment)
 Create a principal unit inertia matrix with identical diagonal elements. More...
 
 UnitInertia_ (const Vec3P &moments, const Vec3P &products=Vec3P(0))
 Create a unit inertia matrix from a vector of the moments of inertia (the inertia matrix diagonal) and optionally a vector of the products of inertia (the off-diagonals). More...
 
 UnitInertia_ (const RealP &xx, const RealP &yy, const RealP &zz)
 Create a principal unit inertia matrix (only non-zero on diagonal). More...
 
 UnitInertia_ (const RealP &xx, const RealP &yy, const RealP &zz, const RealP &xy, const RealP &xz, const RealP &yz)
 This is a general unit inertia matrix. More...
 
 UnitInertia_ (const SymMat33P &m)
 Construct a UnitInertia from a symmetric 3x3 matrix. More...
 
 UnitInertia_ (const Mat33P &m)
 Construct a UnitInertia from a 3x3 symmetric matrix. More...
 
 UnitInertia_ (const Inertia_< P > &inertia)
 Construct a UnitInertia matrix from an Inertia matrix. More...
 
UnitInertia_setUnitInertia (const RealP &xx, const RealP &yy, const RealP &zz)
 Set a UnitInertia matrix to have only principal moments (that is, it will be diagonal). More...
 
UnitInertia_setUnitInertia (const Vec3P &moments, const Vec3P &products=Vec3P(0))
 Set principal moments and optionally off-diagonal terms. More...
 
UnitInertia_setUnitInertia (const RealP &xx, const RealP &yy, const RealP &zz, const RealP &xy, const RealP &xz, const RealP &yz)
 Set this UnitInertia to a general matrix. More...
 
UnitInertia_ shiftToCentroid (const Vec3P &CF) const
 Assuming that this unit inertia matrix is currently taken about some (implicit) frame F's origin OF, produce a new unit inertia matrix which is the same as this one except measured about the body's centroid CF. More...
 
UnitInertia_shiftToCentroidInPlace (const Vec3P &CF)
 Assuming that this unit inertia matrix is currently taken about some (implicit) frame F's origin OF, modify it so that it is instead taken about the body's centroid CF. More...
 
UnitInertia_ shiftFromCentroid (const Vec3P &p) const
 Assuming that the current UnitInertia G is a central inertia (that is, it is inertia about the body centroid CF), create a new object that is the same as this one except shifted to some other point p measured from the centroid. More...
 
UnitInertia_shiftFromCentroidInPlace (const Vec3P &p)
 Assuming that the current UnitInertia G is a central inertia (that is, it is inertia about the body centroid CF), shift it in place to some other point p measured from the centroid. More...
 
UnitInertia_ reexpress (const Rotation_< P > &R_FB) const
 Return a new unit inertia matrix like this one but re-expressed in another frame (leaving the origin point unchanged). More...
 
UnitInertia_ reexpress (const InverseRotation_< P > &R_FB) const
 Rexpress using an inverse rotation to avoid having to convert it. More...
 
UnitInertia_reexpressInPlace (const Rotation_< P > &R_FB)
 Re-express this unit inertia matrix in another frame, changing the object in place; see reexpress() if you want to leave this object unmolested and get a new one instead. More...
 
UnitInertia_reexpressInPlace (const InverseRotation_< P > &R_FB)
 Rexpress using an inverse rotation to avoid having to convert it. More...
 
 operator const SymMat33P & () const
 This is an implicit conversion to const SymMat33. More...
 
const Inertia_< P > & asUnitInertia () const
 Recast this UnitInertia matrix as a unit inertia matrix. More...
 
UnitInertia_setFromUnitInertia (const Inertia_< P > &inertia)
 Set from a unit inertia matrix. More...
 
- Public Member Functions inherited from SimTK::Inertia_< P >
 Inertia_ ()
 Default is a NaN-ed out mess to avoid accidents, even in Release mode. More...
 
 Inertia_ (const P &moment)
 Create a principal inertia matrix with identical diagonal elements, like a sphere where moment=2/5 m r^2, or a cube where moment=1/6 m s^2, with m the total mass, r the sphere's radius and s the length of a side of the cube. More...
 
 Inertia_ (const Vec< 3, P > &p, const P &mass)
 Create an Inertia matrix for a point mass at a given location, measured from the origin OF of the implicit frame F, and expressed in F. More...
 
 Inertia_ (const Vec< 3, P > &moments, const Vec< 3, P > &products=Vec< 3, P >(0))
 Create an inertia matrix from a vector of the moments of inertia (the inertia matrix diagonal) and optionally a vector of the products of inertia (the off-diagonals). More...
 
 Inertia_ (const P &xx, const P &yy, const P &zz)
 Create a principal inertia matrix (only non-zero on diagonal). More...
 
 Inertia_ (const P &xx, const P &yy, const P &zz, const P &xy, const P &xz, const P &yz)
 This is a general inertia matrix. More...
 
 Inertia_ (const SymMat< 3, P > &inertia)
 Construct an Inertia from a symmetric 3x3 matrix. More...
 
 Inertia_ (const Mat< 3, 3, P > &m)
 Construct an Inertia matrix from a 3x3 symmetric matrix. More...
 
Inertia_setInertia (const P &xx, const P &yy, const P &zz)
 Set an inertia matrix to have only principal moments (that is, it will be diagonal). More...
 
Inertia_setInertia (const Vec< 3, P > &moments, const Vec< 3, P > &products=Vec< 3, P >(0))
 Set principal moments and optionally off-diagonal terms. More...
 
Inertia_setInertia (const P &xx, const P &yy, const P &zz, const P &xy, const P &xz, const P &yz)
 Set this Inertia to a general matrix. More...
 
Inertia_operator+= (const Inertia_ &inertia)
 Add in another inertia matrix. More...
 
Inertia_operator-= (const Inertia_ &inertia)
 Subtract off another inertia matrix. More...
 
Inertia_operator*= (const P &s)
 Multiply this inertia matrix by a scalar. Cost is 6 flops. More...
 
Inertia_operator/= (const P &s)
 Divide this inertia matrix by a scalar. More...
 
Inertia_ shiftToMassCenter (const Vec< 3, P > &CF, const P &mass) const
 Assume that the current inertia is about the F frame's origin OF, and expressed in F. More...
 
Inertia_shiftToMassCenterInPlace (const Vec< 3, P > &CF, const P &mass)
 Assume that the current inertia is about the F frame's origin OF, and expressed in F. More...
 
Inertia_ shiftFromMassCenter (const Vec< 3, P > &p, const P &mass) const
 Assuming that the current inertia I is a central inertia (that is, it is inertia about the body center of mass CF), shift it to some other point p measured from the center of mass. More...
 
Inertia_shiftFromMassCenterInPlace (const Vec< 3, P > &p, const P &mass)
 Assuming that the current inertia I is a central inertia (that is, it is inertia about the body center of mass CF), shift it to some other point p measured from the center of mass. More...
 
Inertia_ reexpress (const Rotation_< P > &R_FB) const
 Return a new inertia matrix like this one but re-expressed in another frame (leaving the origin point unchanged). More...
 
Inertia_ reexpress (const InverseRotation_< P > &R_FB) const
 Rexpress using an inverse rotation to avoid having to convert it. More...
 
Inertia_reexpressInPlace (const Rotation_< P > &R_FB)
 Re-express this inertia matrix in another frame, changing the object in place; see reexpress() if you want to leave this object unmolested and get a new one instead. More...
 
Inertia_reexpressInPlace (const InverseRotation_< P > &R_FB)
 Rexpress in place using an inverse rotation to avoid having to convert it. More...
 
trace () const
 
 operator const SymMat< 3, P > & () const
 This is an implicit conversion to a const SymMat33. More...
 
const SymMat< 3, P > & asSymMat33 () const
 Obtain a reference to the underlying symmetric matrix type. More...
 
Mat< 3, 3, P > toMat33 () const
 Expand the internal packed representation into a full 3x3 symmetric matrix with all elements set. More...
 
const Vec< 3, P > & getMoments () const
 Obtain the inertia moments (diagonal of the Inertia matrix) as a Vec3 ordered xx, yy, zz. More...
 
const Vec< 3, P > & getProducts () const
 Obtain the inertia products (off-diagonals of the Inertia matrix) as a Vec3 with elements ordered xy, xz, yz. More...
 
bool isNaN () const
 
bool isInf () const
 
bool isFinite () const
 
bool isNumericallyEqual (const Inertia_< P > &other) const
 Compare this inertia matrix with another one and return true if they are close to within a default numerical tolerance. More...
 
bool isNumericallyEqual (const Inertia_< P > &other, double tol) const
 Compare this inertia matrix with another one and return true if they are close to within a specified numerical tolerance. More...
 

Static Public Member Functions

static bool isValidUnitInertiaMatrix (const SymMat33P &m)
 Test some conditions that must hold for a valid UnitInertia matrix. More...
 
UnitInertia matrix factories

These are UnitInertia matrix factories for some common 3D solids.

Each defines its own frame aligned (when possible) with principal moments. Each has unit mass and its center of mass located at the origin (usually). Use this with shiftFromCentroid() to move it somewhere else, and with reexpress() to express the UnitInertia matrix in another frame.

static UnitInertia_ pointMassAtOrigin ()
 Create a UnitInertia matrix for a point located at the origin – that is, an all-zero matrix. More...
 
static UnitInertia_ pointMassAt (const Vec3P &p)
 Create a UnitInertia matrix for a point of unit mass located at a given location measured from origin OF and expressed in F (where F is the implicit frame of this UnitInertia matrix). More...
 
static UnitInertia_ sphere (const RealP &r)
 Create a UnitInertia matrix for a unit mass sphere of radius r centered at the origin. More...
 
static UnitInertia_ cylinderAlongZ (const RealP &r, const RealP &hz)
 Unit-mass cylinder aligned along z axis; use radius and half-length. More...
 
static UnitInertia_ cylinderAlongY (const RealP &r, const RealP &hy)
 Unit-mass cylinder aligned along y axis; use radius and half-length. More...
 
static UnitInertia_ cylinderAlongX (const RealP &r, const RealP &hx)
 Unit-mass cylinder aligned along x axis; use radius and half-length. More...
 
static UnitInertia_ brick (const RealP &hx, const RealP &hy, const RealP &hz)
 Unit-mass brick given by half-lengths in each direction. More...
 
static UnitInertia_ brick (const Vec3P &halfLengths)
 Alternate interface to brick() that takes a Vec3 for the half lengths. More...
 
static UnitInertia_ ellipsoid (const RealP &hx, const RealP &hy, const RealP &hz)
 Unit-mass ellipsoid given by half-lengths in each direction. More...
 
static UnitInertia_ ellipsoid (const Vec3P &halfLengths)
 Alternate interface to ellipsoid() that takes a Vec3 for the half lengths. More...
 
- Static Public Member Functions inherited from SimTK::Inertia_< P >
static bool isValidInertiaMatrix (const SymMat< 3, P > &m)
 Test some conditions that must hold for a valid Inertia matrix. More...
 
static Inertia_ pointMassAtOrigin ()
 Create an Inertia matrix for a point located at the origin – that is, an all-zero matrix. More...
 
static Inertia_ pointMassAt (const Vec< 3, P > &p, const P &m)
 Create an Inertia matrix for a point of a given mass, located at a given location measured from the origin of the implicit F frame. More...
 
static Inertia_ sphere (const P &r)
 Create a UnitInertia matrix for a unit mass sphere of radius r centered at the origin. More...
 
static Inertia_ cylinderAlongZ (const P &r, const P &hz)
 Unit-mass cylinder aligned along z axis; use radius and half-length. More...
 
static Inertia_ cylinderAlongY (const P &r, const P &hy)
 Unit-mass cylinder aligned along y axis; use radius and half-length. More...
 
static Inertia_ cylinderAlongX (const P &r, const P &hx)
 Unit-mass cylinder aligned along x axis; use radius and half-length. More...
 
static Inertia_ brick (const P &hx, const P &hy, const P &hz)
 Unit-mass brick given by half-lengths in each direction. More...
 
static Inertia_ brick (const Vec< 3, P > &halfLengths)
 Alternate interface to brick() that takes a Vec3 for the half lengths. More...
 
static Inertia_ ellipsoid (const P &hx, const P &hy, const P &hz)
 Unit-mass ellipsoid given by half-lengths in each direction. More...
 
static Inertia_ ellipsoid (const Vec< 3, P > &halfLengths)
 Alternate interface to ellipsoid() that takes a Vec3 for the half lengths. More...
 

Additional Inherited Members

- Protected Member Functions inherited from SimTK::Inertia_< P >
const UnitInertia_< P > & getAsUnitInertia () const
 
UnitInertia_< P > & updAsUnitInertia ()
 
void errChk (const char *methodName) const
 
- Protected Attributes inherited from SimTK::Inertia_< P >
SymMat< 3, P > I_OF_F
 

Detailed Description

template<class P>
class SimTK::UnitInertia_< P >

A UnitInertia matrix is a unit-mass inertia matrix; you can convert it to an Inertia by multiplying it by the actual body mass.

Functionality is limited here to those few operations which ensure unit mass; most operations on a UnitInertia matrix result in a general Inertia instead. You can use a UnitInertia object wherever an Inertia is expected but not vice versa.

When constructing a UnitInertia matrix, note that we cannot verify that it actually has unit mass because every legal Inertia matrix can be viewed as the UnitInertia matrix for some differently-scaled object.

Unit inertia matrices are sometimes called "gyration" matrices; we will often represent them with the symbol "G" to avoid confusion with general inertia matrices for which the symbol "I" (or sometimes "J") is used.

Abbreviations

Typedefs exist for the most common invocations of UnitInertia_<P>:

Constructor & Destructor Documentation

◆ UnitInertia_() [1/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( )
inline

Default is a NaN-ed out mess to avoid accidents, even in Release mode.

Other than this value, a UnitInertia_ should always be valid.

◆ UnitInertia_() [2/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( const RealP &  moment)
inlineexplicit

Create a principal unit inertia matrix with identical diagonal elements.

This is the unit inertia matrix of a unit mass sphere of radius r = sqrt(5/2 * moment) centered on the origin.

◆ UnitInertia_() [3/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( const Vec3P moments,
const Vec3P products = Vec3P(0) 
)
inlineexplicit

Create a unit inertia matrix from a vector of the moments of inertia (the inertia matrix diagonal) and optionally a vector of the products of inertia (the off-diagonals).

Moments are in the order xx,yy,zz; products are xy,xz,yz.

◆ UnitInertia_() [4/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( const RealP &  xx,
const RealP &  yy,
const RealP &  zz 
)
inline

Create a principal unit inertia matrix (only non-zero on diagonal).

◆ UnitInertia_() [5/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( const RealP &  xx,
const RealP &  yy,
const RealP &  zz,
const RealP &  xy,
const RealP &  xz,
const RealP &  yz 
)
inline

This is a general unit inertia matrix.

Note the order of these arguments: moments of inertia first, then products of inertia.

◆ UnitInertia_() [6/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( const SymMat33P m)
inlineexplicit

Construct a UnitInertia from a symmetric 3x3 matrix.

The diagonals must be nonnegative and satisfy the triangle inequality.

◆ UnitInertia_() [7/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( const Mat33P m)
inlineexplicit

Construct a UnitInertia from a 3x3 symmetric matrix.

In Debug mode we'll test that the supplied matrix is numerically close to symmetric, and that it satisfies other requirements of an inertia matrix.

◆ UnitInertia_() [8/8]

template<class P>
SimTK::UnitInertia_< P >::UnitInertia_ ( const Inertia_< P > &  inertia)
inlineexplicit

Construct a UnitInertia matrix from an Inertia matrix.

Note that there is no way to check whether this is really a unit inertia – any inertia matrix may be interpreted as a unit inertia for some shape. So be sure you know what you're doing before you use this constructor!

Member Function Documentation

◆ setUnitInertia() [1/3]

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::setUnitInertia ( const RealP &  xx,
const RealP &  yy,
const RealP &  zz 
)
inline

Set a UnitInertia matrix to have only principal moments (that is, it will be diagonal).

Returns a reference to "this" like an assignment operator.

◆ setUnitInertia() [2/3]

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::setUnitInertia ( const Vec3P moments,
const Vec3P products = Vec3P(0) 
)
inline

Set principal moments and optionally off-diagonal terms.

Returns a reference to "this" like an assignment operator.

◆ setUnitInertia() [3/3]

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::setUnitInertia ( const RealP &  xx,
const RealP &  yy,
const RealP &  zz,
const RealP &  xy,
const RealP &  xz,
const RealP &  yz 
)
inline

Set this UnitInertia to a general matrix.

Note the order of these arguments: moments of inertia first, then products of inertia. Behaves like an assignment statement. Will throw an error message in Debug mode if the supplied elements do not constitute a valid inertia matrix.

◆ shiftToCentroid()

template<class P>
UnitInertia_ SimTK::UnitInertia_< P >::shiftToCentroid ( const Vec3P CF) const
inline

Assuming that this unit inertia matrix is currently taken about some (implicit) frame F's origin OF, produce a new unit inertia matrix which is the same as this one except measured about the body's centroid CF.

We are given the vector from OF to the centroid CF, expressed in F. This produces a new UnitInertia matrix G' whose (implicit) frame F' is aligned with F but has origin CF (an inertia matrix like that is called "central" or "centroidal"). From the parallel axis theorem for inertias, G' = G - Gcom where Gcom is the inertia matrix of a fictitious, unit-mass point located at CF (measured in F) taken about OF. (17 flops)

See also
shiftToCentroidInPlace(), shiftFromCentroid()

◆ shiftToCentroidInPlace()

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::shiftToCentroidInPlace ( const Vec3P CF)
inline

Assuming that this unit inertia matrix is currently taken about some (implicit) frame F's origin OF, modify it so that it is instead taken about the body's centroid CF.

We are given the vector from OF to the centroid CF, expressed in F. This produces a new UnitInertia G' whose (implicit) frame F' is aligned with F but has origin CF (an inertia matrix like that is called "central" or "centroidal"). From the parallel axis theorem for inertias, G' = G - Gcom where Gcom is the inertia matrix of a fictitious, unit-mass point located at CF (measured in F) taken about OF. A reference to the modified object is returned so that you can chain this method in the manner of assignment operators. Cost is 17 flops.

See also
shiftToCentroid() if you want to leave this object unmolested.
shiftFromCentroidInPlace()

◆ shiftFromCentroid()

template<class P>
UnitInertia_ SimTK::UnitInertia_< P >::shiftFromCentroid ( const Vec3P p) const
inline

Assuming that the current UnitInertia G is a central inertia (that is, it is inertia about the body centroid CF), create a new object that is the same as this one except shifted to some other point p measured from the centroid.

This produces a new inertia G' about the point p given by G' = G + Gp where Gp is the inertia of a fictitious point located at p, taken about CF. Cost is 17 flops.

See also
shiftFromCentroidInPlace(), shiftToCentroid()

◆ shiftFromCentroidInPlace()

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::shiftFromCentroidInPlace ( const Vec3P p)
inline

Assuming that the current UnitInertia G is a central inertia (that is, it is inertia about the body centroid CF), shift it in place to some other point p measured from the centroid.

This changes G to a modified inertia G' taken about the point p, with the parallel axis theorem for inertia giving G' = G + Gp where Gp is the inertia of a fictitious, unit-mass point located at p, taken about CF. Cost is 17 flops.

See also
shiftFromCentroid() if you want to leave this object unmolested.
shiftToCentroidInPlace()

◆ reexpress() [1/2]

template<class P>
UnitInertia_ SimTK::UnitInertia_< P >::reexpress ( const Rotation_< P > &  R_FB) const
inline

Return a new unit inertia matrix like this one but re-expressed in another frame (leaving the origin point unchanged).

Call this inertia matrix G_OF_F, that is, it is taken about the origin of some frame F, and expressed in F. We want to return G_OF_B, the same unit inertia matrix, still taken about the origin of F, but expressed in the B frame, given by G_OF_B=R_BF*G_OF_F*R_FB where R_FB is the rotation matrix giving the orientation of frame B in F. This is handled here by a special method of the Rotation class which rotates a symmetric tensor at a cost of 57 flops.

See also
reexpressInPlace()

◆ reexpress() [2/2]

template<class P>
UnitInertia_ SimTK::UnitInertia_< P >::reexpress ( const InverseRotation_< P > &  R_FB) const
inline

Rexpress using an inverse rotation to avoid having to convert it.

See also
rexpress(Rotation) for information

◆ reexpressInPlace() [1/2]

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::reexpressInPlace ( const Rotation_< P > &  R_FB)
inline

Re-express this unit inertia matrix in another frame, changing the object in place; see reexpress() if you want to leave this object unmolested and get a new one instead.

Cost is 57 flops.

See also
reexpress() if you want to leave this object unmolested.

◆ reexpressInPlace() [2/2]

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::reexpressInPlace ( const InverseRotation_< P > &  R_FB)
inline

Rexpress using an inverse rotation to avoid having to convert it.

See also
rexpressInPlace(Rotation) for information

◆ operator const SymMat33P &()

template<class P>
SimTK::UnitInertia_< P >::operator const SymMat33P & ( ) const
inline

This is an implicit conversion to const SymMat33.

◆ asUnitInertia()

template<class P>
const Inertia_<P>& SimTK::UnitInertia_< P >::asUnitInertia ( ) const
inline

Recast this UnitInertia matrix as a unit inertia matrix.

This is just for emphasis; a UnitInertia matrix is already a kind of Inertia matrix by inheritance.

◆ setFromUnitInertia()

template<class P>
UnitInertia_& SimTK::UnitInertia_< P >::setFromUnitInertia ( const Inertia_< P > &  inertia)
inline

Set from a unit inertia matrix.

Note that we can't check; every Inertia matrix can be interpreted as a unit inertia for some shape.

◆ isValidUnitInertiaMatrix()

template<class P>
static bool SimTK::UnitInertia_< P >::isValidUnitInertiaMatrix ( const SymMat33P m)
inlinestatic

Test some conditions that must hold for a valid UnitInertia matrix.

Cost is about 9 flops. TODO: this may not be comprehensive.

◆ pointMassAtOrigin()

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::pointMassAtOrigin ( )
inlinestatic

Create a UnitInertia matrix for a point located at the origin – that is, an all-zero matrix.

◆ pointMassAt()

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::pointMassAt ( const Vec3P p)
inlinestatic

Create a UnitInertia matrix for a point of unit mass located at a given location measured from origin OF and expressed in F (where F is the implicit frame of this UnitInertia matrix).

Cost is 11 flops.

◆ sphere()

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::sphere ( const RealP &  r)
inlinestatic

Create a UnitInertia matrix for a unit mass sphere of radius r centered at the origin.

◆ cylinderAlongZ()

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::cylinderAlongZ ( const RealP &  r,
const RealP &  hz 
)
inlinestatic

Unit-mass cylinder aligned along z axis; use radius and half-length.

If r==0 this is a thin rod; hz=0 it is a thin disk.

◆ cylinderAlongY()

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::cylinderAlongY ( const RealP &  r,
const RealP &  hy 
)
inlinestatic

Unit-mass cylinder aligned along y axis; use radius and half-length.

If r==0 this is a thin rod; hy=0 it is a thin disk.

◆ cylinderAlongX()

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::cylinderAlongX ( const RealP &  r,
const RealP &  hx 
)
inlinestatic

Unit-mass cylinder aligned along x axis; use radius and half-length.

If r==0 this is a thin rod; hx=0 it is a thin disk.

◆ brick() [1/2]

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::brick ( const RealP &  hx,
const RealP &  hy,
const RealP &  hz 
)
inlinestatic

Unit-mass brick given by half-lengths in each direction.

One dimension zero gives inertia of a thin rectangular sheet; two zero gives inertia of a thin rod in the remaining direction.

◆ brick() [2/2]

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::brick ( const Vec3P halfLengths)
inlinestatic

Alternate interface to brick() that takes a Vec3 for the half lengths.

◆ ellipsoid() [1/2]

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::ellipsoid ( const RealP &  hx,
const RealP &  hy,
const RealP &  hz 
)
inlinestatic

Unit-mass ellipsoid given by half-lengths in each direction.

◆ ellipsoid() [2/2]

template<class P>
static UnitInertia_ SimTK::UnitInertia_< P >::ellipsoid ( const Vec3P halfLengths)
inlinestatic

Alternate interface to ellipsoid() that takes a Vec3 for the half lengths.


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