RigidBodyInertia

Struct RigidBodyInertia 

Source
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 origin
  • h: mass × center of mass position (first moment of mass)
  • m: scalar mass
  • : cross-product matrix of h (skew-symmetric matrix)

§Physical Meaning

The spatial inertia captures both:

  1. Rotational inertia: resistance to angular acceleration
  2. Linear inertia: resistance to linear acceleration
  3. Coupling effects: how linear motion creates moments and vice versa

Fields§

§mass: Real

Total mass of the rigid body.

§h: Vec3

First 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: SymmetricMat3

Rotational 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

Source

pub const ZERO: RigidBodyInertia

Zero rigid body inertia (massless body).

Useful for initialization and as the identity element for certain inertia operations.

Source

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 origin
  • inertia_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 the CoM
  • 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.

Source

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 · I

This is useful for scaling body properties or creating proportional inertia variations.

Source

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.

Source

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.

Source

pub fn matrix(&self) -> SMatrix<6, 6>

Source

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

Source§

type Output = ArticulatedBodyInertia

The resulting type after applying the + operator.
Source§

fn add(self, rhs: RigidBodyInertia) -> Self::Output

Performs the + operation. Read more
Source§

impl Add for RigidBodyInertia

Source§

type Output = RigidBodyInertia

The resulting type after applying the + operator.
Source§

fn add(self, rhs: Self) -> Self::Output

Performs the + operation. Read more
Source§

impl Clone for RigidBodyInertia

Source§

fn clone(&self) -> RigidBodyInertia

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for RigidBodyInertia

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Default for RigidBodyInertia

Source§

fn default() -> Self

Returns the “default value” for a type. Read more
Source§

impl From<RigidBodyInertia> for [Real; 10]

Source§

fn from(val: RigidBodyInertia) -> Self

Converts to this type from the input type.
Source§

impl From<RigidBodyInertia> for ArticulatedBodyInertia

Source§

fn from(value: RigidBodyInertia) -> Self

Converts to this type from the input type.
Source§

impl Mul<SpatialVector<Motion>> for RigidBodyInertia

Source§

type Output = SpatialVector<Force>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: SpatialMotionVector) -> Self::Output

Performs the * operation. Read more
Source§

impl Mul<f32> for RigidBodyInertia

Source§

type Output = RigidBodyInertia

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Real) -> Self::Output

Performs the * operation. Read more
Source§

impl Copy for RigidBodyInertia

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.