spatial_math/
spatial_inertia.rs

1// Copyright (C) 2020-2025 spatial-math authors. All Rights Reserved.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7//     http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15use std::ops::{Add, AddAssign, Mul, Sub};
16
17use super::exts::Vec3Ext;
18use super::matrix::SymmetricMat3;
19use super::{Mat3, SpatialForceVector, SpatialMotionVector, Vec3};
20use crate::{Real, SMatrix, VEC3_ZERO};
21
22/// Rigid body spatial inertia matrix implementing Featherstone's spatial inertia formulation.
23///
24/// This represents the complete 6×6 inertia matrix of a rigid body in spatial algebra,
25/// combining both rotational and translational inertia properties. The spatial inertia
26/// relates spatial motion to spatial force: f = I·v
27///
28/// # Matrix Structure
29///
30/// The spatial inertia matrix has the form:
31/// ```text
32///     | I_3×3   h× |
33/// I = |            |
34///     | -h×     m   |
35/// ```
36///
37/// where:
38/// - **`I_3×3`**: 3×3 rotational inertia tensor about the body-fixed frame origin
39/// - **`h`**: mass × center of mass position (first moment of mass)
40/// - **`m`**: scalar mass
41/// - **`h×`**: cross-product matrix of h (skew-symmetric matrix)
42///
43/// # Physical Meaning
44///
45/// The spatial inertia captures both:
46/// 1. **Rotational inertia**: resistance to angular acceleration
47/// 2. **Linear inertia**: resistance to linear acceleration
48/// 3. **Coupling effects**: how linear motion creates moments and vice versa
49#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
50#[derive(Clone, Copy, Debug)]
51pub struct RigidBodyInertia {
52    /// Total mass of the rigid body.
53    pub mass: Real,
54
55    /// First moment of mass: `h = mass × center_of_mass`
56    ///
57    /// This vector couples linear and angular motion in the spatial inertia matrix.
58    /// When expressed about the center of mass, this becomes zero.
59    pub h: Vec3,
60
61    /// Rotational inertia tensor expressed as a symmetric 3×3 matrix.
62    ///
63    /// This is the lower triangular representation of the 3×3 rotational
64    /// inertia tensor about the origin of the body-fixed coordinate frame.
65    pub inertia: SymmetricMat3,
66}
67
68impl Default for RigidBodyInertia {
69    fn default() -> Self {
70        Self::new(1.0, Vec3::zeros(), SymmetricMat3::ONE)
71    }
72}
73
74impl RigidBodyInertia {
75    /// Zero rigid body inertia (massless body).
76    ///
77    /// Useful for initialization and as the identity element
78    /// for certain inertia operations.
79    pub const ZERO: RigidBodyInertia = RigidBodyInertia {
80        mass: 0.0,
81        h: VEC3_ZERO,
82        inertia: SymmetricMat3::ZERO,
83    };
84
85    /// Create a new rigid body spatial inertia from physical properties.
86    ///
87    /// This method constructs the spatial inertia matrix using the parallel axis theorem
88    /// to shift the inertia from the center of mass to the specified reference point.
89    ///
90    /// # Arguments
91    ///
92    /// * `mass` - Total mass of the rigid body (must be positive)
93    /// * `center_of_mass` - Center of mass position relative to the reference frame origin
94    /// * `inertia_com` - 3×3 rotational inertia tensor about the center of mass
95    ///
96    /// # Mathematical Transformation
97    ///
98    /// The parallel axis theorem transforms inertia from center of mass (`CoM`) to reference point:
99    /// ```text
100    /// I_origin = I_com + m[(c·c)I - ccᵀ]
101    /// ```
102    /// where c is the center of mass vector and I is the 3×3 identity matrix.
103    ///
104    /// # Physical Interpretation
105    ///
106    /// - If `center_of_mass = [0, 0, 0]`, the inertia is expressed about the `CoM`
107    /// - The resulting inertia relates spatial motion to spatial force about the origin
108    /// - Positive mass ensures physically meaningful inertia properties
109    ///
110    /// # Panics
111    ///
112    /// Panics if mass is not positive, as negative or zero mass is non-physical.
113    #[inline]
114    pub fn new(mass: Real, center_of_mass: Vec3, inertia_com: SymmetricMat3) -> Self {
115        assert!(mass > 0.0, "mass must be positive:{mass}");
116        //TODO: check inertia_com is positive definite
117        let h = mass * center_of_mass;
118        let cx = center_of_mass.into_cross_matrix();
119        // parallel axis theorem
120        let top_left = inertia_com - SymmetricMat3::from(mass * cx * cx);
121        Self {
122            mass,
123            h,
124            inertia: top_left,
125        }
126    }
127
128    /// Scale the rigid body inertia by a scalar factor.
129    ///
130    /// This operation multiplies all inertia components by the given scalar,
131    /// effectively scaling the mass and all inertia properties proportionally.
132    ///
133    /// # Mathematical Meaning
134    ///
135    /// Given spatial inertia I and scalar s:
136    /// ```text
137    /// I_scaled = s · I
138    /// ```
139    ///
140    /// This is useful for scaling body properties or creating
141    /// proportional inertia variations.
142    #[inline]
143    #[must_use]
144    pub fn scale(&self, scalar: Real) -> Self {
145        Self {
146            mass: self.mass * scalar,
147            h: self.h * scalar,
148            inertia: self.inertia.scale(scalar),
149        }
150    }
151
152    /// Add two rigid body inertias.
153    ///
154    /// This operation combines two rigid bodies into a composite body,
155    /// assuming they are expressed in the same coordinate frame and about
156    /// the same reference point.
157    ///
158    /// # Physical Meaning
159    ///
160    /// The resulting inertia represents the combined properties of both bodies:
161    /// - Total mass is the sum of individual masses
162    /// - First moment of mass (h) is additive
163    /// - Rotational inertia tensors are additive
164    ///
165    /// # Use Case
166    ///
167    /// Commonly used when constructing composite bodies or combining
168    /// multiple rigid components into a single equivalent body.
169    #[inline]
170    #[must_use]
171    pub fn add(&self, rhs: Self) -> Self {
172        Self {
173            mass: self.mass + rhs.mass,
174            h: self.h + rhs.h,
175            inertia: self.inertia.add(rhs.inertia),
176        }
177    }
178
179    /// Multiply spatial inertia with a spatial motion vector to get spatial force.
180    ///
181    /// This implements the fundamental dynamics equation: f = I·v
182    /// where f is spatial force, I is spatial inertia, and v is spatial motion.
183    ///
184    /// # Mathematical Formulation
185    ///
186    /// Given motion vector v = [ω, v] and spatial inertia I:
187    /// ```text
188    /// f = I · v = [n]
189    ///           [f]
190    ///
191    /// where:
192    /// n = I_3×3 · ω + h × v  (moment/torque)
193    /// f = m·v - h × ω        (force)
194    /// ```
195    ///
196    /// # Physical Interpretation
197    ///
198    /// - The moment n includes rotational inertia effects and coupling from linear motion
199    /// - The force f includes translational inertia effects and coupling from angular motion
200    /// - Cross terms (h × v and h × ω) represent the coupling between rotation and translation
201    ///
202    /// This is the core operation in forward dynamics for calculating forces from accelerations.
203    #[inline]
204    pub fn mul_vec(&self, motion_vec: SpatialMotionVector) -> SpatialForceVector {
205        let motion_w = motion_vec.top;
206        let motion_v = motion_vec.bottom;
207        let h = self.h;
208        let m = self.mass;
209        let inertia = self.inertia;
210        // n = I * w + h x v
211        let force_n = inertia.mul_vec(motion_w) + h.cross(&motion_v);
212        let force_f = m * motion_v - h.cross(&motion_w);
213        SpatialForceVector::from_pair(force_n, force_f)
214    }
215
216    pub fn matrix(&self) -> SMatrix<6, 6> {
217        let mut result = SMatrix::<6, 6>::zeros();
218
219        // top left
220        result
221            .fixed_view_mut::<3, 3>(0, 0)
222            .copy_from(&self.inertia.mat3());
223        let h_crm = self.h.into_cross_matrix();
224
225        // top right
226        result.fixed_view_mut::<3, 3>(0, 3).copy_from(&h_crm);
227
228        // bottom left
229        result
230            .fixed_view_mut::<3, 3>(3, 0)
231            .copy_from(&h_crm.transpose());
232
233        // bootom right
234        let mass = Mat3::identity().scale(self.mass);
235        result.fixed_view_mut::<3, 3>(3, 3).copy_from(&mass);
236
237        result
238    }
239
240    /// Convert the `RigidBodyInertia` to an array of 10 elements. The data layout is:
241    ///
242    /// ```text
243    /// | mass | h.x | h.y | h.z | inertia[0]|...|inertia[9]
244    /// ```
245    #[inline]
246    pub fn into_array(self) -> [Real; 10] {
247        let mut array = [0.0; 10];
248        array[0] = self.mass;
249        array[1] = self.h.x;
250        array[2] = self.h.y;
251        array[3] = self.h.z;
252        let inertia_array = self.inertia.into_array();
253        array[4] = inertia_array[0];
254        array[5] = inertia_array[1];
255        array[6] = inertia_array[2];
256        array[7] = inertia_array[3];
257        array[8] = inertia_array[4];
258        array[9] = inertia_array[5];
259        array
260    }
261}
262
263impl From<RigidBodyInertia> for [Real; 10] {
264    #[inline]
265    fn from(val: RigidBodyInertia) -> Self {
266        val.into_array()
267    }
268}
269
270impl Mul<Real> for RigidBodyInertia {
271    type Output = Self;
272
273    #[inline]
274    fn mul(self, rhs: Real) -> Self::Output {
275        self.scale(rhs)
276    }
277}
278
279impl Add<Self> for RigidBodyInertia {
280    type Output = Self;
281
282    #[inline]
283    fn add(self, rhs: Self) -> Self::Output {
284        RigidBodyInertia::add(&self, rhs)
285    }
286}
287
288impl Mul<SpatialMotionVector> for RigidBodyInertia {
289    type Output = SpatialForceVector;
290
291    #[inline]
292    fn mul(self, rhs: SpatialMotionVector) -> Self::Output {
293        self.mul_vec(rhs)
294    }
295}
296
297/// Articulated body spatial inertia matrix for complex multi-body systems.
298///
299/// This represents the effective inertia of an articulated body, which accounts for
300/// the inertia of all bodies in the subtree beyond a given joint. Unlike rigid body
301/// inertia, articulated body inertia captures the dynamic coupling between joints
302/// in a kinematic chain.
303///
304/// # Matrix Structure
305///
306/// The articulated body inertia has the form:
307/// ```text
308///      | I   H |
309/// I_A = |      |
310///      | Hᵀ  M |
311/// ```
312///
313/// where:
314/// - **I**: 3×3 matrix representing rotational inertia effects
315/// - **H**: 3×3 matrix representing coupling between rotation and translation
316/// - **M**: 3×3 matrix representing translational inertia effects
317///
318/// # Physical Meaning
319///
320/// Articulated body inertia represents the effective inertia seen at a joint
321/// when all bodies beyond that joint move together. It accounts for:
322///
323/// 1. **Propagated inertia**: Inertia of all bodies in the subtree
324/// 2. **Dynamic coupling**: How motion at one joint affects other joints
325/// 3. **Constraint forces**: Forces transmitted through the kinematic chain
326///
327/// # Use in Dynamics
328///
329/// This is a key component in Featherstone's Articulated Body Algorithm:
330/// - Used in forward dynamics to compute joint accelerations
331/// - Captures the influence of the entire subtree on each joint
332/// - Enables O(n) complexity dynamics for tree-structured mechanisms
333///
334/// # Storage
335///
336/// The matrix stores 21 independent elements (6 for I, 9 for H, 6 for M),
337/// optimized for the symmetric structure of the top-left and bottom-right blocks.
338#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
339#[derive(Clone, Debug, Default)]
340pub struct ArticulatedBodyInertia {
341    /// Top-left 3×3 block (I) of the articulated body inertia matrix.
342    ///
343    /// This symmetric matrix represents rotational inertia effects and
344    /// couples angular accelerations to resulting moments.
345    pub top_left: SymmetricMat3,
346
347    /// Top-right 3×3 block (H) of the articulated body inertia matrix.
348    ///
349    /// This general (non-symmetric) matrix represents cross-coupling
350    /// between rotational and translational motion in the articulated system.
351    pub h: SMatrix<3, 3>,
352
353    /// Bottom-right 3×3 block (M) of the articulated body inertia matrix.
354    ///
355    /// This symmetric matrix represents translational inertia effects and
356    /// couples linear accelerations to resulting forces.
357    pub mass: SymmetricMat3,
358}
359
360impl ArticulatedBodyInertia {
361    #[inline]
362    #[must_use]
363    pub fn add_arti_inertia(&self, rhs: &Self) -> Self {
364        Self {
365            top_left: self.top_left.add(rhs.top_left),
366            h: self.h + rhs.h,
367            mass: self.mass.add(rhs.mass),
368        }
369    }
370
371    #[inline]
372    #[must_use]
373    pub fn sub_arti_inertia(&self, rhs: &Self) -> Self {
374        Self {
375            top_left: self.top_left - rhs.top_left,
376            h: self.h - rhs.h,
377            mass: self.mass - rhs.mass,
378        }
379    }
380
381    /// Add a rigid body inertia to this articulated body inertia.
382    ///
383    /// This operation is used in the articulated body algorithm when
384    /// propagating inertia from child bodies to parent bodies. It combines
385    /// the effective articulated body inertia of the subtree with the
386    /// rigid body inertia of the current body.
387    ///
388    /// # Physical Meaning
389    ///
390    /// This represents adding the inertia of a rigid body to an existing
391    /// articulated body, effectively extending the articulated system by one body.
392    /// The operation accounts for:
393    /// - Adding the rigid body's mass to the translational inertia
394    /// - Including cross-coupling effects from the rigid body's first moment
395    /// - Adding the rigid body's rotational inertia to the system
396    ///
397    /// # Algorithm Context
398    ///
399    /// This is a crucial step in Featherstone's articulated body algorithm
400    /// for computing the effective inertia at each joint in a kinematic tree.
401    #[inline]
402    #[must_use]
403    pub fn add_spat_inertia(&self, rhs: &RigidBodyInertia) -> Self {
404        let mass = self.mass.add(SymmetricMat3::ONE.scale(rhs.mass));
405        let h = self.h + rhs.h.into_cross_matrix();
406        let inertia = self.top_left + rhs.inertia;
407
408        Self {
409            top_left: inertia,
410            h,
411            mass,
412        }
413    }
414
415    #[inline]
416    pub fn mul_motion_vec(&self, motion_vec: SpatialMotionVector) -> SpatialForceVector {
417        let motion_w = motion_vec.top;
418        let motion_v = motion_vec.bottom;
419        let h = self.h;
420        let n = self.top_left.mul_vec(motion_w) + h * motion_v;
421        //TODO: implement transpose_mul_vec for mat3
422        let f = self.mass.mul_vec(motion_v) + h.transpose() * motion_w;
423        SpatialForceVector::from_pair(n, f)
424    }
425
426    /// take the lower triangle part.
427    #[inline]
428    pub fn from_symmertic_matrix(matrix: SMatrix<6, 6>) -> Self {
429        let inertia = matrix.fixed_view::<3, 3>(0, 0).into();
430        let h = matrix.fixed_view::<3, 3>(0, 3).into();
431        let mass = matrix.fixed_view::<3, 3>(3, 3).into();
432        Self {
433            top_left: inertia,
434            h,
435            mass,
436        }
437    }
438
439    pub fn matrix(&self) -> SMatrix<6, 6> {
440        let mut result = SMatrix::<6, 6>::zeros();
441
442        // top left
443        result
444            .fixed_view_mut::<3, 3>(0, 0)
445            .copy_from(&self.top_left.mat3());
446
447        // top right
448        result.fixed_view_mut::<3, 3>(0, 3).copy_from(&self.h);
449
450        // bottom left
451        result
452            .fixed_view_mut::<3, 3>(3, 0)
453            .copy_from(&self.h.transpose());
454
455        // bootom right
456        result
457            .fixed_view_mut::<3, 3>(3, 3)
458            .copy_from(&self.mass.mat3());
459
460        result
461    }
462}
463
464impl Add<Self> for ArticulatedBodyInertia {
465    type Output = Self;
466
467    #[inline]
468    fn add(self, rhs: Self) -> Self::Output {
469        self.add_arti_inertia(&rhs)
470    }
471}
472
473impl Add<Self> for &ArticulatedBodyInertia {
474    type Output = ArticulatedBodyInertia;
475
476    #[inline]
477    fn add(self, rhs: Self) -> ArticulatedBodyInertia {
478        self.add_arti_inertia(rhs)
479    }
480}
481
482impl AddAssign<&ArticulatedBodyInertia> for ArticulatedBodyInertia {
483    #[inline]
484    fn add_assign(&mut self, rhs: &ArticulatedBodyInertia) {
485        *self = self.add_arti_inertia(rhs);
486    }
487}
488
489impl Sub<Self> for ArticulatedBodyInertia {
490    type Output = Self;
491
492    #[inline]
493    fn sub(self, rhs: Self) -> Self::Output {
494        self.sub_arti_inertia(&rhs)
495    }
496}
497
498impl Sub<ArticulatedBodyInertia> for &ArticulatedBodyInertia {
499    type Output = ArticulatedBodyInertia;
500
501    #[inline]
502    fn sub(self, rhs: ArticulatedBodyInertia) -> Self::Output {
503        self.sub_arti_inertia(&rhs)
504    }
505}
506
507impl Add<RigidBodyInertia> for ArticulatedBodyInertia {
508    type Output = Self;
509
510    #[inline]
511    fn add(self, rhs: RigidBodyInertia) -> Self::Output {
512        self.add_spat_inertia(&rhs)
513    }
514}
515
516impl From<RigidBodyInertia> for ArticulatedBodyInertia {
517    #[inline]
518    fn from(value: RigidBodyInertia) -> Self {
519        Self {
520            top_left: value.inertia,
521            h: value.h.into_cross_matrix(),
522            mass: SymmetricMat3::ONE.scale(value.mass),
523        }
524    }
525}
526
527impl Mul<SpatialMotionVector> for ArticulatedBodyInertia {
528    type Output = SpatialForceVector;
529
530    #[inline]
531    fn mul(self, rhs: SpatialMotionVector) -> Self::Output {
532        self.mul_motion_vec(rhs)
533    }
534}
535
536impl Mul<SpatialMotionVector> for &ArticulatedBodyInertia {
537    type Output = SpatialForceVector;
538
539    #[inline]
540    fn mul(self, rhs: SpatialMotionVector) -> Self::Output {
541        self.mul_motion_vec(rhs)
542    }
543}
544
545#[cfg(test)]
546mod tests {
547    use approx::assert_relative_eq;
548
549    use super::*;
550    use crate::vec3;
551
552    #[test]
553    fn test_rbi_construct() {
554        let mass = 2.0;
555        let com = vec3(1.0, 2.0, 3.0);
556        let inertia_com = SymmetricMat3::from_array([1.0, 2.0, 3.0, 4.0, 5.0, 6.0]);
557        let rbi = RigidBodyInertia::new(mass, com, inertia_com);
558
559        let expected_inertia =
560            inertia_com.mat3() + mass * (com.dot(&com) * Mat3::identity() - com * com.transpose());
561        assert_relative_eq!(rbi.inertia.mat3(), expected_inertia, epsilon = 1e-6);
562    }
563
564    #[test]
565    fn test_inertia_mul_motion_vec() {
566        let mass = 2.0;
567        let com = vec3(1.0, 2.0, 3.0);
568        let inertia_com = SymmetricMat3::from_array([1.0, 2.0, 3.0, 4.0, 5.0, 6.0]);
569        let rbi = RigidBodyInertia::new(mass, com, inertia_com);
570
571        let v = SpatialMotionVector::from_array([1., 2., 3., 4., 5., 6.]);
572        let f = rbi * v;
573        let expected_f = rbi.matrix() * v.into_vec6();
574        assert_relative_eq!(f.into_vec6(), expected_f, epsilon = 1e-6);
575    }
576}