rapier3d/dynamics/joint/multibody_joint/
multibody.rs

1use super::multibody_link::{MultibodyLink, MultibodyLinkVec};
2use super::multibody_workspace::MultibodyWorkspace;
3use crate::dynamics::{RigidBodyHandle, RigidBodySet, RigidBodyType, RigidBodyVelocity};
4#[cfg(feature = "dim3")]
5use crate::math::Matrix;
6use crate::math::{
7    ANG_DIM, AngDim, AngVector, DIM, Dim, Isometry, Jacobian, Point, Real, SPATIAL_DIM, Vector,
8};
9use crate::prelude::MultibodyJoint;
10use crate::utils::{IndexMut2, SimdAngularInertia, SimdCross, SimdCrossMatrix};
11use na::{
12    self, DMatrix, DVector, DVectorView, DVectorViewMut, Dyn, LU, OMatrix, SMatrix, SVector,
13    StorageMut,
14};
15
16#[cfg(doc)]
17use crate::prelude::{GenericJoint, RigidBody};
18
19#[repr(C)]
20#[derive(Copy, Clone, Debug, Default)]
21struct Force {
22    linear: Vector<Real>,
23    angular: AngVector<Real>,
24}
25
26impl Force {
27    fn new(linear: Vector<Real>, angular: AngVector<Real>) -> Self {
28        Self { linear, angular }
29    }
30
31    fn as_vector(&self) -> &SVector<Real, SPATIAL_DIM> {
32        unsafe { std::mem::transmute(self) }
33    }
34}
35
36#[cfg(feature = "dim2")]
37fn concat_rb_mass_matrix(
38    mass: Vector<Real>,
39    inertia: Real,
40) -> SMatrix<Real, SPATIAL_DIM, SPATIAL_DIM> {
41    let mut result = SMatrix::<Real, SPATIAL_DIM, SPATIAL_DIM>::zeros();
42    result[(0, 0)] = mass.x;
43    result[(1, 1)] = mass.y;
44    result[(2, 2)] = inertia;
45    result
46}
47
48#[cfg(feature = "dim3")]
49fn concat_rb_mass_matrix(
50    mass: Vector<Real>,
51    inertia: Matrix<Real>,
52) -> SMatrix<Real, SPATIAL_DIM, SPATIAL_DIM> {
53    let mut result = SMatrix::<Real, SPATIAL_DIM, SPATIAL_DIM>::zeros();
54    result[(0, 0)] = mass.x;
55    result[(1, 1)] = mass.y;
56    result[(2, 2)] = mass.z;
57    result
58        .fixed_view_mut::<ANG_DIM, ANG_DIM>(DIM, DIM)
59        .copy_from(&inertia);
60    result
61}
62
63/// An articulated body simulated using the reduced-coordinates approach.
64#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
65#[derive(Clone, Debug)]
66pub struct Multibody {
67    // TODO: serialization: skip the workspace fields.
68    pub(crate) links: MultibodyLinkVec,
69    pub(crate) velocities: DVector<Real>,
70    pub(crate) damping: DVector<Real>,
71    pub(crate) accelerations: DVector<Real>,
72
73    body_jacobians: Vec<Jacobian<Real>>,
74    // NOTE: the mass matrices are dimensioned based on the non-kinematic degrees of
75    //       freedoms only. The `Self::augmented_mass_permutation` sequence can be used to
76    //       move dofs from/to a format that matches the augmented mass.
77    // TODO: use sparse matrices?
78    augmented_mass: DMatrix<Real>,
79    inv_augmented_mass: LU<Real, Dyn, Dyn>,
80    // The indexing sequence for moving all kinematics degrees of
81    // freedoms to the end of the generalized coordinates vector.
82    augmented_mass_indices: IndexSequence,
83
84    acc_augmented_mass: DMatrix<Real>,
85    acc_inv_augmented_mass: LU<Real, Dyn, Dyn>,
86
87    ndofs: usize,
88    pub(crate) root_is_dynamic: bool,
89    pub(crate) solver_id: usize,
90    self_contacts_enabled: bool,
91
92    /*
93     * Workspaces.
94     */
95    workspace: MultibodyWorkspace,
96    coriolis_v: Vec<OMatrix<Real, Dim, Dyn>>,
97    coriolis_w: Vec<OMatrix<Real, AngDim, Dyn>>,
98    i_coriolis_dt: Jacobian<Real>,
99}
100impl Default for Multibody {
101    fn default() -> Self {
102        Multibody::new()
103    }
104}
105
106impl Multibody {
107    /// Creates a new multibody with no link.
108    pub fn new() -> Self {
109        Self::with_self_contacts(true)
110    }
111
112    pub(crate) fn with_self_contacts(self_contacts_enabled: bool) -> Self {
113        Multibody {
114            links: MultibodyLinkVec(Vec::new()),
115            velocities: DVector::zeros(0),
116            damping: DVector::zeros(0),
117            accelerations: DVector::zeros(0),
118            body_jacobians: Vec::new(),
119            augmented_mass: DMatrix::zeros(0, 0),
120            inv_augmented_mass: LU::new(DMatrix::zeros(0, 0)),
121            acc_augmented_mass: DMatrix::zeros(0, 0),
122            acc_inv_augmented_mass: LU::new(DMatrix::zeros(0, 0)),
123            augmented_mass_indices: IndexSequence::new(),
124            ndofs: 0,
125            solver_id: 0,
126            workspace: MultibodyWorkspace::new(),
127            coriolis_v: Vec::new(),
128            coriolis_w: Vec::new(),
129            i_coriolis_dt: Jacobian::zeros(0),
130            root_is_dynamic: false,
131            self_contacts_enabled,
132            // solver_workspace: Some(SolverWorkspace::new()),
133        }
134    }
135
136    pub(crate) fn with_root(handle: RigidBodyHandle, self_contacts_enabled: bool) -> Self {
137        let mut mb = Multibody::with_self_contacts(self_contacts_enabled);
138        // NOTE: we have no way of knowing if the root in fixed at this point, so
139        //       we mark it as dynamic and will fix later with `Self::update_root_type`.
140        mb.root_is_dynamic = true;
141        let joint = MultibodyJoint::free(Isometry::identity());
142        mb.add_link(None, joint, handle);
143        mb
144    }
145
146    pub(crate) fn remove_link(self, to_remove: usize, joint_only: bool) -> Vec<Multibody> {
147        let mut result = vec![];
148        let mut link2mb = vec![usize::MAX; self.links.len()];
149        let mut link_id2new_id = vec![usize::MAX; self.links.len()];
150
151        // Split multibody and update the set of links and ndofs.
152        for (i, mut link) in self.links.0.into_iter().enumerate() {
153            let is_new_root = i == 0
154                || !joint_only && link.parent_internal_id == to_remove
155                || joint_only && i == to_remove;
156
157            if !joint_only && i == to_remove {
158                continue;
159            } else if is_new_root {
160                link2mb[i] = result.len();
161                result.push(Multibody::with_self_contacts(self.self_contacts_enabled));
162            } else {
163                link2mb[i] = link2mb[link.parent_internal_id]
164            }
165
166            let curr_mb = &mut result[link2mb[i]];
167            link_id2new_id[i] = curr_mb.links.len();
168
169            if is_new_root {
170                let joint = MultibodyJoint::fixed(*link.local_to_world());
171                link.joint = joint;
172            }
173
174            curr_mb.ndofs += link.joint().ndofs();
175            curr_mb.links.push(link);
176        }
177
178        // Adjust all the internal ids, and copy the data from the
179        // previous multibody to the new one.
180        for mb in &mut result {
181            mb.grow_buffers(mb.ndofs, mb.links.len());
182            mb.workspace.resize(mb.links.len(), mb.ndofs);
183
184            let mut assembly_id = 0;
185            for (i, link) in mb.links.iter_mut().enumerate() {
186                let link_ndofs = link.joint().ndofs();
187                mb.velocities
188                    .rows_mut(assembly_id, link_ndofs)
189                    .copy_from(&self.velocities.rows(link.assembly_id, link_ndofs));
190                mb.damping
191                    .rows_mut(assembly_id, link_ndofs)
192                    .copy_from(&self.damping.rows(link.assembly_id, link_ndofs));
193                mb.accelerations
194                    .rows_mut(assembly_id, link_ndofs)
195                    .copy_from(&self.accelerations.rows(link.assembly_id, link_ndofs));
196
197                link.internal_id = i;
198                link.assembly_id = assembly_id;
199
200                // NOTE: for the root, the current`link.parent_internal_id` is invalid since that
201                //       parent lies in a different multibody now.
202                link.parent_internal_id = if i != 0 {
203                    link_id2new_id[link.parent_internal_id]
204                } else {
205                    0
206                };
207                assembly_id += link_ndofs;
208            }
209        }
210
211        result
212    }
213
214    pub(crate) fn append(&mut self, mut rhs: Multibody, parent: usize, joint: MultibodyJoint) {
215        let rhs_root_ndofs = rhs.links[0].joint.ndofs();
216        // Values for rhs will be copied into the buffers of `self` starting at this index.
217        let rhs_copy_shift = self.ndofs + joint.ndofs();
218        // Number of dofs to copy from rhs. The root’s dofs isn’t included because it will be
219        // replaced by `joint.
220        let rhs_copy_ndofs = rhs.ndofs - rhs_root_ndofs;
221
222        // Adjust the ids of all the rhs links except the first one.
223        let base_assembly_id = self.velocities.len() - rhs_root_ndofs + joint.ndofs();
224        let base_internal_id = self.links.len() + 1;
225        let base_parent_id = self.links.len();
226
227        for link in &mut rhs.links.0[1..] {
228            link.assembly_id += base_assembly_id;
229            link.internal_id += base_internal_id;
230            link.parent_internal_id += base_parent_id;
231        }
232
233        // Adjust the first link.
234        {
235            rhs.links[0].joint = joint;
236            rhs.links[0].assembly_id = self.velocities.len();
237            rhs.links[0].internal_id = self.links.len();
238            rhs.links[0].parent_internal_id = parent;
239        }
240
241        // Grow buffers then append data from rhs.
242        self.grow_buffers(rhs_copy_ndofs + rhs.links[0].joint.ndofs(), rhs.links.len());
243
244        if rhs_copy_ndofs > 0 {
245            self.velocities
246                .rows_mut(rhs_copy_shift, rhs_copy_ndofs)
247                .copy_from(&rhs.velocities.rows(rhs_root_ndofs, rhs_copy_ndofs));
248            self.damping
249                .rows_mut(rhs_copy_shift, rhs_copy_ndofs)
250                .copy_from(&rhs.damping.rows(rhs_root_ndofs, rhs_copy_ndofs));
251            self.accelerations
252                .rows_mut(rhs_copy_shift, rhs_copy_ndofs)
253                .copy_from(&rhs.accelerations.rows(rhs_root_ndofs, rhs_copy_ndofs));
254        }
255
256        rhs.links[0]
257            .joint
258            .default_damping(&mut self.damping.rows_mut(base_assembly_id, rhs_root_ndofs));
259
260        self.links.append(&mut rhs.links);
261        self.ndofs = self.velocities.len();
262        self.workspace.resize(self.links.len(), self.ndofs);
263    }
264
265    /// Whether self-contacts are enabled on this multibody.
266    ///
267    /// If set to `false` no two link from this multibody can generate contacts, even
268    /// if the contact is enabled on the individual joint with [`GenericJoint::contacts_enabled`].
269    pub fn self_contacts_enabled(&self) -> bool {
270        self.self_contacts_enabled
271    }
272
273    /// Sets whether self-contacts are enabled on this multibody.
274    ///
275    /// If set to `false` no two link from this multibody can generate contacts, even
276    /// if the contact is enabled on the individual joint with [`GenericJoint::contacts_enabled`].
277    pub fn set_self_contacts_enabled(&mut self, enabled: bool) {
278        self.self_contacts_enabled = enabled;
279    }
280
281    /// The inverse augmented mass matrix of this multibody.
282    pub fn inv_augmented_mass(&self) -> &LU<Real, Dyn, Dyn> {
283        &self.inv_augmented_mass
284    }
285
286    /// The first link of this multibody.
287    #[inline]
288    pub fn root(&self) -> &MultibodyLink {
289        &self.links[0]
290    }
291
292    /// Mutable reference to the first link of this multibody.
293    #[inline]
294    pub fn root_mut(&mut self) -> &mut MultibodyLink {
295        &mut self.links[0]
296    }
297
298    /// Reference `i`-th multibody link of this multibody.
299    ///
300    /// Return `None` if there is less than `i + 1` multibody links.
301    #[inline]
302    pub fn link(&self, id: usize) -> Option<&MultibodyLink> {
303        self.links.get(id)
304    }
305
306    /// Mutable reference to the multibody link with the given id.
307    ///
308    /// Return `None` if the given id does not identifies a multibody link part of `self`.
309    #[inline]
310    pub fn link_mut(&mut self, id: usize) -> Option<&mut MultibodyLink> {
311        self.links.get_mut(id)
312    }
313
314    /// The number of links on this multibody.
315    pub fn num_links(&self) -> usize {
316        self.links.len()
317    }
318
319    /// Iterator through all the links of this multibody.
320    ///
321    /// All link are guaranteed to be yielded before its descendant.
322    pub fn links(&self) -> impl Iterator<Item = &MultibodyLink> {
323        self.links.iter()
324    }
325
326    /// Mutable iterator through all the links of this multibody.
327    ///
328    /// All link are guaranteed to be yielded before its descendant.
329    pub fn links_mut(&mut self) -> impl Iterator<Item = &mut MultibodyLink> {
330        self.links.iter_mut()
331    }
332
333    /// The vector of damping applied to this multibody.
334    #[inline]
335    pub fn damping(&self) -> &DVector<Real> {
336        &self.damping
337    }
338
339    /// Mutable vector of damping applied to this multibody.
340    #[inline]
341    pub fn damping_mut(&mut self) -> &mut DVector<Real> {
342        &mut self.damping
343    }
344
345    pub(crate) fn add_link(
346        &mut self,
347        parent: Option<usize>, // TODO: should be a RigidBodyHandle?
348        dof: MultibodyJoint,
349        body: RigidBodyHandle,
350    ) -> &mut MultibodyLink {
351        assert!(
352            parent.is_none() || !self.links.is_empty(),
353            "Multibody::build_body: invalid parent id."
354        );
355
356        /*
357         * Compute the indices.
358         */
359        let assembly_id = self.velocities.len();
360        let internal_id = self.links.len();
361
362        /*
363         * Grow the buffers.
364         */
365        let ndofs = dof.ndofs();
366        self.grow_buffers(ndofs, 1);
367        self.ndofs += ndofs;
368
369        /*
370         * Setup default damping.
371         */
372        dof.default_damping(&mut self.damping.rows_mut(assembly_id, ndofs));
373
374        /*
375         * Create the multibody.
376         */
377        let local_to_parent = dof.body_to_parent();
378        let local_to_world;
379
380        let parent_internal_id;
381        if let Some(parent) = parent {
382            parent_internal_id = parent;
383            let parent_link = &mut self.links[parent_internal_id];
384            local_to_world = parent_link.local_to_world * local_to_parent;
385        } else {
386            parent_internal_id = 0;
387            local_to_world = local_to_parent;
388        }
389
390        let rb = MultibodyLink::new(
391            body,
392            internal_id,
393            assembly_id,
394            parent_internal_id,
395            dof,
396            local_to_world,
397            local_to_parent,
398        );
399
400        self.links.push(rb);
401        self.workspace.resize(self.links.len(), self.ndofs);
402
403        &mut self.links[internal_id]
404    }
405
406    fn grow_buffers(&mut self, ndofs: usize, num_jacobians: usize) {
407        let len = self.velocities.len();
408        self.velocities.resize_vertically_mut(len + ndofs, 0.0);
409        self.damping.resize_vertically_mut(len + ndofs, 0.0);
410        self.accelerations.resize_vertically_mut(len + ndofs, 0.0);
411        self.body_jacobians
412            .extend((0..num_jacobians).map(|_| Jacobian::zeros(0)));
413    }
414
415    pub(crate) fn update_acceleration(&mut self, bodies: &RigidBodySet) {
416        if self.ndofs == 0 {
417            return; // Nothing to do.
418        }
419
420        self.accelerations.fill(0.0);
421
422        // Eqn 42 to 45
423        for i in 0..self.links.len() {
424            let link = &self.links[i];
425            let rb = &bodies[link.rigid_body];
426
427            let mut acc = RigidBodyVelocity::zero();
428
429            if i != 0 {
430                let parent_id = link.parent_internal_id;
431                let parent_link = &self.links[parent_id];
432                let parent_rb = &bodies[parent_link.rigid_body];
433
434                acc += self.workspace.accs[parent_id];
435                // The 2.0 originates from the two identical terms of Jdot (the terms become
436                // identical once they are multiplied by the generalized velocities).
437                acc.linvel += 2.0 * parent_rb.vels.angvel.gcross(link.joint_velocity.linvel);
438                #[cfg(feature = "dim3")]
439                {
440                    acc.angvel += parent_rb.vels.angvel.cross(&link.joint_velocity.angvel);
441                }
442
443                acc.linvel += parent_rb
444                    .vels
445                    .angvel
446                    .gcross(parent_rb.vels.angvel.gcross(link.shift02));
447                acc.linvel += self.workspace.accs[parent_id].angvel.gcross(link.shift02);
448            }
449
450            acc.linvel += rb.vels.angvel.gcross(rb.vels.angvel.gcross(link.shift23));
451            acc.linvel += acc.angvel.gcross(link.shift23);
452
453            self.workspace.accs[i] = acc;
454
455            // TODO: should gyroscopic forces already be computed by the rigid-body itself
456            //       (at the same time that we add the gravity force)?
457            let gyroscopic;
458            let rb_inertia = rb.mprops.effective_angular_inertia();
459            let rb_mass = rb.mprops.effective_mass();
460
461            #[cfg(feature = "dim3")]
462            {
463                gyroscopic = rb.vels.angvel.cross(&(rb_inertia * rb.vels.angvel));
464            }
465            #[cfg(feature = "dim2")]
466            {
467                gyroscopic = 0.0;
468            }
469
470            let external_forces = Force::new(
471                rb.forces.force - rb_mass.component_mul(&acc.linvel),
472                rb.forces.torque - gyroscopic - rb_inertia * acc.angvel,
473            );
474            self.accelerations.gemv_tr(
475                1.0,
476                &self.body_jacobians[i],
477                external_forces.as_vector(),
478                1.0,
479            );
480        }
481
482        self.accelerations
483            .cmpy(-1.0, &self.damping, &self.velocities, 1.0);
484
485        self.augmented_mass_indices
486            .with_rearranged_rows_mut(&mut self.accelerations, |accs| {
487                self.acc_inv_augmented_mass.solve_mut(accs);
488            });
489    }
490
491    /// Computes the constant terms of the dynamics.
492    #[profiling::function]
493    pub(crate) fn update_dynamics(&mut self, dt: Real, bodies: &mut RigidBodySet) {
494        /*
495         * Compute velocities.
496         * NOTE: this is needed for kinematic bodies too.
497         */
498        let link = &mut self.links[0];
499        let joint_velocity = link
500            .joint
501            .jacobian_mul_coordinates(&self.velocities.as_slice()[link.assembly_id..]);
502
503        link.joint_velocity = joint_velocity;
504        bodies.index_mut_internal(link.rigid_body).vels = link.joint_velocity;
505
506        for i in 1..self.links.len() {
507            let (link, parent_link) = self.links.get_mut_with_parent(i);
508            let rb = &bodies[link.rigid_body];
509            let parent_rb = &bodies[parent_link.rigid_body];
510
511            let joint_velocity = link
512                .joint
513                .jacobian_mul_coordinates(&self.velocities.as_slice()[link.assembly_id..]);
514            link.joint_velocity = joint_velocity.transformed(
515                &(parent_link.local_to_world.rotation * link.joint.data.local_frame1.rotation),
516            );
517            let mut new_rb_vels = parent_rb.vels + link.joint_velocity;
518            let shift = rb.mprops.world_com - parent_rb.mprops.world_com;
519            new_rb_vels.linvel += parent_rb.vels.angvel.gcross(shift);
520            new_rb_vels.linvel += link.joint_velocity.angvel.gcross(link.shift23);
521
522            bodies.index_mut_internal(link.rigid_body).vels = new_rb_vels;
523        }
524
525        /*
526         * Update augmented mass matrix.
527         */
528        self.update_inertias(dt, bodies);
529    }
530
531    fn update_body_jacobians(&mut self) {
532        for i in 0..self.links.len() {
533            let link = &self.links[i];
534
535            if self.body_jacobians[i].ncols() != self.ndofs {
536                // TODO: use a resize instead.
537                self.body_jacobians[i] = Jacobian::zeros(self.ndofs);
538            }
539
540            let parent_to_world;
541
542            if i != 0 {
543                let parent_id = link.parent_internal_id;
544                let parent_link = &self.links[parent_id];
545                parent_to_world = parent_link.local_to_world;
546
547                let (link_j, parent_j) = self.body_jacobians.index_mut_const(i, parent_id);
548                link_j.copy_from(parent_j);
549
550                {
551                    let mut link_j_v = link_j.fixed_rows_mut::<DIM>(0);
552                    let parent_j_w = parent_j.fixed_rows::<ANG_DIM>(DIM);
553
554                    let shift_tr = (link.shift02).gcross_matrix_tr();
555                    link_j_v.gemm(1.0, &shift_tr, &parent_j_w, 1.0);
556                }
557            } else {
558                self.body_jacobians[i].fill(0.0);
559                parent_to_world = Isometry::identity();
560            }
561
562            let ndofs = link.joint.ndofs();
563            let mut tmp = SMatrix::<Real, SPATIAL_DIM, SPATIAL_DIM>::zeros();
564            let mut link_joint_j = tmp.columns_mut(0, ndofs);
565            let mut link_j_part = self.body_jacobians[i].columns_mut(link.assembly_id, ndofs);
566            link.joint.jacobian(
567                &(parent_to_world.rotation * link.joint.data.local_frame1.rotation),
568                &mut link_joint_j,
569            );
570            link_j_part += link_joint_j;
571
572            {
573                let link_j = &mut self.body_jacobians[i];
574                let (mut link_j_v, link_j_w) =
575                    link_j.rows_range_pair_mut(0..DIM, DIM..DIM + ANG_DIM);
576                let shift_tr = link.shift23.gcross_matrix_tr();
577                link_j_v.gemm(1.0, &shift_tr, &link_j_w, 1.0);
578            }
579        }
580    }
581
582    fn update_inertias(&mut self, dt: Real, bodies: &RigidBodySet) {
583        if self.ndofs == 0 {
584            return; // Nothing to do.
585        }
586
587        if self.augmented_mass.ncols() != self.ndofs {
588            // TODO: do a resize instead of a full reallocation.
589            self.augmented_mass = DMatrix::zeros(self.ndofs, self.ndofs);
590            self.acc_augmented_mass = DMatrix::zeros(self.ndofs, self.ndofs);
591        } else {
592            self.augmented_mass.fill(0.0);
593            self.acc_augmented_mass.fill(0.0);
594        }
595
596        self.augmented_mass_indices.clear();
597
598        if self.coriolis_v.len() != self.links.len() {
599            self.coriolis_v.resize(
600                self.links.len(),
601                OMatrix::<Real, Dim, Dyn>::zeros(self.ndofs),
602            );
603            self.coriolis_w.resize(
604                self.links.len(),
605                OMatrix::<Real, AngDim, Dyn>::zeros(self.ndofs),
606            );
607            self.i_coriolis_dt = Jacobian::zeros(self.ndofs);
608        }
609
610        let mut curr_assembly_id = 0;
611
612        for i in 0..self.links.len() {
613            let link = &self.links[i];
614            let rb = &bodies[link.rigid_body];
615            let rb_mass = rb.mprops.effective_mass();
616            let rb_inertia = rb.mprops.effective_angular_inertia().into_matrix();
617            let body_jacobian = &self.body_jacobians[i];
618
619            // NOTE: the mass matrix index reordering operates on the assumption that the assembly
620            //       ids are traversed in order. This assert is here to ensure the assumption always
621            //       hold.
622            assert_eq!(
623                curr_assembly_id, link.assembly_id,
624                "Internal error: contiguity assumption on assembly_id does not hold."
625            );
626            curr_assembly_id += link.joint.ndofs();
627
628            if link.joint.kinematic {
629                for k in link.assembly_id..link.assembly_id + link.joint.ndofs() {
630                    self.augmented_mass_indices.remove(k);
631                }
632            } else {
633                for k in link.assembly_id..link.assembly_id + link.joint.ndofs() {
634                    self.augmented_mass_indices.keep(k);
635                }
636            }
637
638            #[allow(unused_mut)] // mut is needed for 3D but not for 2D.
639            let mut augmented_inertia = rb_inertia;
640
641            #[cfg(feature = "dim3")]
642            {
643                // Derivative of gyroscopic forces.
644                let gyroscopic_matrix = rb.vels.angvel.gcross_matrix() * rb_inertia
645                    - (rb_inertia * rb.vels.angvel).gcross_matrix();
646
647                augmented_inertia += gyroscopic_matrix * dt;
648            }
649
650            // TODO: optimize that (knowing the structure of the augmented inertia matrix).
651            // TODO: this could be better optimized in 2D.
652            let rb_mass_matrix_wo_gyro = concat_rb_mass_matrix(rb_mass, rb_inertia);
653            let rb_mass_matrix = concat_rb_mass_matrix(rb_mass, augmented_inertia);
654            self.augmented_mass
655                .quadform(1.0, &rb_mass_matrix_wo_gyro, body_jacobian, 1.0);
656            self.acc_augmented_mass
657                .quadform(1.0, &rb_mass_matrix, body_jacobian, 1.0);
658
659            /*
660             *
661             * Coriolis matrix.
662             *
663             */
664            let rb_j = &self.body_jacobians[i];
665            let rb_j_w = rb_j.fixed_rows::<ANG_DIM>(DIM);
666
667            let ndofs = link.joint.ndofs();
668
669            if i != 0 {
670                let parent_id = link.parent_internal_id;
671                let parent_link = &self.links[parent_id];
672                let parent_rb = &bodies[parent_link.rigid_body];
673                let parent_j = &self.body_jacobians[parent_id];
674                let parent_j_w = parent_j.fixed_rows::<ANG_DIM>(DIM);
675                let parent_w = parent_rb.vels.angvel.gcross_matrix();
676
677                let (coriolis_v, parent_coriolis_v) = self.coriolis_v.index_mut2(i, parent_id);
678                let (coriolis_w, parent_coriolis_w) = self.coriolis_w.index_mut2(i, parent_id);
679
680                coriolis_v.copy_from(parent_coriolis_v);
681                coriolis_w.copy_from(parent_coriolis_w);
682
683                // [c1 - c0].gcross() * (JDot + JDot/u * qdot)"
684                let shift_cross_tr = link.shift02.gcross_matrix_tr();
685                coriolis_v.gemm(1.0, &shift_cross_tr, parent_coriolis_w, 1.0);
686
687                // JDot (but the 2.0 originates from the sum of two identical terms in JDot and JDot/u * gdot)
688                let dvel_cross = (rb.vels.angvel.gcross(link.shift02)
689                    + 2.0 * link.joint_velocity.linvel)
690                    .gcross_matrix_tr();
691                coriolis_v.gemm(1.0, &dvel_cross, &parent_j_w, 1.0);
692
693                // JDot/u * qdot
694                coriolis_v.gemm(
695                    1.0,
696                    &link.joint_velocity.linvel.gcross_matrix_tr(),
697                    &parent_j_w,
698                    1.0,
699                );
700                coriolis_v.gemm(1.0, &(parent_w * shift_cross_tr), &parent_j_w, 1.0);
701
702                #[cfg(feature = "dim3")]
703                {
704                    let vel_wrt_joint_w = link.joint_velocity.angvel.gcross_matrix();
705                    coriolis_w.gemm(-1.0, &vel_wrt_joint_w, &parent_j_w, 1.0);
706                }
707
708                // JDot (but the 2.0 originates from the sum of two identical terms in JDot and JDot/u * gdot)
709                if !link.joint.kinematic {
710                    let mut coriolis_v_part = coriolis_v.columns_mut(link.assembly_id, ndofs);
711
712                    let mut tmp1 = SMatrix::<Real, SPATIAL_DIM, SPATIAL_DIM>::zeros();
713                    let mut rb_joint_j = tmp1.columns_mut(0, ndofs);
714                    link.joint.jacobian(
715                        &(parent_link.local_to_world.rotation
716                            * link.joint.data.local_frame1.rotation),
717                        &mut rb_joint_j,
718                    );
719
720                    let rb_joint_j_v = rb_joint_j.fixed_rows::<DIM>(0);
721                    coriolis_v_part.gemm(2.0, &parent_w, &rb_joint_j_v, 1.0);
722
723                    #[cfg(feature = "dim3")]
724                    {
725                        let rb_joint_j_w = rb_joint_j.fixed_rows::<ANG_DIM>(DIM);
726                        let mut coriolis_w_part = coriolis_w.columns_mut(link.assembly_id, ndofs);
727                        coriolis_w_part.gemm(1.0, &parent_w, &rb_joint_j_w, 1.0);
728                    }
729                }
730            } else {
731                self.coriolis_v[i].fill(0.0);
732                self.coriolis_w[i].fill(0.0);
733            }
734
735            let coriolis_v = &mut self.coriolis_v[i];
736            let coriolis_w = &mut self.coriolis_w[i];
737
738            {
739                // [c3 - c2].gcross() * (JDot + JDot/u * qdot)
740                let shift_cross_tr = link.shift23.gcross_matrix_tr();
741                coriolis_v.gemm(1.0, &shift_cross_tr, coriolis_w, 1.0);
742
743                // JDot
744                let dvel_cross = rb.vels.angvel.gcross(link.shift23).gcross_matrix_tr();
745                coriolis_v.gemm(1.0, &dvel_cross, &rb_j_w, 1.0);
746
747                // JDot/u * qdot
748                coriolis_v.gemm(
749                    1.0,
750                    &(rb.vels.angvel.gcross_matrix() * shift_cross_tr),
751                    &rb_j_w,
752                    1.0,
753                );
754            }
755
756            let coriolis_v = &mut self.coriolis_v[i];
757            let coriolis_w = &mut self.coriolis_w[i];
758
759            /*
760             * Meld with the mass matrix.
761             */
762            {
763                let mut i_coriolis_dt_v = self.i_coriolis_dt.fixed_rows_mut::<DIM>(0);
764                i_coriolis_dt_v.copy_from(coriolis_v);
765                i_coriolis_dt_v
766                    .column_iter_mut()
767                    .for_each(|mut c| c.component_mul_assign(&(rb_mass * dt)));
768            }
769
770            #[cfg(feature = "dim2")]
771            {
772                let mut i_coriolis_dt_w = self.i_coriolis_dt.fixed_rows_mut::<ANG_DIM>(DIM);
773                // NOTE: this is just an axpy, but on row columns.
774                i_coriolis_dt_w.zip_apply(coriolis_w, |o, x| *o = x * dt * rb_inertia);
775            }
776            #[cfg(feature = "dim3")]
777            {
778                let mut i_coriolis_dt_w = self.i_coriolis_dt.fixed_rows_mut::<ANG_DIM>(DIM);
779                i_coriolis_dt_w.gemm(dt, &rb_inertia, coriolis_w, 0.0);
780            }
781
782            self.acc_augmented_mass
783                .gemm_tr(1.0, rb_j, &self.i_coriolis_dt, 1.0);
784        }
785
786        /*
787         * Damping.
788         */
789        for i in 0..self.ndofs {
790            self.acc_augmented_mass[(i, i)] += self.damping[i] * dt;
791            self.augmented_mass[(i, i)] += self.damping[i] * dt;
792        }
793
794        let effective_dim = self
795            .augmented_mass_indices
796            .dim_after_removal(self.acc_augmented_mass.nrows());
797
798        // PERF: since we clone the matrix anyway for LU, should be directly output
799        //       a new matrix instead of applying permutations?
800        self.augmented_mass_indices
801            .rearrange_columns(&mut self.acc_augmented_mass, true);
802        self.augmented_mass_indices
803            .rearrange_columns(&mut self.augmented_mass, true);
804
805        self.augmented_mass_indices
806            .rearrange_rows(&mut self.acc_augmented_mass, true);
807        self.augmented_mass_indices
808            .rearrange_rows(&mut self.augmented_mass, true);
809
810        // TODO: avoid allocation inside LU at each timestep.
811        self.acc_inv_augmented_mass = LU::new(
812            self.acc_augmented_mass
813                .view((0, 0), (effective_dim, effective_dim))
814                .into_owned(),
815        );
816        self.inv_augmented_mass = LU::new(
817            self.augmented_mass
818                .view((0, 0), (effective_dim, effective_dim))
819                .into_owned(),
820        );
821    }
822
823    /// The generalized velocity at the multibody_joint of the given link.
824    #[inline]
825    pub fn joint_velocity(&self, link: &MultibodyLink) -> DVectorView<Real> {
826        let ndofs = link.joint().ndofs();
827        DVectorView::from_slice(
828            &self.velocities.as_slice()[link.assembly_id..link.assembly_id + ndofs],
829            ndofs,
830        )
831    }
832
833    /// The generalized accelerations of this multibodies.
834    #[inline]
835    pub fn generalized_acceleration(&self) -> DVectorView<Real> {
836        self.accelerations.rows(0, self.ndofs)
837    }
838
839    /// The generalized velocities of this multibodies.
840    #[inline]
841    pub fn generalized_velocity(&self) -> DVectorView<Real> {
842        self.velocities.rows(0, self.ndofs)
843    }
844
845    /// The body jacobian for link `link_id` calculated by the last call to [`Multibody::forward_kinematics`].
846    #[inline]
847    pub fn body_jacobian(&self, link_id: usize) -> &Jacobian<Real> {
848        &self.body_jacobians[link_id]
849    }
850
851    /// The mutable generalized velocities of this multibodies.
852    #[inline]
853    pub fn generalized_velocity_mut(&mut self) -> DVectorViewMut<Real> {
854        self.velocities.rows_mut(0, self.ndofs)
855    }
856
857    #[inline]
858    pub(crate) fn integrate(&mut self, dt: Real) {
859        for rb in self.links.iter_mut() {
860            rb.joint
861                .integrate(dt, &self.velocities.as_slice()[rb.assembly_id..])
862        }
863    }
864
865    /// Apply displacements, in generalized coordinates, to this multibody.
866    ///
867    /// Note this does **not** updates the link poses, only their generalized coordinates.
868    /// To update the link poses and associated rigid-bodies, call [`Self::forward_kinematics`].
869    pub fn apply_displacements(&mut self, disp: &[Real]) {
870        for link in self.links.iter_mut() {
871            link.joint.apply_displacement(&disp[link.assembly_id..])
872        }
873    }
874
875    pub(crate) fn update_root_type(&mut self, bodies: &RigidBodySet, take_body_pose: bool) {
876        if let Some(rb) = bodies.get(self.links[0].rigid_body) {
877            if rb.is_dynamic() != self.root_is_dynamic {
878                let root_pose = if take_body_pose {
879                    *rb.position()
880                } else {
881                    self.links[0].local_to_world
882                };
883
884                if rb.is_dynamic() {
885                    let free_joint = MultibodyJoint::free(root_pose);
886                    let prev_root_ndofs = self.links[0].joint().ndofs();
887                    self.links[0].joint = free_joint;
888                    self.links[0].assembly_id = 0;
889                    self.ndofs += SPATIAL_DIM;
890
891                    self.velocities = self.velocities.clone().insert_rows(0, SPATIAL_DIM, 0.0);
892                    self.damping = self.damping.clone().insert_rows(0, SPATIAL_DIM, 0.0);
893                    self.accelerations =
894                        self.accelerations.clone().insert_rows(0, SPATIAL_DIM, 0.0);
895
896                    for link in &mut self.links[1..] {
897                        link.assembly_id += SPATIAL_DIM - prev_root_ndofs;
898                    }
899                } else {
900                    assert!(self.velocities.len() >= SPATIAL_DIM);
901                    assert!(self.damping.len() >= SPATIAL_DIM);
902                    assert!(self.accelerations.len() >= SPATIAL_DIM);
903
904                    let fixed_joint = MultibodyJoint::fixed(root_pose);
905                    let prev_root_ndofs = self.links[0].joint().ndofs();
906                    self.links[0].joint = fixed_joint;
907                    self.links[0].assembly_id = 0;
908                    self.ndofs -= prev_root_ndofs;
909
910                    if self.ndofs == 0 {
911                        self.velocities = DVector::zeros(0);
912                        self.damping = DVector::zeros(0);
913                        self.accelerations = DVector::zeros(0);
914                    } else {
915                        self.velocities =
916                            self.velocities.index((prev_root_ndofs.., 0)).into_owned();
917                        self.damping = self.damping.index((prev_root_ndofs.., 0)).into_owned();
918                        self.accelerations = self
919                            .accelerations
920                            .index((prev_root_ndofs.., 0))
921                            .into_owned();
922                    }
923
924                    for link in &mut self.links[1..] {
925                        link.assembly_id -= prev_root_ndofs;
926                    }
927                }
928
929                self.root_is_dynamic = rb.is_dynamic();
930            }
931
932            // Make sure the positions are properly set to match the rigid-body’s.
933            if take_body_pose {
934                if self.links[0].joint.data.locked_axes.is_empty() {
935                    self.links[0].joint.set_free_pos(*rb.position());
936                } else {
937                    self.links[0].joint.data.local_frame1 = *rb.position();
938                }
939            }
940        }
941    }
942
943    /// Update the rigid-body poses based on this multibody joint poses.
944    ///
945    /// This is typically called after [`Self::forward_kinematics`] to apply the new joint poses
946    /// to the rigid-bodies.
947    pub fn update_rigid_bodies(&self, bodies: &mut RigidBodySet, update_mass_properties: bool) {
948        self.update_rigid_bodies_internal(bodies, update_mass_properties, false, true)
949    }
950
951    pub(crate) fn update_rigid_bodies_internal(
952        &self,
953        bodies: &mut RigidBodySet,
954        update_mass_properties: bool,
955        update_next_positions_only: bool,
956        change_tracking: bool,
957    ) {
958        // Handle the children. They all have a parent within this multibody.
959        for link in self.links.iter() {
960            let rb = if change_tracking {
961                bodies.get_mut_internal_with_modification_tracking(link.rigid_body)
962            } else {
963                bodies.get_mut_internal(link.rigid_body)
964            };
965
966            if let Some(rb) = rb {
967                rb.pos.next_position = link.local_to_world;
968
969                if !update_next_positions_only {
970                    rb.pos.position = link.local_to_world;
971                }
972
973                if update_mass_properties {
974                    rb.mprops.update_world_mass_properties(&link.local_to_world);
975                }
976            }
977        }
978    }
979
980    // TODO: make a version that doesn’t write back to bodies and doesn’t update the jacobians
981    //       (i.e. just something used by the velocity solver’s small steps).
982    /// Apply forward-kinematics to this multibody.
983    ///
984    /// This will update the [`MultibodyLink`] pose information as wall as the body jacobians.
985    /// This will also ensure that the multibody has the proper number of degrees of freedom if
986    /// its root node changed between dynamic and non-dynamic.
987    ///
988    /// Note that this does **not** update the poses of the [`RigidBody`] attached to the joints.
989    /// Run [`Self::update_rigid_bodies`] to trigger that update.
990    ///
991    /// This method updates `self` with the result of the forward-kinematics operation.
992    /// For a non-mutable version running forward kinematics on a single link, see
993    /// [`Self::forward_kinematics_single_link`].
994    ///
995    /// ## Parameters
996    /// - `bodies`: the set of rigid-bodies.
997    /// - `read_root_pose_from_rigid_body`: if set to `true`, the root joint (either a fixed joint,
998    ///   or a free joint) will have its pose set to its associated-rigid-body pose. Set this to `true`
999    ///   when the root rigid-body pose has been modified and needs to affect the multibody.
1000    pub fn forward_kinematics(
1001        &mut self,
1002        bodies: &RigidBodySet,
1003        read_root_pose_from_rigid_body: bool,
1004    ) {
1005        // Be sure the degrees of freedom match and take the root position if needed.
1006        self.update_root_type(bodies, read_root_pose_from_rigid_body);
1007
1008        // Special case for the root, which has no parent.
1009        {
1010            let link = &mut self.links[0];
1011            link.local_to_parent = link.joint.body_to_parent();
1012            link.local_to_world = link.local_to_parent;
1013        }
1014
1015        // Handle the children. They all have a parent within this multibody.
1016        for i in 1..self.links.len() {
1017            let (link, parent_link) = self.links.get_mut_with_parent(i);
1018
1019            link.local_to_parent = link.joint.body_to_parent();
1020            link.local_to_world = parent_link.local_to_world * link.local_to_parent;
1021
1022            {
1023                let parent_rb = &bodies[parent_link.rigid_body];
1024                let link_rb = &bodies[link.rigid_body];
1025                let c0 = parent_link.local_to_world * parent_rb.mprops.local_mprops.local_com;
1026                let c2 = link.local_to_world
1027                    * Point::from(link.joint.data.local_frame2.translation.vector);
1028                let c3 = link.local_to_world * link_rb.mprops.local_mprops.local_com;
1029
1030                link.shift02 = c2 - c0;
1031                link.shift23 = c3 - c2;
1032            }
1033
1034            assert_eq!(
1035                bodies[link.rigid_body].body_type,
1036                RigidBodyType::Dynamic,
1037                "A rigid-body that is not at the root of a multibody must be dynamic."
1038            );
1039        }
1040
1041        /*
1042         * Compute body jacobians.
1043         */
1044        self.update_body_jacobians();
1045    }
1046
1047    /// Computes the ids of all the links between the root and the link identified by `link_id`.
1048    pub fn kinematic_branch(&self, link_id: usize) -> Vec<usize> {
1049        let mut branch = vec![]; // Perf: avoid allocation.
1050        let mut curr_id = Some(link_id);
1051
1052        while let Some(id) = curr_id {
1053            branch.push(id);
1054            curr_id = self.links[id].parent_id();
1055        }
1056
1057        branch.reverse();
1058        branch
1059    }
1060
1061    /// Apply forward-kinematics to compute the position of a single link of this multibody.
1062    ///
1063    /// If `out_jacobian` is `Some`, this will simultaneously compute the new jacobian of this link.
1064    /// If `displacement` is `Some`, the generalized position considered during transform propagation
1065    /// is the sum of the current position of `self` and this `displacement`.
1066    // TODO: this shares a lot of code with `forward_kinematics` and `update_body_jacobians`, except
1067    //       that we are only traversing a single kinematic chain. Could this be refactored?
1068    pub fn forward_kinematics_single_link(
1069        &self,
1070        bodies: &RigidBodySet,
1071        link_id: usize,
1072        displacement: Option<&[Real]>,
1073        out_jacobian: Option<&mut Jacobian<Real>>,
1074    ) -> Isometry<Real> {
1075        let branch = self.kinematic_branch(link_id);
1076        self.forward_kinematics_single_branch(bodies, &branch, displacement, out_jacobian)
1077    }
1078
1079    /// Apply forward-kinematics to compute the position of a single sorted branch of this multibody.
1080    ///
1081    /// The given `branch` must have the following properties:
1082    /// - It must be sorted, i.e., `branch[i] < branch[i + 1]`.
1083    /// - All the indices must be part of the same kinematic branch.
1084    /// - If a link is `branch[i]`, then `branch[i - 1]` must be its parent.
1085    ///
1086    /// In general, this method shouldn’t be used directly and [`Self::forward_kinematics_single_link`]
1087    /// should be preferred since it computes the branch indices automatically.
1088    ///
1089    /// If you want to calculate the branch indices manually, see [`Self::kinematic_branch`].
1090    ///
1091    /// If `out_jacobian` is `Some`, this will simultaneously compute the new jacobian of this branch.
1092    /// This represents the body jacobian for the last link in the branch.
1093    ///
1094    /// If `displacement` is `Some`, the generalized position considered during transform propagation
1095    /// is the sum of the current position of `self` and this `displacement`.
1096    // TODO: this shares a lot of code with `forward_kinematics` and `update_body_jacobians`, except
1097    //       that we are only traversing a single kinematic chain. Could this be refactored?
1098    #[profiling::function]
1099    pub fn forward_kinematics_single_branch(
1100        &self,
1101        bodies: &RigidBodySet,
1102        branch: &[usize],
1103        displacement: Option<&[Real]>,
1104        mut out_jacobian: Option<&mut Jacobian<Real>>,
1105    ) -> Isometry<Real> {
1106        if let Some(out_jacobian) = out_jacobian.as_deref_mut() {
1107            if out_jacobian.ncols() != self.ndofs {
1108                *out_jacobian = Jacobian::zeros(self.ndofs);
1109            } else {
1110                out_jacobian.fill(0.0);
1111            }
1112        }
1113
1114        let mut parent_link: Option<MultibodyLink> = None;
1115
1116        for i in branch {
1117            let mut link = self.links[*i];
1118
1119            if let Some(displacement) = displacement {
1120                link.joint
1121                    .apply_displacement(&displacement[link.assembly_id..]);
1122            }
1123
1124            let parent_to_world;
1125
1126            if let Some(parent_link) = parent_link {
1127                link.local_to_parent = link.joint.body_to_parent();
1128                link.local_to_world = parent_link.local_to_world * link.local_to_parent;
1129
1130                {
1131                    let parent_rb = &bodies[parent_link.rigid_body];
1132                    let link_rb = &bodies[link.rigid_body];
1133                    let c0 = parent_link.local_to_world * parent_rb.mprops.local_mprops.local_com;
1134                    let c2 = link.local_to_world
1135                        * Point::from(link.joint.data.local_frame2.translation.vector);
1136                    let c3 = link.local_to_world * link_rb.mprops.local_mprops.local_com;
1137
1138                    link.shift02 = c2 - c0;
1139                    link.shift23 = c3 - c2;
1140                }
1141
1142                parent_to_world = parent_link.local_to_world;
1143
1144                if let Some(out_jacobian) = out_jacobian.as_deref_mut() {
1145                    let (mut link_j_v, parent_j_w) =
1146                        out_jacobian.rows_range_pair_mut(0..DIM, DIM..DIM + ANG_DIM);
1147                    let shift_tr = (link.shift02).gcross_matrix_tr();
1148                    link_j_v.gemm(1.0, &shift_tr, &parent_j_w, 1.0);
1149                }
1150            } else {
1151                link.local_to_parent = link.joint.body_to_parent();
1152                link.local_to_world = link.local_to_parent;
1153                parent_to_world = Isometry::identity();
1154            }
1155
1156            if let Some(out_jacobian) = out_jacobian.as_deref_mut() {
1157                let ndofs = link.joint.ndofs();
1158                let mut tmp = SMatrix::<Real, SPATIAL_DIM, SPATIAL_DIM>::zeros();
1159                let mut link_joint_j = tmp.columns_mut(0, ndofs);
1160                let mut link_j_part = out_jacobian.columns_mut(link.assembly_id, ndofs);
1161                link.joint.jacobian(
1162                    &(parent_to_world.rotation * link.joint.data.local_frame1.rotation),
1163                    &mut link_joint_j,
1164                );
1165                link_j_part += link_joint_j;
1166
1167                {
1168                    let (mut link_j_v, link_j_w) =
1169                        out_jacobian.rows_range_pair_mut(0..DIM, DIM..DIM + ANG_DIM);
1170                    let shift_tr = link.shift23.gcross_matrix_tr();
1171                    link_j_v.gemm(1.0, &shift_tr, &link_j_w, 1.0);
1172                }
1173            }
1174
1175            parent_link = Some(link);
1176        }
1177
1178        parent_link
1179            .map(|link| link.local_to_world)
1180            .unwrap_or_else(Isometry::identity)
1181    }
1182
1183    /// The total number of freedoms of this multibody.
1184    #[inline]
1185    pub fn ndofs(&self) -> usize {
1186        self.ndofs
1187    }
1188
1189    pub(crate) fn fill_jacobians(
1190        &self,
1191        link_id: usize,
1192        unit_force: Vector<Real>,
1193        unit_torque: SVector<Real, ANG_DIM>,
1194        j_id: &mut usize,
1195        jacobians: &mut DVector<Real>,
1196    ) -> (Real, Real) {
1197        if self.ndofs == 0 {
1198            return (0.0, 0.0);
1199        }
1200
1201        let wj_id = *j_id + self.ndofs;
1202        let force = Force {
1203            linear: unit_force,
1204            #[cfg(feature = "dim2")]
1205            angular: unit_torque[0],
1206            #[cfg(feature = "dim3")]
1207            angular: unit_torque,
1208        };
1209
1210        let link = &self.links[link_id];
1211        let mut out_j = jacobians.rows_mut(*j_id, self.ndofs);
1212        self.body_jacobians[link.internal_id].tr_mul_to(force.as_vector(), &mut out_j);
1213
1214        // TODO: Optimize with a copy_nonoverlapping?
1215        for i in 0..self.ndofs {
1216            jacobians[wj_id + i] = jacobians[*j_id + i];
1217        }
1218
1219        {
1220            let mut out_invm_j = jacobians.rows_mut(wj_id, self.ndofs);
1221            self.augmented_mass_indices
1222                .with_rearranged_rows_mut(&mut out_invm_j, |out_invm_j| {
1223                    self.inv_augmented_mass.solve_mut(out_invm_j);
1224                });
1225        }
1226
1227        let j = jacobians.rows(*j_id, self.ndofs);
1228        let invm_j = jacobians.rows(wj_id, self.ndofs);
1229        *j_id += self.ndofs * 2;
1230
1231        (j.dot(&invm_j), j.dot(&self.generalized_velocity()))
1232    }
1233
1234    // #[cfg(feature = "parallel")]
1235    // #[inline]
1236    // pub(crate) fn has_active_internal_constraints(&self) -> bool {
1237    //     self.links()
1238    //         .any(|link| link.joint().num_velocity_constraints() != 0)
1239    // }
1240
1241    #[cfg(feature = "parallel")]
1242    #[inline]
1243    #[allow(dead_code)] // That will likely be useful when we re-introduce intra-island parallelism.
1244    pub(crate) fn num_active_internal_constraints_and_jacobian_lines(&self) -> (usize, usize) {
1245        let num_constraints: usize = self
1246            .links
1247            .iter()
1248            .map(|l| l.joint().num_velocity_constraints())
1249            .sum();
1250        (num_constraints, num_constraints)
1251    }
1252}
1253
1254#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
1255#[derive(Clone, Debug)]
1256struct IndexSequence {
1257    first_to_remove: usize,
1258    index_map: Vec<usize>,
1259}
1260
1261impl IndexSequence {
1262    fn new() -> Self {
1263        Self {
1264            first_to_remove: usize::MAX,
1265            index_map: vec![],
1266        }
1267    }
1268
1269    fn clear(&mut self) {
1270        self.first_to_remove = usize::MAX;
1271        self.index_map.clear();
1272    }
1273
1274    fn keep(&mut self, i: usize) {
1275        if self.first_to_remove == usize::MAX {
1276            // Nothing got removed yet. No need to register any
1277            // special indexing.
1278            return;
1279        }
1280
1281        self.index_map.push(i);
1282    }
1283
1284    fn remove(&mut self, i: usize) {
1285        if self.first_to_remove == usize::MAX {
1286            self.first_to_remove = i;
1287        }
1288    }
1289
1290    fn dim_after_removal(&self, original_dim: usize) -> usize {
1291        if self.first_to_remove == usize::MAX {
1292            original_dim
1293        } else {
1294            self.first_to_remove + self.index_map.len()
1295        }
1296    }
1297
1298    fn rearrange_columns<R: na::Dim, C: na::Dim, S: StorageMut<Real, R, C>>(
1299        &self,
1300        mat: &mut na::Matrix<Real, R, C, S>,
1301        clear_removed: bool,
1302    ) {
1303        if self.first_to_remove == usize::MAX {
1304            // Nothing to rearrange.
1305            return;
1306        }
1307
1308        for (target_shift, source) in self.index_map.iter().enumerate() {
1309            let target = self.first_to_remove + target_shift;
1310            let (mut target_col, source_col) = mat.columns_range_pair_mut(target, *source);
1311            target_col.copy_from(&source_col);
1312        }
1313
1314        if clear_removed {
1315            mat.columns_range_mut(self.first_to_remove + self.index_map.len()..)
1316                .fill(0.0);
1317        }
1318    }
1319
1320    fn rearrange_rows<R: na::Dim, C: na::Dim, S: StorageMut<Real, R, C>>(
1321        &self,
1322        mat: &mut na::Matrix<Real, R, C, S>,
1323        clear_removed: bool,
1324    ) {
1325        if self.first_to_remove == usize::MAX {
1326            // Nothing to rearrange.
1327            return;
1328        }
1329
1330        for mut col in mat.column_iter_mut() {
1331            for (target_shift, source) in self.index_map.iter().enumerate() {
1332                let target = self.first_to_remove + target_shift;
1333                col[target] = col[*source];
1334            }
1335
1336            if clear_removed {
1337                col.rows_range_mut(self.first_to_remove + self.index_map.len()..)
1338                    .fill(0.0);
1339            }
1340        }
1341    }
1342
1343    fn inv_rearrange_rows<R: na::Dim, C: na::Dim, S: StorageMut<Real, R, C>>(
1344        &self,
1345        mat: &mut na::Matrix<Real, R, C, S>,
1346    ) {
1347        if self.first_to_remove == usize::MAX {
1348            // Nothing to rearrange.
1349            return;
1350        }
1351
1352        for mut col in mat.column_iter_mut() {
1353            for (target_shift, source) in self.index_map.iter().enumerate().rev() {
1354                let target = self.first_to_remove + target_shift;
1355                col[*source] = col[target];
1356                col[target] = 0.0;
1357            }
1358        }
1359    }
1360
1361    fn with_rearranged_rows_mut<C: na::Dim, S: StorageMut<Real, Dyn, C>>(
1362        &self,
1363        mat: &mut na::Matrix<Real, Dyn, C, S>,
1364        mut f: impl FnMut(&mut na::MatrixViewMut<Real, Dyn, C, S::RStride, S::CStride>),
1365    ) {
1366        self.rearrange_rows(mat, true);
1367        let effective_dim = self.dim_after_removal(mat.nrows());
1368        if effective_dim > 0 {
1369            f(&mut mat.rows_mut(0, effective_dim));
1370        }
1371        self.inv_rearrange_rows(mat);
1372    }
1373}
1374
1375#[cfg(test)]
1376mod test {
1377    use super::IndexSequence;
1378    use crate::dynamics::{ImpulseJointSet, IslandManager};
1379    use crate::math::{Real, SPATIAL_DIM};
1380    use crate::prelude::{
1381        ColliderSet, MultibodyJointHandle, MultibodyJointSet, RevoluteJoint, RigidBodyBuilder,
1382        RigidBodySet,
1383    };
1384    use na::{DVector, RowDVector};
1385
1386    #[test]
1387    fn test_multibody_append() {
1388        let mut bodies = RigidBodySet::new();
1389        let mut joints = MultibodyJointSet::new();
1390
1391        let a = bodies.insert(RigidBodyBuilder::dynamic());
1392        let b = bodies.insert(RigidBodyBuilder::dynamic());
1393        let c = bodies.insert(RigidBodyBuilder::dynamic());
1394        let d = bodies.insert(RigidBodyBuilder::dynamic());
1395
1396        #[cfg(feature = "dim2")]
1397        let joint = RevoluteJoint::new();
1398        #[cfg(feature = "dim3")]
1399        let joint = RevoluteJoint::new(na::Vector::x_axis());
1400
1401        let mb_handle = joints.insert(a, b, joint, true).unwrap();
1402        joints.insert(c, d, joint, true).unwrap();
1403        joints.insert(b, c, joint, true).unwrap();
1404
1405        assert_eq!(joints.get(mb_handle).unwrap().0.ndofs, SPATIAL_DIM + 3);
1406    }
1407
1408    #[test]
1409    fn test_multibody_insert() {
1410        let mut rnd = oorandom::Rand32::new(1234);
1411
1412        for k in 0..10 {
1413            let mut bodies = RigidBodySet::new();
1414            let mut multibody_joints = MultibodyJointSet::new();
1415
1416            let num_links = 100;
1417            let mut handles = vec![];
1418
1419            for _ in 0..num_links {
1420                handles.push(bodies.insert(RigidBodyBuilder::dynamic()));
1421            }
1422
1423            let mut insertion_id: Vec<_> = (0..num_links - 1).collect();
1424
1425            #[cfg(feature = "dim2")]
1426            let joint = RevoluteJoint::new();
1427            #[cfg(feature = "dim3")]
1428            let joint = RevoluteJoint::new(na::Vector::x_axis());
1429
1430            match k {
1431                0 => {} // Remove in insertion order.
1432                1 => {
1433                    // Remove from leaf to root.
1434                    insertion_id.reverse();
1435                }
1436                _ => {
1437                    // Shuffle the vector a bit.
1438                    // (This test checks multiple shuffle arrangements due to k > 2).
1439                    for l in 0..num_links - 1 {
1440                        insertion_id.swap(l, rnd.rand_range(0..num_links as u32 - 1) as usize);
1441                    }
1442                }
1443            }
1444
1445            let mut mb_handle = MultibodyJointHandle::invalid();
1446            for i in insertion_id {
1447                mb_handle = multibody_joints
1448                    .insert(handles[i], handles[i + 1], joint, true)
1449                    .unwrap();
1450            }
1451
1452            assert_eq!(
1453                multibody_joints.get(mb_handle).unwrap().0.ndofs,
1454                SPATIAL_DIM + num_links - 1
1455            );
1456        }
1457    }
1458
1459    #[test]
1460    fn test_multibody_remove() {
1461        let mut rnd = oorandom::Rand32::new(1234);
1462
1463        for k in 0..10 {
1464            let mut bodies = RigidBodySet::new();
1465            let mut multibody_joints = MultibodyJointSet::new();
1466            let mut colliders = ColliderSet::new();
1467            let mut impulse_joints = ImpulseJointSet::new();
1468            let mut islands = IslandManager::new();
1469
1470            let num_links = 100;
1471            let mut handles = vec![];
1472
1473            for _ in 0..num_links {
1474                handles.push(bodies.insert(RigidBodyBuilder::dynamic()));
1475            }
1476
1477            #[cfg(feature = "dim2")]
1478            let joint = RevoluteJoint::new();
1479            #[cfg(feature = "dim3")]
1480            let joint = RevoluteJoint::new(na::Vector::x_axis());
1481
1482            for i in 0..num_links - 1 {
1483                multibody_joints
1484                    .insert(handles[i], handles[i + 1], joint, true)
1485                    .unwrap();
1486            }
1487
1488            match k {
1489                0 => {} // Remove in insertion order.
1490                1 => {
1491                    // Remove from leaf to root.
1492                    handles.reverse();
1493                }
1494                _ => {
1495                    // Shuffle the vector a bit.
1496                    // (This test checks multiple shuffle arrangements due to k > 2).
1497                    for l in 0..num_links {
1498                        handles.swap(l, rnd.rand_range(0..num_links as u32) as usize);
1499                    }
1500                }
1501            }
1502
1503            for handle in handles {
1504                bodies.remove(
1505                    handle,
1506                    &mut islands,
1507                    &mut colliders,
1508                    &mut impulse_joints,
1509                    &mut multibody_joints,
1510                    true,
1511                );
1512            }
1513        }
1514    }
1515
1516    fn test_sequence() -> IndexSequence {
1517        let mut seq = IndexSequence::new();
1518        seq.remove(2);
1519        seq.remove(3);
1520        seq.remove(4);
1521        seq.keep(5);
1522        seq.keep(6);
1523        seq.remove(7);
1524        seq.keep(8);
1525        seq
1526    }
1527
1528    #[test]
1529    fn index_sequence_rearrange_columns() {
1530        let seq = test_sequence();
1531        let mut vec = RowDVector::from_fn(10, |_, c| c as Real);
1532        seq.rearrange_columns(&mut vec, true);
1533        assert_eq!(
1534            vec,
1535            RowDVector::from(vec![0.0, 1.0, 5.0, 6.0, 8.0, 0.0, 0.0, 0.0, 0.0, 0.0])
1536        );
1537    }
1538
1539    #[test]
1540    fn index_sequence_rearrange_rows() {
1541        let seq = test_sequence();
1542        let mut vec = DVector::from_fn(10, |r, _| r as Real);
1543        seq.rearrange_rows(&mut vec, true);
1544        assert_eq!(
1545            vec,
1546            DVector::from(vec![0.0, 1.0, 5.0, 6.0, 8.0, 0.0, 0.0, 0.0, 0.0, 0.0])
1547        );
1548        seq.inv_rearrange_rows(&mut vec);
1549        assert_eq!(
1550            vec,
1551            DVector::from(vec![0.0, 1.0, 0.0, 0.0, 0.0, 5.0, 6.0, 0.0, 8.0, 0.0])
1552        );
1553    }
1554
1555    #[test]
1556    fn index_sequence_with_rearranged_rows_mut() {
1557        let seq = test_sequence();
1558        let mut vec = DVector::from_fn(10, |r, _| r as Real);
1559        seq.with_rearranged_rows_mut(&mut vec, |v| {
1560            assert_eq!(v.len(), 5);
1561            assert_eq!(*v, DVector::from(vec![0.0, 1.0, 5.0, 6.0, 8.0]));
1562            *v *= 10.0;
1563        });
1564        assert_eq!(
1565            vec,
1566            DVector::from(vec![0.0, 10.0, 0.0, 0.0, 0.0, 50.0, 60.0, 0.0, 80.0, 0.0])
1567        );
1568    }
1569}