pub struct RigidBodyInertia {
pub mass: Real,
pub h: Vec3,
pub inertia: SymmetricMat3,
}Expand description
Rigid body spatial inertia matrix implementing Featherstone’s spatial inertia formulation.
This represents the complete 6×6 inertia matrix of a rigid body in spatial algebra, combining both rotational and translational inertia properties. The spatial inertia relates spatial motion to spatial force: f = I·v
§Matrix Structure
The spatial inertia matrix has the form:
| I_3×3 h× |
I = | |
| -h× m |where:
I_3×3: 3×3 rotational inertia tensor about the body-fixed frame originh: mass × center of mass position (first moment of mass)m: scalar massh×: cross-product matrix of h (skew-symmetric matrix)
§Physical Meaning
The spatial inertia captures both:
- Rotational inertia: resistance to angular acceleration
- Linear inertia: resistance to linear acceleration
- Coupling effects: how linear motion creates moments and vice versa
Fields§
§mass: RealTotal mass of the rigid body.
h: Vec3First moment of mass: h = mass × center_of_mass
This vector couples linear and angular motion in the spatial inertia matrix. When expressed about the center of mass, this becomes zero.
inertia: SymmetricMat3Rotational inertia tensor expressed as a symmetric 3×3 matrix.
This is the lower triangular representation of the 3×3 rotational inertia tensor about the origin of the body-fixed coordinate frame.
Implementations§
Source§impl RigidBodyInertia
impl RigidBodyInertia
Sourcepub const ZERO: RigidBodyInertia
pub const ZERO: RigidBodyInertia
Zero rigid body inertia (massless body).
Useful for initialization and as the identity element for certain inertia operations.
Sourcepub fn new(mass: Real, center_of_mass: Vec3, inertia_com: SymmetricMat3) -> Self
pub fn new(mass: Real, center_of_mass: Vec3, inertia_com: SymmetricMat3) -> Self
Create a new rigid body spatial inertia from physical properties.
This method constructs the spatial inertia matrix using the parallel axis theorem to shift the inertia from the center of mass to the specified reference point.
§Arguments
mass- Total mass of the rigid body (must be positive)center_of_mass- Center of mass position relative to the reference frame origininertia_com- 3×3 rotational inertia tensor about the center of mass
§Mathematical Transformation
The parallel axis theorem transforms inertia from center of mass (CoM) to reference point:
I_origin = I_com + m[(c·c)I - ccᵀ]where c is the center of mass vector and I is the 3×3 identity matrix.
§Physical Interpretation
- If
center_of_mass = [0, 0, 0], the inertia is expressed about theCoM - The resulting inertia relates spatial motion to spatial force about the origin
- Positive mass ensures physically meaningful inertia properties
§Panics
Panics if mass is not positive, as negative or zero mass is non-physical.
Sourcepub fn scale(&self, scalar: Real) -> Self
pub fn scale(&self, scalar: Real) -> Self
Scale the rigid body inertia by a scalar factor.
This operation multiplies all inertia components by the given scalar, effectively scaling the mass and all inertia properties proportionally.
§Mathematical Meaning
Given spatial inertia I and scalar s:
I_scaled = s · IThis is useful for scaling body properties or creating proportional inertia variations.
Sourcepub fn add(&self, rhs: Self) -> Self
pub fn add(&self, rhs: Self) -> Self
Add two rigid body inertias.
This operation combines two rigid bodies into a composite body, assuming they are expressed in the same coordinate frame and about the same reference point.
§Physical Meaning
The resulting inertia represents the combined properties of both bodies:
- Total mass is the sum of individual masses
- First moment of mass (h) is additive
- Rotational inertia tensors are additive
§Use Case
Commonly used when constructing composite bodies or combining multiple rigid components into a single equivalent body.
Sourcepub fn mul_vec(&self, motion_vec: SpatialMotionVector) -> SpatialForceVector
pub fn mul_vec(&self, motion_vec: SpatialMotionVector) -> SpatialForceVector
Multiply spatial inertia with a spatial motion vector to get spatial force.
This implements the fundamental dynamics equation: f = I·v where f is spatial force, I is spatial inertia, and v is spatial motion.
§Mathematical Formulation
Given motion vector v = [ω, v] and spatial inertia I:
f = I · v = [n]
[f]
where:
n = I_3×3 · ω + h × v (moment/torque)
f = m·v - h × ω (force)§Physical Interpretation
- The moment n includes rotational inertia effects and coupling from linear motion
- The force f includes translational inertia effects and coupling from angular motion
- Cross terms (h × v and h × ω) represent the coupling between rotation and translation
This is the core operation in forward dynamics for calculating forces from accelerations.
pub fn matrix(&self) -> SMatrix<6, 6>
Sourcepub fn into_array(self) -> [Real; 10]
pub fn into_array(self) -> [Real; 10]
Convert the RigidBodyInertia to an array of 10 elements. The data layout is:
| mass | h.x | h.y | h.z | inertia[0]|...|inertia[9]Trait Implementations§
Source§impl Add<RigidBodyInertia> for ArticulatedBodyInertia
impl Add<RigidBodyInertia> for ArticulatedBodyInertia
Source§type Output = ArticulatedBodyInertia
type Output = ArticulatedBodyInertia
+ operator.Source§impl Add for RigidBodyInertia
impl Add for RigidBodyInertia
Source§impl Clone for RigidBodyInertia
impl Clone for RigidBodyInertia
Source§fn clone(&self) -> RigidBodyInertia
fn clone(&self) -> RigidBodyInertia
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for RigidBodyInertia
impl Debug for RigidBodyInertia
Source§impl Default for RigidBodyInertia
impl Default for RigidBodyInertia
Source§impl From<RigidBodyInertia> for [Real; 10]
impl From<RigidBodyInertia> for [Real; 10]
Source§fn from(val: RigidBodyInertia) -> Self
fn from(val: RigidBodyInertia) -> Self
Source§impl From<RigidBodyInertia> for ArticulatedBodyInertia
impl From<RigidBodyInertia> for ArticulatedBodyInertia
Source§fn from(value: RigidBodyInertia) -> Self
fn from(value: RigidBodyInertia) -> Self
Source§impl Mul<SpatialVector<Motion>> for RigidBodyInertia
impl Mul<SpatialVector<Motion>> for RigidBodyInertia
Source§type Output = SpatialVector<Force>
type Output = SpatialVector<Force>
* operator.Source§impl Mul<f32> for RigidBodyInertia
impl Mul<f32> for RigidBodyInertia
impl Copy for RigidBodyInertia
Auto Trait Implementations§
impl Freeze for RigidBodyInertia
impl RefUnwindSafe for RigidBodyInertia
impl Send for RigidBodyInertia
impl Sync for RigidBodyInertia
impl Unpin for RigidBodyInertia
impl UnwindSafe for RigidBodyInertia
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.