A class for inertial information about a rigid body consisting of the scalar mass and a 3x3 symmetric moment of inertia matrix stored as two Vector3's. More...
#include <gz/math/MassMatrix3.hh>
Public Member Functions | |
MassMatrix3 () | |
Default Constructor, which inializes the mass and moments to zero. More... | |
MassMatrix3 (const MassMatrix3< T > &_m)=default | |
Copy constructor. More... | |
MassMatrix3 (const T &_mass, const Vector3< T > &_ixxyyzz, const Vector3< T > &_ixyxzyz) | |
Constructor. More... | |
~MassMatrix3 ()=default | |
Destructor. More... | |
Vector3< T > | DiagonalMoments () const |
Get the diagonal moments of inertia (Ixx, Iyy, Izz). More... | |
T | Epsilon (const T _tolerance=GZ_MASSMATRIX3_DEFAULT_TOLERANCE< T >) const |
Get an epsilon value that represents the amount of acceptable error in a MassMatrix3. The epsilon value is related to machine precision multiplied by the largest possible moment of inertia. More... | |
bool | EquivalentBox (Vector3< T > &_size, Quaternion< T > &_rot, const T _tol=1e-6) const |
Get dimensions and rotation offset of uniform box with equivalent mass and moment of inertia. To compute this, the Matrix3 is diagonalized. The eigenvalues on the diagonal and the rotation offset of the principal axes are returned. More... | |
bool | IsNearPositive (const T _tolerance=GZ_MASSMATRIX3_DEFAULT_TOLERANCE< T >) const |
Verify that inertia values are positive semidefinite. More... | |
bool | IsPositive (const T _tolerance=GZ_MASSMATRIX3_DEFAULT_TOLERANCE< T >) const |
Verify that inertia values are positive definite. More... | |
bool | IsValid (const T _tolerance=GZ_MASSMATRIX3_DEFAULT_TOLERANCE< T >) const |
Verify that inertia values are positive semi-definite and satisfy the triangle inequality. More... | |
T | Ixx () const |
Get IXX. More... | |
T | Ixy () const |
Get IXY. More... | |
T | Ixz () const |
Get IXZ. More... | |
T | Iyy () const |
Get IYY. More... | |
T | Iyz () const |
Get IYZ. More... | |
T | Izz () const |
Get IZZ. More... | |
T | Mass () const |
Get the mass. More... | |
Matrix3< T > | Moi () const |
returns Moments of Inertia as a Matrix3 More... | |
Vector3< T > | OffDiagonalMoments () const |
Get the off-diagonal moments of inertia (Ixy, Ixz, Iyz). More... | |
bool | operator!= (const MassMatrix3< T > &_m) const |
Inequality test operator. More... | |
MassMatrix3 & | operator= (const MassMatrix3< T > &_massMatrix)=default |
Equal operator. More... | |
bool | operator== (const MassMatrix3< T > &_m) const |
Equality comparison operator. More... | |
Quaternion< T > | PrincipalAxesOffset (const T _tol=1e-6) const |
Compute rotational offset of principal axes. More... | |
Vector3< T > | PrincipalMoments (const T _tol=1e-6) const |
Compute principal moments of inertia, which are the eigenvalues of the moment of inertia matrix. More... | |
bool | SetDiagonalMoments (const Vector3< T > &_ixxyyzz) |
Set the diagonal moments of inertia (Ixx, Iyy, Izz). More... | |
bool | SetFromBox (const Material &_mat, const Vector3< T > &_size, const Quaternion< T > &_rot=Quaternion< T >::Identity) |
Set inertial properties based on a Material and equivalent box. More... | |
bool | SetFromBox (const T _mass, const Vector3< T > &_size, const Quaternion< T > &_rot=Quaternion< T >::Identity) |
Set inertial properties based on mass and equivalent box. More... | |
bool | SetFromBox (const Vector3< T > &_size, const Quaternion< T > &_rot=Quaternion< T >::Identity) |
Set inertial properties based on equivalent box using the current mass value. More... | |
bool | SetFromConeZ (const Material &_mat, const T _length, const T _radius, const Quaternion< T > &_rot=Quaternion< T >::Identity) |
Set inertial properties based on a Material and equivalent cone aligned with Z axis. More... | |
bool | SetFromConeZ (const T _length, const T _radius, const Quaternion< T > &_rot) |
Set inertial properties based on equivalent cone aligned with Z axis using the current mass value. More... | |
bool | SetFromConeZ (const T _mass, const T _length, const T _radius, const Quaternion< T > &_rot=Quaternion< T >::Identity) |
Set inertial properties based on mass and equivalent cone aligned with Z axis. More... | |
bool | SetFromCylinderZ (const Material &_mat, const T _length, const T _radius, const Quaternion< T > &_rot=Quaternion< T >::Identity) |
Set inertial properties based on a Material and equivalent cylinder aligned with Z axis. More... | |
bool | SetFromCylinderZ (const T _length, const T _radius, const Quaternion< T > &_rot) |
Set inertial properties based on equivalent cylinder aligned with Z axis using the current mass value. More... | |
bool | SetFromCylinderZ (const T _mass, const T _length, const T _radius, const Quaternion< T > &_rot=Quaternion< T >::Identity) |
Set inertial properties based on mass and equivalent cylinder aligned with Z axis. More... | |
bool | SetFromSphere (const Material &_mat, const T _radius) |
Set inertial properties based on a material and equivalent sphere. More... | |
bool | SetFromSphere (const T _mass, const T _radius) |
Set inertial properties based on mass and equivalent sphere. More... | |
bool | SetFromSphere (const T _radius) |
Set inertial properties based on equivalent sphere using the current mass value. More... | |
bool | SetInertiaMatrix (const T &_ixx, const T &_iyy, const T &_izz, const T &_ixy, const T &_ixz, const T &_iyz) |
Set the moment of inertia matrix. More... | |
bool | SetIxx (const T &_v) |
Set IXX. More... | |
bool | SetIxy (const T &_v) |
Set IXY. More... | |
bool | SetIxz (const T &_v) |
Set IXZ. More... | |
bool | SetIyy (const T &_v) |
Set IYY. More... | |
bool | SetIyz (const T &_v) |
Set IYZ. More... | |
bool | SetIzz (const T &_v) |
Set IZZ. More... | |
bool | SetMass (const T &_m) |
Set the mass. More... | |
bool | SetMoi (const Matrix3< T > &_moi) |
Sets Moments of Inertia (MOI) from a Matrix3. Symmetric component of input matrix is used by averaging off-axis terms. More... | |
bool | SetOffDiagonalMoments (const Vector3< T > &_ixyxzyz) |
Set the off-diagonal moments of inertia (Ixy, Ixz, Iyz). More... | |
Static Public Member Functions | |
static T | Epsilon (const Vector3< T > &_moments, const T _tolerance=GZ_MASSMATRIX3_DEFAULT_TOLERANCE< T >) |
Get an epsilon value that represents the amount of acceptable error in a MassMatrix3. The epsilon value is related to machine precision multiplied by the largest possible moment of inertia. More... | |
static bool | ValidMoments (const Vector3< T > &_moments, const T _tolerance=GZ_MASSMATRIX3_DEFAULT_TOLERANCE< T >) |
Verify that principal moments are positive and satisfy the triangle inequality. More... | |
Detailed Description
template<typename T>
class gz::math::MassMatrix3< T >
A class for inertial information about a rigid body consisting of the scalar mass and a 3x3 symmetric moment of inertia matrix stored as two Vector3's.
Constructor & Destructor Documentation
◆ MassMatrix3() [1/3]
|
inline |
Default Constructor, which inializes the mass and moments to zero.
◆ MassMatrix3() [2/3]
|
inline |
Constructor.
- Parameters
-
[in] _mass Mass value in kg if using metric. [in] _ixxyyzz Diagonal moments of inertia. [in] _ixyxzyz Off-diagonal moments of inertia
◆ MassMatrix3() [3/3]
|
default |
Copy constructor.
- Parameters
-
[in] _m MassMatrix3 element to copy
◆ ~MassMatrix3()
|
default |
Destructor.
Member Function Documentation
◆ DiagonalMoments()
|
inline |
Get the diagonal moments of inertia (Ixx, Iyy, Izz).
- Returns
- The diagonal moments.
Referenced by MassMatrix3< T >::Epsilon(), and MassMatrix3< T >::operator==().
◆ Epsilon() [1/2]
|
inline |
Get an epsilon value that represents the amount of acceptable error in a MassMatrix3. The epsilon value is related to machine precision multiplied by the largest possible moment of inertia.
- Parameters
-
[in] _tolerance A factor that is used to adjust the return value. A value of zero will cause the return value to be zero. A good value is 10, which is also the MASSMATRIX3_DEFAULT_TOLERANCE.
References MassMatrix3< T >::DiagonalMoments().
Referenced by MassMatrix3< T >::IsNearPositive(), MassMatrix3< T >::IsPositive(), and MassMatrix3< T >::ValidMoments().
◆ Epsilon() [2/2]
|
inlinestatic |
Get an epsilon value that represents the amount of acceptable error in a MassMatrix3. The epsilon value is related to machine precision multiplied by the largest possible moment of inertia.
This function is used by IsValid(), IsNearPositive(), IsPositive(), and ValidMoments().
- Parameters
-
[in] _moments Principal moments of inertia. [in] _tolerance A factor that is used to adjust the return value. A value of zero will cause the return value to be zero. A good value is 10, which is also the MASSMATRIX3_DEFAULT_TOLERANCE.
- Returns
- The epsilon value computed using:
References numeric_limits::epsilon(), and Vector3< T >::Sum().
◆ EquivalentBox()
|
inline |
Get dimensions and rotation offset of uniform box with equivalent mass and moment of inertia. To compute this, the Matrix3 is diagonalized. The eigenvalues on the diagonal and the rotation offset of the principal axes are returned.
- Parameters
-
[in] _size Dimensions of box aligned with principal axes. [in] _rot Rotational offset of principal axes. [in] _tol Relative tolerance.
- Returns
- True if box properties were computed successfully.
- Todo:
- Use a mock class to test this line
References MassMatrix3< T >::IsPositive(), MassMatrix3< T >::PrincipalAxesOffset(), MassMatrix3< T >::PrincipalMoments(), MassMatrix3< T >::ValidMoments(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
◆ IsNearPositive()
|
inline |
Verify that inertia values are positive semidefinite.
- Parameters
-
[in] _tolerance The amount of relative error to accept when checking whether this MassMatrix3 has a valid mass and moment of inertia. Refer to Epsilon() for a description of _tolerance.
- Returns
- True if mass is nonnegative and moment of inertia matrix is positive semidefinite. The following is how the return value is calculated
References MassMatrix3< T >::Epsilon(), MassMatrix3< T >::Ixx(), MassMatrix3< T >::Ixy(), MassMatrix3< T >::Iyy(), MassMatrix3< T >::Moi(), and std::pow().
Referenced by MassMatrix3< T >::IsValid().
◆ IsPositive()
|
inline |
Verify that inertia values are positive definite.
- Parameters
-
[in] _tolerance The amount of error to accept when checking whether this MassMatrix3 has a valid mass and moment of inertia. Refer to Epsilon() for a description of _tolerance.
- Returns
- True if mass is positive and moment of inertia matrix is positive definite. The following is how the return value is calculated
References MassMatrix3< T >::Epsilon(), MassMatrix3< T >::Ixx(), MassMatrix3< T >::Ixy(), MassMatrix3< T >::Iyy(), MassMatrix3< T >::Moi(), and std::pow().
Referenced by MassMatrix3< T >::EquivalentBox().
◆ IsValid()
|
inline |
Verify that inertia values are positive semi-definite and satisfy the triangle inequality.
- Parameters
-
[in] _tolerance The amount of error to accept when checking whether the MassMatrix3 has a valid mass and moment of inertia. This value is passed on to IsNearPositive() and ValidMoments(), which in turn pass the tolerance value to Epsilon(). Refer to Epsilon() for a description of _tolerance.
- Returns
- True if IsNearPositive(_tolerance) and ValidMoments(this->PrincipalMoments(), _tolerance) both return true.
References MassMatrix3< T >::IsNearPositive(), MassMatrix3< T >::PrincipalMoments(), and MassMatrix3< T >::ValidMoments().
Referenced by MassMatrix3< T >::SetDiagonalMoments(), MassMatrix3< T >::SetInertiaMatrix(), MassMatrix3< T >::SetIxx(), MassMatrix3< T >::SetIxy(), MassMatrix3< T >::SetIxz(), MassMatrix3< T >::SetIyy(), MassMatrix3< T >::SetIyz(), MassMatrix3< T >::SetIzz(), MassMatrix3< T >::SetMass(), MassMatrix3< T >::SetMoi(), and MassMatrix3< T >::SetOffDiagonalMoments().
◆ Ixx()
|
inline |
Get IXX.
- Returns
- IXX value
Referenced by MassMatrix3< T >::IsNearPositive(), and MassMatrix3< T >::IsPositive().
◆ Ixy()
|
inline |
Get IXY.
- Returns
- IXY value
Referenced by MassMatrix3< T >::IsNearPositive(), and MassMatrix3< T >::IsPositive().
◆ Ixz()
|
inline |
Get IXZ.
- Returns
- IXZ value
◆ Iyy()
|
inline |
Get IYY.
- Returns
- IYY value
Referenced by MassMatrix3< T >::IsNearPositive(), and MassMatrix3< T >::IsPositive().
◆ Iyz()
|
inline |
Get IYZ.
- Returns
- IYZ value
◆ Izz()
|
inline |
Get IZZ.
- Returns
- IZZ value
◆ Mass()
|
inline |
Get the mass.
- Returns
- The mass value
Referenced by MassMatrix3< T >::operator==(), MassMatrix3< T >::SetFromBox(), MassMatrix3< T >::SetFromConeZ(), MassMatrix3< T >::SetFromCylinderZ(), and MassMatrix3< T >::SetFromSphere().
◆ Moi()
|
inline |
returns Moments of Inertia as a Matrix3
- Returns
- Moments of Inertia as a Matrix3
Referenced by MassMatrix3< T >::IsNearPositive(), and MassMatrix3< T >::IsPositive().
◆ OffDiagonalMoments()
|
inline |
Get the off-diagonal moments of inertia (Ixy, Ixz, Iyz).
- Returns
- The off-diagonal moments of inertia.
Referenced by MassMatrix3< T >::operator==().
◆ operator!=()
|
inline |
Inequality test operator.
- Parameters
-
[in] _m MassMatrix3<T> to test
- Returns
- True if not equal (using the default tolerance of 1e-6)
◆ operator=()
|
default |
◆ operator==()
|
inline |
Equality comparison operator.
- Parameters
-
[in] _m MassMatrix3 to copy.
- Returns
- true if each component is equal within a default tolerance, false otherwise
References MassMatrix3< T >::DiagonalMoments(), MassMatrix3< T >::Mass(), and MassMatrix3< T >::OffDiagonalMoments().
◆ PrincipalAxesOffset()
|
inline |
Compute rotational offset of principal axes.
- Parameters
-
[in] _tol Relative tolerance given by absolute value of _tol. Negative values of _tol are interpreted as a flag that causes principal moments to always be sorted from smallest to largest.
- Returns
- Quaternion representing rotational offset of principal axes. With a rotation matrix constructed from this quaternion R(q) and a diagonal matrix L with principal moments on the diagonal, the original moment of inertia matrix MOI can be reconstructed with MOI = R(q).Transpose() * L * R(q)
- Todo:
- Use a mock class to test this line
References Vector3< T >::Equal(), GZ_PI_2, Quaternion< T >::Inverse(), Angle::Normalize(), std::pow(), MassMatrix3< T >::PrincipalMoments(), Angle::Radian(), Vector2< T >::Set(), and Vector2< T >::SquaredLength().
Referenced by MassMatrix3< T >::EquivalentBox().
◆ PrincipalMoments()
|
inline |
Compute principal moments of inertia, which are the eigenvalues of the moment of inertia matrix.
- Parameters
-
[in] _tol Relative tolerance given by absolute value of _tol. Negative values of _tol are interpreted as a flag that causes principal moments to always be sorted from smallest to largest.
- Returns
- Principal moments of inertia. If the matrix is already diagonal and _tol is positive, they are returned in the existing order. Otherwise, the moments are sorted from smallest to largest.
References GZ_PI, std::pow(), gz::math::sort3(), and Vector3< T >::Sum().
Referenced by MassMatrix3< T >::EquivalentBox(), MassMatrix3< T >::IsValid(), and MassMatrix3< T >::PrincipalAxesOffset().
◆ SetDiagonalMoments()
|
inline |
Set the diagonal moments of inertia (Ixx, Iyy, Izz).
- Parameters
-
[in] _ixxyyzz diagonal moments of inertia
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetFromBox() [1/3]
|
inline |
Set inertial properties based on a Material and equivalent box.
- Parameters
-
[in] _mat Material that specifies a density. Uniform density is used. [in] _size Size of equivalent box. [in] _rot Rotational offset of equivalent box.
- Returns
- True if inertial properties were set successfully.
References Material::Density(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
Referenced by OrientedBox< T >::MassMatrix(), and MassMatrix3< T >::SetFromBox().
◆ SetFromBox() [2/3]
|
inline |
Set inertial properties based on mass and equivalent box.
- Parameters
-
[in] _mass Mass to set. [in] _size Size of equivalent box. [in] _rot Rotational offset of equivalent box.
- Returns
- True if inertial properties were set successfully.
References Vector3< T >::Min(), MassMatrix3< T >::SetFromBox(), and MassMatrix3< T >::SetMass().
◆ SetFromBox() [3/3]
|
inline |
Set inertial properties based on equivalent box using the current mass value.
- Parameters
-
[in] _size Size of equivalent box. [in] _rot Rotational offset of equivalent box.
- Returns
- True if inertial properties were set successfully.
References MassMatrix3< T >::Mass(), Vector3< T >::Min(), std::pow(), MassMatrix3< T >::SetMoi(), Matrix3< T >::Transposed(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
◆ SetFromConeZ() [1/3]
|
inline |
Set inertial properties based on a Material and equivalent cone aligned with Z axis.
- Parameters
-
[in] _mat Material that specifies a density. Uniform density is used. [in] _length Length of cone along Z axis. [in] _radius Radius of cone. [in] _rot Rotational offset of equivalent cone.
- Returns
- True if inertial properties were set successfully.
References Material::Density(), and GZ_PI.
Referenced by MassMatrix3< T >::SetFromConeZ().
◆ SetFromConeZ() [2/3]
|
inline |
Set inertial properties based on equivalent cone aligned with Z axis using the current mass value.
- Parameters
-
[in] _length Length of cone along Z axis. [in] _radius Radius of cone. [in] _rot Rotational offset of equivalent cone.
- Returns
- True if inertial properties were set successfully.
References MassMatrix3< T >::Mass(), std::pow(), MassMatrix3< T >::SetMoi(), and Matrix3< T >::Transposed().
◆ SetFromConeZ() [3/3]
|
inline |
Set inertial properties based on mass and equivalent cone aligned with Z axis.
- Parameters
-
[in] _mass Mass to set. [in] _length Length of cone along Z axis. [in] _radius Radius of cone. [in] _rot Rotational offset of equivalent cone.
- Returns
- True if inertial properties were set successfully.
References MassMatrix3< T >::SetFromConeZ(), and MassMatrix3< T >::SetMass().
◆ SetFromCylinderZ() [1/3]
|
inline |
Set inertial properties based on a Material and equivalent cylinder aligned with Z axis.
- Parameters
-
[in] _mat Material that specifies a density. Uniform density is used. [in] _length Length of cylinder along Z axis. [in] _radius Radius of cylinder. [in] _rot Rotational offset of equivalent cylinder.
- Returns
- True if inertial properties were set successfully.
References Material::Density(), and GZ_PI.
Referenced by MassMatrix3< T >::SetFromCylinderZ().
◆ SetFromCylinderZ() [2/3]
|
inline |
Set inertial properties based on equivalent cylinder aligned with Z axis using the current mass value.
- Parameters
-
[in] _length Length of cylinder along Z axis. [in] _radius Radius of cylinder. [in] _rot Rotational offset of equivalent cylinder.
- Returns
- True if inertial properties were set successfully.
References MassMatrix3< T >::Mass(), std::pow(), MassMatrix3< T >::SetMoi(), and Matrix3< T >::Transposed().
◆ SetFromCylinderZ() [3/3]
|
inline |
Set inertial properties based on mass and equivalent cylinder aligned with Z axis.
- Parameters
-
[in] _mass Mass to set. [in] _length Length of cylinder along Z axis. [in] _radius Radius of cylinder. [in] _rot Rotational offset of equivalent cylinder.
- Returns
- True if inertial properties were set successfully.
References MassMatrix3< T >::SetFromCylinderZ(), and MassMatrix3< T >::SetMass().
◆ SetFromSphere() [1/3]
|
inline |
Set inertial properties based on a material and equivalent sphere.
- Parameters
-
[in] _mat Material that specifies a density. Uniform density is used. [in] _radius Radius of equivalent, uniform sphere.
- Returns
- True if inertial properties were set successfully.
References Material::Density(), GZ_PI, and std::pow().
Referenced by MassMatrix3< T >::SetFromSphere().
◆ SetFromSphere() [2/3]
|
inline |
Set inertial properties based on mass and equivalent sphere.
- Parameters
-
[in] _mass Mass to set. [in] _radius Radius of equivalent, uniform sphere.
- Returns
- True if inertial properties were set successfully.
References MassMatrix3< T >::SetFromSphere(), and MassMatrix3< T >::SetMass().
◆ SetFromSphere() [3/3]
|
inline |
Set inertial properties based on equivalent sphere using the current mass value.
- Parameters
-
[in] _radius Radius of equivalent, uniform sphere.
- Returns
- True if inertial properties were set successfully.
References MassMatrix3< T >::Mass(), std::pow(), and MassMatrix3< T >::SetMoi().
◆ SetInertiaMatrix()
|
inline |
Set the moment of inertia matrix.
- Parameters
-
[in] _ixx X second moment of inertia (MOI) about x axis. [in] _iyy Y second moment of inertia about y axis. [in] _izz Z second moment of inertia about z axis. [in] _ixy XY inertia. [in] _ixz XZ inertia. [in] _iyz YZ inertia.
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetIxx()
|
inline |
Set IXX.
- Parameters
-
[in] _v IXX value
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetIxy()
|
inline |
Set IXY.
- Parameters
-
[in] _v IXY value
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetIxz()
|
inline |
Set IXZ.
- Parameters
-
[in] _v IXZ value
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetIyy()
|
inline |
Set IYY.
- Parameters
-
[in] _v IYY value
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetIyz()
|
inline |
Set IYZ.
- Parameters
-
[in] _v IYZ value
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetIzz()
|
inline |
Set IZZ.
- Parameters
-
[in] _v IZZ value
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ SetMass()
|
inline |
Set the mass.
- Parameters
-
[in] _m New mass value.
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
Referenced by MassMatrix3< T >::SetFromBox(), MassMatrix3< T >::SetFromConeZ(), MassMatrix3< T >::SetFromCylinderZ(), and MassMatrix3< T >::SetFromSphere().
◆ SetMoi()
|
inline |
Sets Moments of Inertia (MOI) from a Matrix3. Symmetric component of input matrix is used by averaging off-axis terms.
- Parameters
-
[in] _moi Moments of Inertia as a Matrix3
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
Referenced by MassMatrix3< T >::SetFromBox(), MassMatrix3< T >::SetFromConeZ(), MassMatrix3< T >::SetFromCylinderZ(), and MassMatrix3< T >::SetFromSphere().
◆ SetOffDiagonalMoments()
|
inline |
Set the off-diagonal moments of inertia (Ixy, Ixz, Iyz).
- Parameters
-
[in] _ixyxzyz off-diagonal moments of inertia
- Returns
- True if the MassMatrix3 is valid.
References MassMatrix3< T >::IsValid().
◆ ValidMoments()
|
inlinestatic |
Verify that principal moments are positive and satisfy the triangle inequality.
- Parameters
-
[in] _moments Principal moments of inertia. [in] _tolerance The amount of error to accept when checking whether the moments are positive and satisfy the triangle inequality. Refer to Epsilon() for a description of _tolerance.
- Returns
- True if moments of inertia are positive and satisfy the triangle inequality. The following is how the return value is calculated.
References MassMatrix3< T >::Epsilon().
Referenced by MassMatrix3< T >::EquivalentBox(), and MassMatrix3< T >::IsValid().
The documentation for this class was generated from the following file: