Skip to main content

mujoco_rs/wrappers/
mj_data.rs

1//! MjData related.
2use crate::{view_creator, info_method, info_with_view, array_slice_dyn};
3use crate::wrappers::mj_auxiliary::{MjVisual, MjStatistic};
4use crate::wrappers::mj_option::MjOption;
5use crate::{getter_setter, mujoco_c::*};
6use crate::error::MjDataError;
7
8use super::mj_statistic::{MjWarningStat, MjTimerStat, MjSolverStat};
9use super::mj_model::{MjModel, MjtSameFrame, MjtObj, MjtStage};
10use super::mj_auxiliary::MjContact;
11use super::mj_primitive::*;
12
13use std::ops::{Deref, DerefMut};
14use std::ptr::{self, NonNull};
15use std::ffi::CString;
16use std::borrow::Cow;
17use std::path::Path;
18use std::fmt::Debug;
19
20/*******************************************/
21// Types
22/// State component elements as integer bitflags and several convenient combinations of these flags. Used by
23/// `mj_getState`, `mj_setState` and `mj_stateSize`.
24pub type MjtState = mjtState;
25
26/// Constraint types. These values are not used in mjModel, but are used in the mjData field `d->efc_type` when the list
27/// of active constraints is constructed at each simulation time step.
28pub type MjtConstraint = mjtConstraint;
29
30/// These values are used by the solver internally to keep track of the constraint states.
31pub type MjtConstraintState = mjtConstraintState;
32
33/// Warning types. The number of warning types is given by `mjNWARNING` which is also the length of the array
34/// `mjData.warning`.
35pub type MjtWarning = mjtWarning;
36
37/// Timer types. The number of timer types is given by `mjNTIMER` which is also the length of the array
38/// `mjData.timer`, as well as the length of the string array `mjTIMERSTRING` with timer names.
39pub type MjtTimer = mjtTimer;
40
41/// Sleep state of an object.
42pub type MjtSleepState = mjtSleepState;
43/*******************************************/
44
45
46/**************************************************************************************************/
47// MjData
48/**************************************************************************************************/
49
50/// Wrapper around the `mjData` struct.
51/// Provides lifetime guarantees as well as automatic cleanup.
52#[derive(Debug)]
53pub struct MjData<M: Deref<Target = MjModel>> {
54    data: NonNull<mjData>,
55    model: M
56}
57
58// Allow usage in threaded contexts as long as M itself is Send / Sync
59// (e.g. Arc<MjModel>). Non-Send M types such as Rc<MjModel> are correctly
60// excluded by the M: Send / M: Sync bounds.
61// SAFETY: MjData owns its mjData heap allocation exclusively. Send/Sync follow from M's bounds.
62unsafe impl<M: Deref<Target = MjModel> + Send> Send for MjData<M> {}
63unsafe impl<M: Deref<Target = MjModel> + Sync> Sync for MjData<M> {}
64
65
66impl<M: Deref<Target = MjModel>> MjData<M> {
67    /// Creates a new [`MjData`] linked to `model`.
68    ///
69    /// # Panics
70    /// Panics if MuJoCo fails to allocate the data structure.
71    /// Use [`MjData::try_new`] for a fallible alternative.
72    pub fn new(model: M) -> Self {
73        Self::try_new(model).expect("allocation of MjData failed")
74    }
75
76    /// Fallible version of [`MjData::new`].
77    ///
78    /// # Errors
79    /// Returns [`MjDataError::AllocationFailed`] if MuJoCo returns a null pointer from `mj_makeData`.
80    ///
81    /// Prefer this method over [`MjData::new`] when you want to handle
82    /// allocation failures without a panic.
83    pub fn try_new(model: M) -> Result<Self, MjDataError> {
84        // SAFETY: model.ffi() is a valid non-null mjModel pointer; mj_makeData may return null
85        // on allocation failure, handled below.
86        let data_ptr = unsafe { mj_makeData(model.ffi()) };
87        NonNull::new(data_ptr)
88            .map(|data| Self { data, model })
89            .ok_or(MjDataError::AllocationFailed)
90    }
91
92    /// Sets a new [`MjModel`] to be used within the instance. This can be used to modify [`MjModel`]'s
93    /// parameters without causing size mismatches or violating borrow checker's requirements.
94    /// This can be done by keeping a clone of the model, which is then modified and swapped.
95    /// 
96    /// # Panics
97    /// Panics if the signature of `model` does not match the signature of the model
98    /// this data belongs to.
99    /// 
100    /// Use [`MjData::try_swap_model`] for a fallible alternative.
101    /// 
102    /// # Notes
103    /// This method only validates model-signature compatibility.
104    /// **Not all model parameters are safe (for correct simulation) to change at runtime.**
105    /// See [here](https://mujoco.readthedocs.io/en/3.9.0/programming/simulation.html#mjmodel-changes)
106    /// to see what parameters can be changed.
107    /// 
108    /// If `M` implements [`DerefMut`], prefer
109    /// [`model_mut`](MjData::model_mut) for direct in-place modification instead.
110    /// 
111    /// If model recompilation speed is not an issue,
112    /// it is recommended to use [`MjSpec`](crate::wrappers::mj_editing::MjSpec) instead.
113    /// 
114    /// # Example
115    /// ```
116    /// # use mujoco_rs::prelude::*;
117    /// let mut model_template = Box::new(MjSpec::new().compile().unwrap());
118    /// let model_used = model_template.clone();
119    /// let mut data = MjData::new(model_used);
120    /// 
121    /// model_template.opt_mut().timestep = 0.004;
122    /// model_template = data.swap_model(model_template);
123    /// ```
124    pub fn swap_model(&mut self, model: M) -> M {
125        self.try_swap_model(model).expect("swap_model failed: model signature mismatch")
126    }
127
128    /// Fallible version of [`MjData::swap_model`].
129    ///
130    /// # Errors
131    /// Returns [`MjDataError::SignatureMismatch`] if the new model's signature
132    /// does not match the current one.
133    pub fn try_swap_model(&mut self, model: M) -> Result<M, MjDataError> {
134        let new_signature = model.signature();
135        let current_signature = self.model.signature();
136        if new_signature != current_signature {
137            return Err(MjDataError::SignatureMismatch { source: new_signature, destination: current_signature });
138        }
139
140        Ok(std::mem::replace(&mut self.model, model))
141    }
142
143    /// Returns a slice of detected contacts.
144    /// To obtain the contact force, call [`MjData::contact_force`].
145    #[deprecated(since = "3.0.0", note = "use contact() instead")]
146    pub fn contacts(&self) -> &[MjContact] {
147        let ffi = self.ffi();
148        let ptr = ffi.contact;
149        if ptr.is_null() {
150            &[]
151        } else {
152            // SAFETY: ptr is non-null (checked above), points to a valid array of `ncon`
153            // initialized mjContact values owned by MjData, and is valid for `'self`.
154            unsafe { std::slice::from_raw_parts(ptr, ffi.ncon as usize) }
155        }
156    }
157
158    info_method! { Data, [model], body, [
159        xfrc_applied: 6, xpos: 3, xquat: 4, xmat: 9, xipos: 3, ximat: 9, subtree_com: 3, cinert: 10,
160        crb: 10, cvel: 6, subtree_linvel: 3, subtree_angmom: 3, cacc: 6, cfrc_int: 6, cfrc_ext: 6,
161        awake: 1
162    ], [], []}
163    info_method! { Data, [model], camera, [xpos: 3, xmat: 9], [], []}
164    info_method! { Data, [model], geom, [xpos: 3, xmat: 9], [], []}
165    info_method! { Data, [model], site, [xpos: 3, xmat: 9], [], []}
166    info_method! { Data, [model], light, [xpos: 3, xdir: 3], [], []}
167
168    info_method! { Data, [model], actuator,
169        [ctrl: 1, length: 1, velocity: 1, force: 1],
170        [],
171        [act: na]
172    }
173
174    /// Obtains a [`MjJointDataInfo`] struct containing information about the name, id, and
175    /// indices required for obtaining a slice view to the correct locations in [`MjData`].
176    /// The actual view can be obtained via [`MjJointDataInfo::view`].
177    /// # Panics
178    /// When the `name` contains '\0' characters, a panic occurs.
179    pub fn joint(&self, name: &str) -> Option<MjJointDataInfo> {
180        let model = self.model();
181        let id = model.name_to_id(MjtObj::mjOBJ_JOINT, name)?;
182        let nq_range = {
183            let slice = model.jnt_qposadr();
184            crate::util::optional_sparse_addr_range(slice, id, model.nq() as usize).unwrap_or((0, 0))
185        };
186        let nv_range = {
187            let slice = model.jnt_dofadr();
188            crate::util::optional_sparse_addr_range(slice, id, model.nv() as usize).unwrap_or((0, 0))
189        };
190
191        let qpos = nq_range;
192        let qvel = nv_range;
193        let qacc_warmstart = nv_range;
194        let qfrc_applied = nv_range;
195        let qacc = nv_range;
196        let xanchor = (id * 3, 3);
197        let xaxis = (id * 3, 3);
198        #[allow(non_snake_case)]
199        let qLDiagInv = nv_range;
200        let qfrc_bias = nv_range;
201        let qfrc_passive = nv_range;
202        let qfrc_actuator = nv_range;
203        let qfrc_smooth = nv_range;
204        let qacc_smooth = nv_range;
205        let qfrc_constraint = nv_range;
206        let qfrc_inverse = nv_range;
207
208        let qfrc_spring = nv_range;
209        let qfrc_damper = nv_range;
210        let qfrc_gravcomp = nv_range;
211        let qfrc_fluid = nv_range;
212
213        let model_signature = self.model.signature();
214        Some(MjJointDataInfo {name: name.to_string(), id, model_signature,
215            qpos, qvel, qacc_warmstart, qfrc_applied, qacc, xanchor, xaxis, qLDiagInv, qfrc_bias,
216            qfrc_spring, qfrc_damper, qfrc_gravcomp, qfrc_fluid, qfrc_passive,
217            qfrc_actuator, qfrc_smooth, qacc_smooth, qfrc_constraint, qfrc_inverse
218        })
219    }
220
221    info_method! { Data, [model], sensor, [], [], [data: nsensordata] }
222
223
224    info_method! { Data, [model], tendon,
225        [wrapadr: 1, wrapnum: 1, efcadr: 1, length: 1, velocity: 1],
226        [],
227        [J: nJten]
228    }
229
230    /// Steps the MuJoCo simulation.
231    pub fn step(&mut self) {
232        unsafe {
233            mj_step(self.model.ffi(), self.ffi_mut());
234        }
235    }
236
237    /// Runs the first phase of a simulation step: computes kinematics and sensor data,
238    /// before the user sets controls. This is a wrapper around `mj_step1`.
239    pub fn step1(&mut self) {
240        unsafe {
241            mj_step1(self.model.ffi(), self.ffi_mut());
242        }
243    }
244
245    /// Runs the second phase of a simulation step: computes dynamics and integrates forward
246    /// in time, after the user sets controls. This is a wrapper around `mj_step2`.
247    pub fn step2(&mut self) {
248        unsafe {
249            mj_step2(self.model.ffi(), self.ffi_mut());
250        }
251    }
252
253    /// Forward dynamics: same as mj_step but do not integrate in time.
254    /// This is a wrapper around `mj_forward`.
255    pub fn forward(&mut self) {
256        unsafe {
257            mj_forward(self.model.ffi(), self.ffi_mut());
258        }
259    }
260
261    /// [`MjData::forward`] dynamics with skip.
262    /// This is a wrapper around `mj_forwardSkip`.
263    pub fn forward_skip(&mut self, skipstage: MjtStage, skipsensor: bool) {
264        unsafe {
265            mj_forwardSkip(self.model.ffi(), self.ffi_mut(), skipstage as i32, skipsensor as i32);
266        }
267    }
268
269    /// Inverse dynamics: qacc must be set before calling this function.
270    /// This is a wrapper around `mj_inverse`.
271    pub fn inverse(&mut self) {
272        unsafe {
273            mj_inverse(self.model.ffi(), self.ffi_mut());
274        }
275    }
276
277    /// [`MjData::inverse`] dynamics with skip; skipstage is [`MjtStage`].
278    /// This is a wrapper around `mj_inverseSkip`.
279    pub fn inverse_skip(&mut self, skipstage: MjtStage, skipsensor: bool) {
280        unsafe {
281            mj_inverseSkip(self.model.ffi(), self.ffi_mut(), skipstage as i32, skipsensor as i32);
282        }
283    }
284
285    /// Extracts the contact force in the contact frame for the given `contact_id`.
286    /// The `contact_id` matches the index of the contact when iterating
287    /// via [`MjData::contact`].
288    /// Calls `mj_contactForce` internally.
289    /// # Note
290    /// When `contact_id >= ncon`, `[0; 6]` is returned.
291    pub fn contact_force(&self, contact_id: usize) -> [MjtNum; 6] {
292        let mut force = [0.0; 6];
293        unsafe {
294            mj_contactForce(
295                self.model.ffi(), self.data.as_ptr(),
296                contact_id as i32, &mut force
297            );
298        }
299        force
300    }
301
302    /* Partially auto-generated */
303
304    /// Reset data to defaults.
305    pub fn reset(&mut self) {
306        unsafe { mj_resetData(self.model.ffi(), self.ffi_mut()) }
307    }
308
309    /// Reset data to defaults, fill everything else with debug_value.
310    ///
311    /// # Safety
312    /// `debug_value` is written as raw bytes into every buffer-resident array,
313    /// including ones whose element types have validity invariants (e.g.
314    /// [`bvh_active`](Self::bvh_active) -> `&[bool]`,
315    /// [`body_awake`](Self::body_awake) -> `&[MjtSleepState]`). The caller must
316    /// not call such accessors before a subsequent [`reset`](Self::reset) unless
317    /// `debug_value` produces valid bit patterns for them.
318    pub unsafe fn reset_debug(&mut self, debug_value: u8) {
319        unsafe { mj_resetDataDebug(self.model.ffi(), self.ffi_mut(), debug_value) }
320    }
321
322    /// Reset data to keyframe `key` (zero-based index).
323    ///
324    /// # Errors
325    /// Returns [`MjDataError::IndexOutOfBounds`] if `key >= nkey`.
326    pub fn reset_keyframe(&mut self, key: usize) -> Result<(), MjDataError> {
327        let nkey = self.model.ffi().nkey as usize;
328        if key >= nkey {
329            return Err(MjDataError::IndexOutOfBounds {
330                kind: "key",
331                id: key,
332                upper: nkey,
333            });
334        }
335        unsafe { mj_resetDataKeyframe(self.model.ffi(), self.ffi_mut(), key as i32) }
336        Ok(())
337    }
338
339    /// Print mjData to text file, specifying format.
340    /// float_format must be a valid printf-style format string for a single float value.
341    /// # Returns
342    /// `Ok(())` on success.
343    /// # Errors
344    /// - [`MjDataError::InvalidUtf8Path`] if the path contains invalid UTF-8.
345    /// # Panics
346    /// When either string contains '\0' characters, a panic occurs.
347    pub fn print_formatted<T: AsRef<Path>>(&self, filename: T, float_format: &str) -> Result<(), MjDataError> {
348        let path_str = filename.as_ref().to_str()
349            .ok_or(MjDataError::InvalidUtf8Path)?;
350        let c_filename = CString::new(path_str).unwrap();
351        let c_float_format = CString::new(float_format).unwrap();
352        unsafe { mj_printFormattedData(self.model.ffi(), self.ffi(), c_filename.as_ptr(), c_float_format.as_ptr()) }
353        Ok(())
354    }
355
356    /// Print data to text file.
357    /// # Returns
358    /// `Ok(())` on success.
359    /// # Errors
360    /// - [`MjDataError::InvalidUtf8Path`] if the path contains invalid UTF-8.
361    /// # Panics
362    /// When the filename contains '\0' characters, a panic occurs.
363    pub fn print<T: AsRef<Path>>(&self, filename: T) -> Result<(), MjDataError> {
364        let path_str = filename.as_ref().to_str()
365            .ok_or(MjDataError::InvalidUtf8Path)?;
366        let c_filename = CString::new(path_str).unwrap();
367        unsafe { mj_printData(self.model.ffi(), self.ffi(), c_filename.as_ptr()) }
368        Ok(())
369    }
370
371    /// Run position-dependent computations.
372    pub fn fwd_position(&mut self) {
373        unsafe { mj_fwdPosition(self.model.ffi(), self.ffi_mut()) }
374    }
375
376    /// Run velocity-dependent computations.
377    pub fn fwd_velocity(&mut self) {
378        unsafe { mj_fwdVelocity(self.model.ffi(), self.ffi_mut()) }
379    }
380
381    /// Compute actuator force qfrc_actuator.
382    pub fn fwd_actuation(&mut self) {
383        unsafe { mj_fwdActuation(self.model.ffi(), self.ffi_mut()) }
384    }
385
386    /// Add up all non-constraint forces, compute qacc_smooth.
387    pub fn fwd_acceleration(&mut self) {
388        unsafe { mj_fwdAcceleration(self.model.ffi(), self.ffi_mut()) }
389    }
390
391    /// Run selected constraint solver.
392    pub fn fwd_constraint(&mut self) {
393        unsafe { mj_fwdConstraint(self.model.ffi(), self.ffi_mut()) }
394    }
395
396    /// Euler integrator, semi-implicit in velocity.
397    pub fn euler(&mut self) {
398        unsafe { mj_Euler(self.model.ffi(), self.ffi_mut()) }
399    }
400
401    /// Runge-Kutta explicit order-N integrator.
402    ///
403    /// # Panics
404    /// Panics if `n != 4`. The underlying MuJoCo C implementation only supports N=4;
405    /// any other value causes an unconditional process abort via `mjERROR`.
406    pub fn runge_kutta(&mut self, n: u32) {
407        assert!(n == 4, "mj_RungeKutta only supports N=4, got {n}");
408        unsafe { mj_RungeKutta(self.model.ffi(), self.ffi_mut(), n as i32) }
409    }
410
411    /// Implicit-in-velocity integrators.
412    pub fn implicit(&mut self) {
413        unsafe { mj_implicit(self.model.ffi(), self.ffi_mut()) }
414    }
415
416    /// Run position-dependent computations in inverse dynamics.
417    pub fn inv_position(&mut self) {
418        unsafe { mj_invPosition(self.model.ffi(), self.ffi_mut()) }
419    }
420
421    /// Run velocity-dependent computations in inverse dynamics.
422    pub fn inv_velocity(&mut self) {
423        unsafe { mj_invVelocity(self.model.ffi(), self.ffi_mut()) }
424    }
425
426    /// Apply the analytical formula for inverse constraint dynamics.
427    pub fn inv_constraint(&mut self) {
428        unsafe { mj_invConstraint(self.model.ffi(), self.ffi_mut()) }
429    }
430
431    /// Compare forward and inverse dynamics, save results in fwdinv.
432    pub fn compare_fwd_inv(&mut self) {
433        unsafe { mj_compareFwdInv(self.model.ffi(), self.ffi_mut()) }
434    }
435
436    /// Evaluate position-dependent sensors.
437    pub fn sensor_pos(&mut self) {
438        unsafe { mj_sensorPos(self.model.ffi(), self.ffi_mut()) }
439    }
440
441    /// Evaluate velocity-dependent sensors.
442    pub fn sensor_vel(&mut self) {
443        unsafe { mj_sensorVel(self.model.ffi(), self.ffi_mut()) }
444    }
445
446    /// Evaluate acceleration and force-dependent sensors.
447    pub fn sensor_acc(&mut self) {
448        unsafe { mj_sensorAcc(self.model.ffi(), self.ffi_mut()) }
449    }
450
451    /// Evaluate position-dependent energy (potential).
452    pub fn energy_pos(&mut self) {
453        unsafe { mj_energyPos(self.model.ffi(), self.ffi_mut()) }
454    }
455
456    /// Evaluate velocity-dependent energy (kinetic).
457    pub fn energy_vel(&mut self) {
458        unsafe { mj_energyVel(self.model.ffi(), self.ffi_mut()) }
459    }
460
461    /// Check qpos, reset if any element is too big or nan.
462    pub fn check_pos(&mut self) {
463        unsafe { mj_checkPos(self.model.ffi(), self.ffi_mut()) }
464    }
465
466    /// Check qvel, reset if any element is too big or nan.
467    pub fn check_vel(&mut self) {
468        unsafe { mj_checkVel(self.model.ffi(), self.ffi_mut()) }
469    }
470
471    /// Check qacc, reset if any element is too big or nan.
472    pub fn check_acc(&mut self) {
473        unsafe { mj_checkAcc(self.model.ffi(), self.ffi_mut()) }
474    }
475
476    /// Run forward kinematics.
477    pub fn kinematics(&mut self) {
478        unsafe { mj_kinematics(self.model.ffi(), self.ffi_mut()) }
479    }
480
481    /// Map inertias and motion dofs to global frame centered at CoM.
482    pub fn com_pos(&mut self) {
483        unsafe { mj_comPos(self.model.ffi(), self.ffi_mut()) }
484    }
485
486    /// Compute camera and light positions and orientations.
487    pub fn camlight(&mut self) {
488        unsafe { mj_camlight(self.model.ffi(), self.ffi_mut()) }
489    }
490
491    /// Compute flex-related quantities.
492    pub fn flex_comp(&mut self) {
493        unsafe { mj_flex(self.model.ffi(), self.ffi_mut()) }
494    }
495
496    /// Compute tendon lengths, velocities and moment arms.
497    pub fn tendon_comp(&mut self) {
498        unsafe { mj_tendon(self.model.ffi(), self.ffi_mut()) }
499    }
500
501    /// Compute actuator transmission lengths and moments.
502    pub fn transmission(&mut self) {
503        unsafe { mj_transmission(self.model.ffi(), self.ffi_mut()) }
504    }
505
506    /// Run composite rigid body inertia algorithm (CRB).
507    pub fn crb_comp(&mut self) {
508        unsafe { mj_crb(self.model.ffi(), self.ffi_mut()) }
509    }
510
511    /// Make inertia matrix.
512    pub fn make_m(&mut self) {
513        unsafe { mj_makeM(self.model.ffi(), self.ffi_mut()) }
514    }
515
516    /// Compute sparse L'*D*L factorization of inertia matrix.
517    pub fn factor_m(&mut self) {
518        unsafe { mj_factorM(self.model.ffi(), self.ffi_mut()) }
519    }
520
521    /// Compute cvel, cdof_dot.
522    pub fn com_vel(&mut self) {
523        unsafe { mj_comVel(self.model.ffi(), self.ffi_mut()) }
524    }
525
526    /// Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces.
527    pub fn passive(&mut self) {
528        unsafe { mj_passive(self.model.ffi(), self.ffi_mut()) }
529    }
530
531    /// Sub-tree linear velocity and angular momentum: compute subtree_linvel, subtree_angmom.
532    pub fn subtree_vel(&mut self) {
533        unsafe { mj_subtreeVel(self.model.ffi(), self.ffi_mut()) }
534    }
535
536    /// RNE: compute M(qpos)*qacc + C(qpos,qvel); flg_acc=false removes inertial term.
537    pub fn rne(&mut self, flg_acc: bool) -> Vec<MjtNum> {
538        let mut out = vec![0.0; self.model.ffi().nv as usize];
539        unsafe { mj_rne(self.model.ffi(), self.ffi_mut(), flg_acc as i32, out.as_mut_ptr()) };
540        out
541    }
542
543    /// RNE with complete data: compute cacc, cfrc_ext, cfrc_int.
544    pub fn rne_post_constraint(&mut self) {
545        unsafe { mj_rnePostConstraint(self.model.ffi(), self.ffi_mut()) }
546    }
547
548    /// Run collision detection.
549    pub fn collision(&mut self) {
550        unsafe { mj_collision(self.model.ffi(), self.ffi_mut()) }
551    }
552
553    /// Construct constraints.
554    pub fn make_constraint(&mut self) {
555        unsafe { mj_makeConstraint(self.model.ffi(), self.ffi_mut()) }
556    }
557
558    /// Find constraint islands.
559    pub fn island(&mut self) {
560        unsafe { mj_island(self.model.ffi(), self.ffi_mut()) }
561    }
562
563    /// Compute inverse constraint inertia efc_AR.
564    pub fn project_constraint(&mut self) {
565        unsafe { mj_projectConstraint(self.model.ffi(), self.ffi_mut()) }
566    }
567
568    /// Compute efc_vel, efc_aref.
569    pub fn reference_constraint(&mut self) {
570        unsafe { mj_referenceConstraint(self.model.ffi(), self.ffi_mut()) }
571    }
572
573    /// Compute efc_state, efc_force, qfrc_constraint, and (optionally) cone Hessians.
574    /// If cost is not `None`, set `*cost = s(jar)` where `jar = Jac*qacc - aref`.
575    /// # Errors
576    /// Returns [`MjDataError::BufferTooSmall`] if `jar.len() < nefc` (buffer too small).
577    pub fn constraint_update(&mut self, jar: &[MjtNum], cost: Option<&mut MjtNum>, flg_cone_hessian: bool) -> Result<(), MjDataError> {
578        let nefc = self.ffi().nefc as usize;
579        if jar.len() < nefc {
580            return Err(MjDataError::BufferTooSmall { name: "jar", got: jar.len(), needed: nefc });
581        }
582
583        unsafe { mj_constraintUpdate(
584            self.model.ffi(), self.ffi_mut(),
585            jar.as_ptr(), cost.map_or(ptr::null_mut(), |x| x as *mut MjtNum),
586            flg_cone_hessian as i32
587        ) };
588
589        Ok(())
590    }
591
592    /// Initializes the actuator history buffer for actuator `id` (wraps `mj_initCtrlHistory`).
593    /// `times`: optional timestamps slice of length `nsample`; `None` keeps existing timestamps.
594    /// `values`: control values slice of length `nsample`.
595    /// # Errors
596    /// - [`MjDataError::IndexOutOfBounds`] if `id >= nu`.
597    /// - [`MjDataError::NoHistoryBuffer`] if the actuator has no history buffer.
598    /// - [`MjDataError::LengthMismatch`] if `times` or `values` have the wrong length.
599    pub fn init_ctrl_history(&mut self, id: usize, times: Option<&[MjtNum]>, values: &[MjtNum]) -> Result<(), MjDataError> {
600        let nu = self.model.ffi().nu as usize;
601        if id >= nu {
602            return Err(MjDataError::IndexOutOfBounds { kind: "actuator_id", id, upper: nu });
603        }
604
605        let nsample = self.model.actuator_history()[id][0];
606        if nsample <= 0 {
607            return Err(MjDataError::NoHistoryBuffer { kind: "actuator", id });
608        }
609
610        let ns = nsample as usize;
611        if let Some(t) = times
612            && t.len() != ns
613        {
614            return Err(MjDataError::LengthMismatch { name: "times", expected: ns, got: t.len() });
615        }
616        if values.len() != ns {
617            return Err(MjDataError::LengthMismatch { name: "values", expected: ns, got: values.len() });
618        }
619
620        unsafe {
621            mj_initCtrlHistory(
622                self.model.ffi(), self.ffi_mut(), id as i32,
623                times.map_or(ptr::null(), |x| x.as_ptr()),
624                values.as_ptr()
625            );
626        }
627
628        Ok(())
629    }
630
631    /// Initializes the sensor history buffer for sensor `id` (wraps `mj_initSensorHistory`).
632    /// `times`: optional timestamps slice of length `nsample`; `None` keeps existing timestamps.
633    /// `values`: sensor values slice of length `nsample * dim`.
634    /// `phase`: time phase offset.
635    /// # Errors
636    /// - [`MjDataError::IndexOutOfBounds`] if `id >= nsensor`.
637    /// - [`MjDataError::NoHistoryBuffer`] if the sensor has no history buffer.
638    /// - [`MjDataError::LengthMismatch`] if `times` or `values` have the wrong length.
639    pub fn init_sensor_history(&mut self, id: usize, times: Option<&[MjtNum]>, values: &[MjtNum], phase: MjtNum) -> Result<(), MjDataError> {
640        let nsensor = self.model.ffi().nsensor as usize;
641        if id >= nsensor {
642            return Err(MjDataError::IndexOutOfBounds { kind: "sensor_id", id, upper: nsensor });
643        }
644
645        let nsample = self.model.sensor_history()[id][0];
646        if nsample <= 0 {
647            return Err(MjDataError::NoHistoryBuffer { kind: "sensor", id });
648        }
649
650        let dim = self.model.sensor_dim()[id] as usize;
651        let required = (nsample as usize) * dim;
652
653        if let Some(t) = times
654            && t.len() != nsample as usize
655        {
656            return Err(MjDataError::LengthMismatch { name: "times", expected: nsample as usize, got: t.len() });
657        }
658        if values.len() != required {
659            return Err(MjDataError::LengthMismatch { name: "values", expected: required, got: values.len() });
660        }
661
662        unsafe {
663            mj_initSensorHistory(
664                self.model.ffi(), self.ffi_mut(), id as i32,
665                times.map_or(ptr::null(), |x| x.as_ptr()),
666                values.as_ptr(), phase
667            );
668        }
669
670        Ok(())
671    }
672
673    /// Reads the control history value for actuator `id` at `time`
674    /// (`interp`: -1=stored, 0=ZOH, 1=linear, 2=cubic).
675    /// # Panics
676    /// Panics when `id >= nu`. Use [`MjData::try_read_ctrl`] for a fallible alternative.
677    pub fn read_ctrl(&self, id: usize, time: MjtNum, interp: i32) -> MjtNum {
678        self.try_read_ctrl(id, time, interp).unwrap()
679    }
680
681    /// Fallible version of [`MjData::read_ctrl`].
682    /// # Errors
683    /// Returns [`MjDataError::IndexOutOfBounds`] when `id >= nu`.
684    pub fn try_read_ctrl(&self, id: usize, time: MjtNum, interp: i32) -> Result<MjtNum, MjDataError> {
685        let nu = self.model.ffi().nu as usize;
686        if id >= nu {
687            return Err(MjDataError::IndexOutOfBounds { kind: "actuator_id", id, upper: nu });
688        }
689        let val = unsafe { mj_readCtrl(self.model.ffi(), self.ffi(), id as i32, time, interp) };
690        Ok(val)
691    }
692
693    /// Reads sensor `id` at `time` into `dst` (`interp`: -1=stored, 0=ZOH, 1=linear, 2=cubic).
694    /// `dst` must be exactly `sensor_dim[id]` elements long.
695    /// # Errors
696    /// Returns [`MjDataError::IndexOutOfBounds`] when `id >= nsensor`.
697    /// Returns [`MjDataError::LengthMismatch`] when `dst.len() != sensor_dim[id]`.
698    pub fn read_sensor_into(&self, id: usize, time: MjtNum, interp: i32, dst: &mut [MjtNum]) -> Result<(), MjDataError> {
699        let nsensor = self.model.ffi().nsensor as usize;
700        if id >= nsensor {
701            return Err(MjDataError::IndexOutOfBounds { kind: "sensor_id", id, upper: nsensor });
702        }
703
704        let dim = self.model.sensor_dim()[id] as usize;
705        if dst.len() != dim {
706            return Err(MjDataError::LengthMismatch { name: "dst", expected: dim, got: dst.len() });
707        }
708        let ptr = unsafe { mj_readSensor(self.model.ffi(), self.ffi(), id as i32, time, dst.as_mut_ptr(), interp) };
709        if !ptr.is_null() {
710            // C returned a pointer (no interpolation) - copy into dst.
711            dst.copy_from_slice(unsafe { std::slice::from_raw_parts(ptr, dim) });
712        }
713        Ok(())
714    }
715
716    /// Reads sensor `id` at `time` into a stack-allocated `[MjtNum; N]`
717    /// (`interp`: -1=stored, 0=ZOH, 1=linear, 2=cubic). `N` must match `sensor_dim[id]`.
718    /// See also [`read_sensor`](Self::read_sensor), [`read_sensor_into`](Self::read_sensor_into).
719    /// # Panics
720    /// Panics when `id >= nsensor` or `N != sensor_dim[id]`.
721    /// Use [`MjData::try_read_sensor_fixed`] for a fallible alternative.
722    pub fn read_sensor_fixed<const N: usize>(&self, id: usize, time: MjtNum, interp: i32) -> [MjtNum; N] {
723        self.try_read_sensor_fixed(id, time, interp).unwrap()
724    }
725
726    /// Fallible version of [`MjData::read_sensor_fixed`].
727    /// # Errors
728    /// Returns [`MjDataError::IndexOutOfBounds`] when `id >= nsensor`.
729    /// Returns [`MjDataError::LengthMismatch`] when `N != sensor_dim[id]`.
730    pub fn try_read_sensor_fixed<const N: usize>(&self, id: usize, time: MjtNum, interp: i32) -> Result<[MjtNum; N], MjDataError> {
731        let nsensor = self.model.ffi().nsensor as usize;
732        if id >= nsensor {
733            return Err(MjDataError::IndexOutOfBounds { kind: "sensor_id", id, upper: nsensor });
734        }
735
736        let dim = self.model.sensor_dim()[id] as usize;
737        if N != dim {
738            return Err(MjDataError::LengthMismatch { name: "N", expected: dim, got: N });
739        }
740        let mut out = [0.0 as MjtNum; N];
741        let ptr = unsafe { mj_readSensor(self.model.ffi(), self.ffi(), id as i32, time, out.as_mut_ptr(), interp) };
742        if !ptr.is_null() {
743            // C returned a pointer (no interpolation) - copy into out.
744            out.copy_from_slice(unsafe { std::slice::from_raw_parts(ptr, N) });
745        }
746        Ok(out)
747    }
748
749    /// Reads sensor `id` at `time` (`interp`: -1=stored, 0=ZOH, 1=linear, 2=cubic).
750    ///
751    /// Returns [`Cow::Borrowed`] (zero-copy) for exact matches, ZOH, and extrapolation.
752    /// Returns [`Cow::Owned`] for linear/cubic interpolation.
753    /// See also [`read_sensor_fixed`](Self::read_sensor_fixed), [`read_sensor_into`](Self::read_sensor_into).
754    /// # Panics
755    /// Panics when `id >= nsensor`. Use [`MjData::try_read_sensor`] for a fallible alternative.
756    pub fn read_sensor(&self, id: usize, time: MjtNum, interp: i32) -> Cow<'_, [MjtNum]> {
757        self.try_read_sensor(id, time, interp).unwrap()
758    }
759
760    /// Fallible version of [`MjData::read_sensor`].
761    /// # Errors
762    /// Returns [`MjDataError::IndexOutOfBounds`] when `id >= nsensor`.
763    pub fn try_read_sensor(&self, id: usize, time: MjtNum, interp: i32) -> Result<Cow<'_, [MjtNum]>, MjDataError> {
764        let nsensor = self.model.ffi().nsensor as usize;
765        if id >= nsensor {
766            return Err(MjDataError::IndexOutOfBounds { kind: "sensor_id", id, upper: nsensor });
767        }
768
769        let dim = self.model.sensor_dim()[id] as usize;
770        let mut out = vec![0.0 as MjtNum; dim];
771        let ptr = unsafe { mj_readSensor(self.model.ffi(), self.ffi(), id as i32, time, out.as_mut_ptr(), interp) };
772        if !ptr.is_null() {
773            // C returned a pointer (no interpolation) - borrow it directly.
774            Ok(Cow::Borrowed(unsafe { std::slice::from_raw_parts(ptr, dim) }))
775        } else {
776            // C wrote result into out.
777            Ok(Cow::Owned(out))
778        }
779    }
780
781    /// Adds a contact to the contact list.
782    ///
783    /// This wraps `mj_addContact`, an advanced entry point intended for custom collision routines:
784    /// it copies `con` into the data arena verbatim, without validating it.
785    ///
786    /// # Returns
787    /// `Ok(())` on success.
788    ///
789    /// # Errors
790    /// Returns [`MjDataError::ContactBufferFull`] if the contact buffer is full.
791    ///
792    /// # Safety
793    /// The caller must ensure `con` is a valid contact for the model in this data. MuJoCo later
794    /// indexes several of the stored contact's fields without any bounds check (when building
795    /// constraints and when reading contact forces), so a malformed contact can cause out-of-bounds
796    /// access.
797    pub unsafe fn add_contact(&mut self, con: &MjContact) -> Result<(), MjDataError> {
798        match unsafe { mj_addContact(self.model.ffi(), self.ffi_mut(), con) } {
799            0 => Ok(()),
800            _ => Err(MjDataError::ContactBufferFull),
801        }
802    }
803
804    /// Compute 3/6-by-nv end-effector Jacobian of a global point attached to the given body.
805    /// Set `jacp` to `true` to calculate the translational Jacobian and `jacr` to `true` for
806    /// the rotational Jacobian. Returns a `(Vec, Vec)` for translation and rotation. Empty `Vec`s
807    /// indicate that the corresponding Jacobian was not computed.
808    /// # Panics
809    /// Panics when `body_id >= nbody`. Use [`MjData::try_jac`] for a fallible alternative.
810    pub fn jac(&self, jacp: bool, jacr: bool, point: &[MjtNum; 3], body_id: usize) -> (Vec<MjtNum>, Vec<MjtNum>) {
811        self.try_jac(jacp, jacr, point, body_id).unwrap()
812    }
813
814    /// Fallible version of [`MjData::jac`].
815    /// # Errors
816    /// Returns [`MjDataError::IndexOutOfBounds`] when `body_id` is `>= nbody`.
817    pub fn try_jac(&self, jacp: bool, jacr: bool, point: &[MjtNum; 3], body_id: usize) -> Result<(Vec<MjtNum>, Vec<MjtNum>), MjDataError> {
818        let nbody = self.model.ffi().nbody;
819        if body_id >= nbody as usize {
820            return Err(MjDataError::IndexOutOfBounds { kind: "body_id", id: body_id, upper: nbody as usize });
821        }
822        let required_len = 3 * self.model.ffi().nv as usize;
823        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
824        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
825        unsafe {
826            mj_jac(
827                self.model.ffi(), self.ffi(),
828                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
829                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
830                point, body_id as i32,
831            )
832        };
833        Ok((jacp_vec, jacr_vec))
834    }
835
836    /// Compute body frame end-effector Jacobian.
837    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
838    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
839    /// # Panics
840    /// Panics when `body_id` is out of range. Use [`MjData::try_jac_body`] for a fallible alternative.
841    pub fn jac_body(&self, jacp: bool, jacr: bool, body_id: usize) -> (Vec<MjtNum>, Vec<MjtNum>) {
842        self.try_jac_body(jacp, jacr, body_id).unwrap()
843    }
844
845    /// Fallible version of [`MjData::jac_body`].
846    /// # Errors
847    /// Returns [`MjDataError::IndexOutOfBounds`] when `body_id` is out of range.
848    pub fn try_jac_body(&self, jacp: bool, jacr: bool, body_id: usize) -> Result<(Vec<MjtNum>, Vec<MjtNum>), MjDataError> {
849        let nbody = self.model.ffi().nbody;
850        if body_id >= nbody as usize {
851            return Err(MjDataError::IndexOutOfBounds { kind: "body_id", id: body_id, upper: nbody as usize });
852        }
853        let required_len = 3 * self.model.ffi().nv as usize;
854        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
855        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
856        unsafe {
857            mj_jacBody(
858                self.model.ffi(), self.ffi(),
859                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
860                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
861                body_id as i32,
862            )
863        };
864        Ok((jacp_vec, jacr_vec))
865    }
866
867    /// Compute body center-of-mass end-effector Jacobian.
868    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
869    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
870    /// # Panics
871    /// Panics when `body_id` is out of range. Use [`MjData::try_jac_body_com`] for a fallible alternative.
872    pub fn jac_body_com(&self, jacp: bool, jacr: bool, body_id: usize) -> (Vec<MjtNum>, Vec<MjtNum>) {
873        self.try_jac_body_com(jacp, jacr, body_id).unwrap()
874    }
875
876    /// Fallible version of [`MjData::jac_body_com`].
877    /// # Errors
878    /// Returns [`MjDataError::IndexOutOfBounds`] when `body_id` is out of range.
879    pub fn try_jac_body_com(&self, jacp: bool, jacr: bool, body_id: usize) -> Result<(Vec<MjtNum>, Vec<MjtNum>), MjDataError> {
880        let nbody = self.model.ffi().nbody;
881        if body_id >= nbody as usize {
882            return Err(MjDataError::IndexOutOfBounds { kind: "body_id", id: body_id, upper: nbody as usize });
883        }
884        let required_len = 3 * self.model.ffi().nv as usize;
885        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
886        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
887        unsafe {
888            mj_jacBodyCom(
889                self.model.ffi(), self.ffi(),
890                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
891                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
892                body_id as i32,
893            )
894        };
895        Ok((jacp_vec, jacr_vec))
896    }
897
898    /// Compute subtree center-of-mass end-effector Jacobian (translational only).
899    /// Returns a `Vec` of length `3 * nv` (row-major 3xnv matrix).
900    /// # Panics
901    /// Panics when `body_id` is out of range. Use [`MjData::try_jac_subtree_com`] for a fallible alternative.
902    pub fn jac_subtree_com(&mut self, body_id: usize) -> Vec<MjtNum> {
903        self.try_jac_subtree_com(body_id).unwrap()
904    }
905
906    /// Fallible version of [`MjData::jac_subtree_com`].
907    /// # Errors
908    /// Returns [`MjDataError::IndexOutOfBounds`] when `body_id` is out of range.
909    pub fn try_jac_subtree_com(&mut self, body_id: usize) -> Result<Vec<MjtNum>, MjDataError> {
910        let nbody = self.model.ffi().nbody;
911        if body_id >= nbody as usize {
912            return Err(MjDataError::IndexOutOfBounds { kind: "body_id", id: body_id, upper: nbody as usize });
913        }
914        let required_len = 3 * self.model.ffi().nv as usize;
915        let mut jacp_vec = vec![0 as MjtNum; required_len];
916        unsafe {
917            mj_jacSubtreeCom(
918                self.model.ffi(), self.ffi_mut(),
919                jacp_vec.as_mut_ptr(),
920                body_id as i32,
921            )
922        };
923        Ok(jacp_vec)
924    }
925
926    /// Compute geom end-effector Jacobian.
927    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
928    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
929    /// # Panics
930    /// Panics when `geom_id` is out of range. Use [`MjData::try_jac_geom`] for a fallible alternative.
931    pub fn jac_geom(&self, jacp: bool, jacr: bool, geom_id: usize) -> (Vec<MjtNum>, Vec<MjtNum>) {
932        self.try_jac_geom(jacp, jacr, geom_id).unwrap()
933    }
934
935    /// Fallible version of [`MjData::jac_geom`].
936    /// # Errors
937    /// Returns [`MjDataError::IndexOutOfBounds`] when `geom_id` is out of range.
938    pub fn try_jac_geom(&self, jacp: bool, jacr: bool, geom_id: usize) -> Result<(Vec<MjtNum>, Vec<MjtNum>), MjDataError> {
939        let ngeom = self.model.ffi().ngeom;
940        if geom_id >= ngeom as usize {
941            return Err(MjDataError::IndexOutOfBounds { kind: "geom_id", id: geom_id, upper: ngeom as usize });
942        }
943        let required_len = 3 * self.model.ffi().nv as usize;
944        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
945        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
946        unsafe {
947            mj_jacGeom(
948                self.model.ffi(), self.ffi(),
949                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
950                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
951                geom_id as i32,
952            )
953        };
954        Ok((jacp_vec, jacr_vec))
955    }
956
957    /// Compute site end-effector Jacobian.
958    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
959    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
960    /// # Panics
961    /// Panics when `site_id` is out of range. Use [`MjData::try_jac_site`] for a fallible alternative.
962    pub fn jac_site(&self, jacp: bool, jacr: bool, site_id: usize) -> (Vec<MjtNum>, Vec<MjtNum>) {
963        self.try_jac_site(jacp, jacr, site_id).unwrap()
964    }
965
966    /// Fallible version of [`MjData::jac_site`].
967    /// # Errors
968    /// Returns [`MjDataError::IndexOutOfBounds`] when `site_id` is out of range.
969    pub fn try_jac_site(&self, jacp: bool, jacr: bool, site_id: usize) -> Result<(Vec<MjtNum>, Vec<MjtNum>), MjDataError> {
970        let nsite = self.model.ffi().nsite;
971        if site_id >= nsite as usize {
972            return Err(MjDataError::IndexOutOfBounds { kind: "site_id", id: site_id, upper: nsite as usize });
973        }
974        let required_len = 3 * self.model.ffi().nv as usize;
975        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
976        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
977        unsafe {
978            mj_jacSite(
979                self.model.ffi(), self.ffi(),
980                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
981                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
982                site_id as i32,
983            )
984        };
985        Ok((jacp_vec, jacr_vec))
986    }
987
988    /// Compute subtree angular momentum matrix.
989    /// # Panics
990    /// Panics when `body_id` is out of range. Use [`MjData::try_angmom_mat`] for a fallible alternative.
991    pub fn angmom_mat(&mut self, body_id: usize) -> Vec<MjtNum> {
992        self.try_angmom_mat(body_id).unwrap()
993    }
994
995    /// Fallible version of [`MjData::angmom_mat`].
996    /// # Errors
997    /// Returns [`MjDataError::IndexOutOfBounds`] when `body_id` is out of range.
998    pub fn try_angmom_mat(&mut self, body_id: usize) -> Result<Vec<MjtNum>, MjDataError> {
999        let nbody = self.model.ffi().nbody;
1000        if body_id >= nbody as usize {
1001            return Err(MjDataError::IndexOutOfBounds { kind: "body_id", id: body_id, upper: nbody as usize });
1002        }
1003        let mut mat = vec![0.0; 3 * self.model.ffi().nv as usize];
1004        unsafe { mj_angmomMat(self.model.ffi(), self.ffi_mut(), mat.as_mut_ptr(), body_id as i32) };
1005        Ok(mat)
1006    }
1007
1008    /// Run all kinematics-like computations (kinematics, comPos, camlight, flex, tendon).
1009    pub fn forward_kinematics(&mut self) {
1010        unsafe { mj_fwdKinematics(self.model.ffi(), self.ffi_mut()) }
1011    }
1012
1013    /// Compute object 6D velocity (rot:lin) in object-centered frame, world/local orientation.
1014    /// # Panics
1015    /// Panics when `obj_type` is unsupported or `obj_id` is out of range.
1016    /// Use [`MjData::try_object_velocity`] for a fallible alternative.
1017    pub fn object_velocity(&self, obj_type: MjtObj, obj_id: usize, flg_local: bool) -> [MjtNum; 6] {
1018        self.try_object_velocity(obj_type, obj_id, flg_local).unwrap()
1019    }
1020
1021    /// Fallible version of [`MjData::object_velocity`].
1022    /// # Errors
1023    /// Returns:
1024    /// - [`MjDataError::UnsupportedObjectType`] when `obj_type` is not one of
1025    ///   `mjOBJ_BODY`, `mjOBJ_XBODY`, `mjOBJ_GEOM`, `mjOBJ_SITE`, `mjOBJ_CAMERA`.
1026    /// - [`MjDataError::IndexOutOfBounds`] when `obj_id` is out of range for the given type.
1027    pub fn try_object_velocity(&self, obj_type: MjtObj, obj_id: usize, flg_local: bool) -> Result<[MjtNum; 6], MjDataError> {
1028        let max_id = match obj_type {
1029            MjtObj::mjOBJ_BODY | MjtObj::mjOBJ_XBODY => self.model.ffi().nbody,
1030            MjtObj::mjOBJ_GEOM => self.model.ffi().ngeom,
1031            MjtObj::mjOBJ_SITE => self.model.ffi().nsite,
1032            MjtObj::mjOBJ_CAMERA => self.model.ffi().ncam,
1033            _ => return Err(MjDataError::UnsupportedObjectType(obj_type as i32)),
1034        };
1035        if obj_id >= max_id as usize {
1036            return Err(MjDataError::IndexOutOfBounds { kind: "obj_id", id: obj_id, upper: max_id as usize });
1037        }
1038        let mut result: [MjtNum; 6] = [0.0; 6];
1039        unsafe {
1040            mj_objectVelocity(self.model.ffi(), self.ffi(), obj_type as i32, obj_id as i32, &mut result, flg_local as i32)
1041        };
1042        Ok(result)
1043    }
1044
1045    /// Compute object 6D acceleration (rot:lin) in object-centered frame, world/local orientation.
1046    /// # Panics
1047    /// Panics when `obj_type` is unsupported or `obj_id` is out of range.
1048    /// Use [`MjData::try_object_acceleration`] for a fallible alternative.
1049    pub fn object_acceleration(&self, obj_type: MjtObj, obj_id: usize, flg_local: bool) -> [MjtNum; 6] {
1050        self.try_object_acceleration(obj_type, obj_id, flg_local).unwrap()
1051    }
1052
1053    /// Fallible version of [`MjData::object_acceleration`].
1054    /// # Errors
1055    /// Returns:
1056    /// - [`MjDataError::UnsupportedObjectType`] when `obj_type` is not supported.
1057    /// - [`MjDataError::IndexOutOfBounds`] when `obj_id` is out of range for the given type.
1058    pub fn try_object_acceleration(&self, obj_type: MjtObj, obj_id: usize, flg_local: bool) -> Result<[MjtNum; 6], MjDataError> {
1059        let max_id = match obj_type {
1060            MjtObj::mjOBJ_BODY | MjtObj::mjOBJ_XBODY => self.model.ffi().nbody,
1061            MjtObj::mjOBJ_GEOM => self.model.ffi().ngeom,
1062            MjtObj::mjOBJ_SITE => self.model.ffi().nsite,
1063            MjtObj::mjOBJ_CAMERA => self.model.ffi().ncam,
1064            _ => return Err(MjDataError::UnsupportedObjectType(obj_type as i32)),
1065        };
1066        if obj_id >= max_id as usize {
1067            return Err(MjDataError::IndexOutOfBounds { kind: "obj_id", id: obj_id, upper: max_id as usize });
1068        }
1069        let mut result: [MjtNum; 6] = [0.0; 6];
1070        unsafe {
1071            mj_objectAcceleration(self.model.ffi(), self.ffi(), obj_type as i32, obj_id as i32, &mut result, flg_local as i32)
1072        };
1073        Ok(result)
1074    }
1075
1076    /// Returns smallest signed distance between two geoms and optionally the contact segment.
1077    /// # Panics
1078    /// Panics when either geom id is `>= ngeom`. Use [`MjData::try_geom_distance`] for a fallible alternative.
1079    pub fn geom_distance(&mut self, geom1_id: usize, geom2_id: usize, dist_max: MjtNum, fromto: Option<&mut [MjtNum; 6]>) -> MjtNum {
1080        self.try_geom_distance(geom1_id, geom2_id, dist_max, fromto).unwrap()
1081    }
1082
1083    /// Fallible version of [`MjData::geom_distance`].
1084    /// # Errors
1085    /// Returns [`MjDataError::IndexOutOfBounds`] when either geom id is `>= ngeom`.
1086    pub fn try_geom_distance(&mut self, geom1_id: usize, geom2_id: usize, dist_max: MjtNum, fromto: Option<&mut [MjtNum; 6]>) -> Result<MjtNum, MjDataError> {
1087        let ngeom = self.model.ffi().ngeom;
1088        if geom1_id >= ngeom as usize {
1089            return Err(MjDataError::IndexOutOfBounds { kind: "geom1_id", id: geom1_id, upper: ngeom as usize });
1090        }
1091        if geom2_id >= ngeom as usize {
1092            return Err(MjDataError::IndexOutOfBounds { kind: "geom2_id", id: geom2_id, upper: ngeom as usize });
1093        }
1094        Ok(unsafe {
1095            mj_geomDistance(
1096                self.model.ffi(), self.ffi_mut(),
1097                geom1_id as i32, geom2_id as i32, dist_max,
1098                fromto.map_or(ptr::null_mut(), |x| x),
1099            )
1100        })
1101    }
1102
1103    /// Map from body local to global Cartesian coordinates. Returns (global position, global orientation matrix).
1104    /// `sameframe` takes values from [`MjtSameFrame`]. Wraps `mj_local2Global`.
1105    /// # Panics
1106    /// Panics when `body_id` is out of range. Use [`MjData::try_local_to_global`] for a fallible alternative.
1107    pub fn local_to_global(&mut self, pos: &[MjtNum; 3], quat: &[MjtNum; 4], body_id: usize, sameframe: MjtSameFrame) -> ([MjtNum; 3], [MjtNum; 9]) {
1108        self.try_local_to_global(pos, quat, body_id, sameframe).unwrap()
1109    }
1110
1111    /// Fallible version of [`MjData::local_to_global`].
1112    /// # Errors
1113    /// Returns [`MjDataError::IndexOutOfBounds`] when `body_id` is out of range.
1114    pub fn try_local_to_global(&mut self, pos: &[MjtNum; 3], quat: &[MjtNum; 4], body_id: usize, sameframe: MjtSameFrame) -> Result<([MjtNum; 3], [MjtNum; 9]), MjDataError> {
1115        let nbody = self.model.ffi().nbody;
1116        if body_id >= nbody as usize {
1117            return Err(MjDataError::IndexOutOfBounds { kind: "body_id", id: body_id, upper: nbody as usize });
1118        }
1119        let mut xpos: [MjtNum; 3] = [0.0; 3];
1120        let mut xmat: [MjtNum; 9] = [0.0; 9];
1121        unsafe {
1122            mj_local2Global(self.ffi_mut(), &mut xpos, &mut xmat, pos, quat, body_id as i32, sameframe as MjtByte)
1123        };
1124        Ok((xpos, xmat))
1125    }
1126
1127    /// Intersect multiple rays emanating from a single point.
1128    /// Similar semantics to mj_ray, but `vec` is an array of (nray x 3) directions.
1129    /// If `normals_out` is `Some`, it must be a slice of `nray` elements filled with surface normals. Use `None` to skip normals.
1130    /// # Panics
1131    /// Panics if `normals_out` length does not match `vec.len()`.
1132    /// Use [`MjData::try_multi_ray`] for a fallible alternative.
1133    #[allow(clippy::too_many_arguments)]
1134    pub fn multi_ray(
1135        &mut self, pnt: &[MjtNum; 3], vec: &[[MjtNum; 3]], geomgroup: Option<&[MjtByte; mjNGROUP as usize]>,
1136        flg_static: MjtBool, bodyexclude: Option<usize>, cutoff: MjtNum, normals_out: Option<&mut [[MjtNum; 3]]>
1137    ) -> (Vec<Option<usize>>, Vec<MjtNum>) {
1138        self.try_multi_ray(pnt, vec, geomgroup, flg_static, bodyexclude, cutoff, normals_out).unwrap()
1139    }
1140
1141    /// Fallible version of [`MjData::multi_ray`].
1142    /// # Errors
1143    /// Returns [`MjDataError::LengthMismatch`] if `normals_out` length does not match `vec.len()`.
1144    #[allow(clippy::too_many_arguments)]
1145    pub fn try_multi_ray(
1146        &mut self, pnt: &[MjtNum; 3], vec: &[[MjtNum; 3]], geomgroup: Option<&[MjtByte; mjNGROUP as usize]>,
1147        flg_static: MjtBool, bodyexclude: Option<usize>, cutoff: MjtNum, normals_out: Option<&mut [[MjtNum; 3]]>
1148    ) -> Result<(Vec<Option<usize>>, Vec<MjtNum>), MjDataError> {
1149        let nray = vec.len();
1150        if let Some(buf) = &normals_out
1151            && buf.len() != nray
1152        {
1153            return Err(MjDataError::LengthMismatch { name: "normals_out", expected: nray, got: buf.len() });
1154        }
1155
1156        let mut geom_id_raw = vec![0i32; nray];
1157        let mut distance = vec![0.0; nray];
1158
1159        unsafe { mj_multiRay(
1160            self.model.ffi(), self.ffi_mut(), pnt,
1161            bytemuck::cast_slice::<[MjtNum; 3], MjtNum>(vec).as_ptr(),
1162            geomgroup.map_or(ptr::null(), |x| x.as_ptr()),
1163            flg_static, bodyexclude.map_or(-1i32, |id| id as i32), geom_id_raw.as_mut_ptr(),
1164            distance.as_mut_ptr(),
1165            normals_out.map_or(ptr::null_mut(), |x| bytemuck::cast_slice_mut::<[MjtNum; 3], MjtNum>(x).as_mut_ptr()),
1166            nray as i32, cutoff
1167        ) };
1168
1169        let geom_id = geom_id_raw.into_iter().map(|id| if id == -1 { None } else { Some(id as usize) }).collect();
1170        Ok((geom_id, distance))
1171    }
1172
1173    /// Intersect ray (pnt+x*vec, x>=0) with visible geoms, except geoms in bodyexclude.
1174    /// Returns `(geomid, distance)` where distance is -1 if no intersection.
1175    /// If `normal_out` is `Some`, it will be filled with the surface normal at the intersection.
1176    /// `geomgroup` and `flg_static` are as in mjvOption; pass `None` for `geomgroup` to skip group exclusion.
1177    pub fn ray(
1178        &mut self, pnt: &[MjtNum; 3], vec: &[MjtNum; 3],
1179        geomgroup: Option<&[MjtByte; mjNGROUP as usize]>, flg_static: MjtBool, bodyexclude: Option<usize>,
1180        normal_out: Option<&mut [MjtNum; 3]>
1181    ) -> (Option<usize>, MjtNum) {
1182        // `normal_out` is a fixed-size array; nothing to validate at runtime here.
1183        let mut geom_id_raw = -1i32;
1184        let dist = unsafe { mj_ray(
1185            self.model.ffi(), self.ffi(),
1186            pnt, vec,
1187            geomgroup.map_or(ptr::null(), |x| x.as_ptr()),
1188            flg_static, bodyexclude.map_or(-1i32, |id| id as i32), &mut geom_id_raw,
1189            normal_out.map_or(ptr::null_mut(), |x| x)
1190        ) };
1191        let geom_id = if geom_id_raw == -1 { None } else { Some(geom_id_raw as usize) };
1192        (geom_id, dist)
1193    }
1194
1195    /// Intersect ray with visible flexes.
1196    /// Return distance to nearest surface, or -1 if no intersection.
1197    /// If `vertid` is `Some`, it will be filled with the id of the nearest vertex.
1198    /// If `normal_out` is `Some`, it will be filled with the surface normal at the intersection.
1199    /// `flex_layer`, `flg_vert`, `flg_edge`, `flg_face`, `flg_skin` and `flexid` control what and where to intersect.
1200    ///
1201    /// # Panics
1202    /// Panics if `flexid` is out of bounds (must be `0 <= flexid < nflex`).
1203    ///
1204    /// Use [`MjData::try_ray_flex`] for a fallible alternative.
1205    #[allow(clippy::too_many_arguments)]
1206    pub fn ray_flex(
1207        &self, flex_layer: i32, flg_vert: MjtBool, flg_edge: MjtBool, flg_face: MjtBool, flg_skin: MjtBool, flexid: usize,
1208        pnt: &[MjtNum; 3], vec: &[MjtNum; 3],
1209        vertid: Option<&mut i32>, normal_out: Option<&mut [MjtNum; 3]>
1210    ) -> MjtNum {
1211        self.try_ray_flex(flex_layer, flg_vert, flg_edge, flg_face, flg_skin, flexid, pnt, vec, vertid, normal_out).unwrap()
1212    }
1213
1214    /// Intersect ray with flex, returning the distance or -1.0 if no intersection.
1215    ///
1216    /// # Errors
1217    /// Returns [`MjDataError::IndexOutOfBounds`] if `flexid >= nflex`.
1218    ///
1219    /// Use [`MjData::ray_flex`] for a panicking alternative.
1220    #[allow(clippy::too_many_arguments)]
1221    pub fn try_ray_flex(
1222        &self, flex_layer: i32, flg_vert: MjtBool, flg_edge: MjtBool, flg_face: MjtBool, flg_skin: MjtBool, flexid: usize,
1223        pnt: &[MjtNum; 3], vec: &[MjtNum; 3],
1224        vertid: Option<&mut i32>, normal_out: Option<&mut [MjtNum; 3]>
1225    ) -> Result<MjtNum, MjDataError> {
1226        let nflex = self.model.ffi().nflex as usize;
1227        if flexid >= nflex {
1228            return Err(MjDataError::IndexOutOfBounds { kind: "flexid", id: flexid, upper: nflex });
1229        }
1230        Ok(unsafe { mj_rayFlex(
1231            self.model.ffi(), self.ffi(),
1232            flex_layer, flg_vert, flg_edge, flg_face, flg_skin, flexid as i32,
1233            pnt, vec,
1234            vertid.map_or(ptr::null_mut(), |x| x), normal_out.map_or(ptr::null_mut(), |x| x)
1235        ) })
1236    }
1237
1238    /// Copies data state from `src` to `self` based on the specified `spec` combination of `mjtState` flags.
1239    ///
1240    /// # Errors
1241    /// Returns [`MjDataError::SignatureMismatch`] if `src` was created from
1242    /// a different model.
1243    pub fn copy_state_from_data<N: Deref<Target = MjModel>>(&mut self, src: &MjData<N>, spec: u32) -> Result<(), MjDataError> {
1244        let src_sig = src.model.signature();
1245        let dst_sig = self.model.signature();
1246        if src_sig != dst_sig {
1247            return Err(MjDataError::SignatureMismatch {
1248                source: src_sig,
1249                destination: dst_sig,
1250            });
1251        }
1252        unsafe {
1253            mj_copyState(self.model.ffi(), src.ffi(), self.ffi_mut(), spec as i32);
1254        }
1255        Ok(())
1256    }
1257
1258    /// Intersect ray with hfield.
1259    /// Returns the distance to the intersection, or -1.0 if no intersection.
1260    ///
1261    /// # Panics
1262    /// Panics if `geom_id` is out of bounds (must be `0 <= geom_id < ngeom`).
1263    ///
1264    /// Use [`MjData::try_ray_hfield`] for a fallible alternative.
1265    pub fn ray_hfield(
1266        &self, geom_id: usize, pnt: &[MjtNum; 3], vec: &[MjtNum; 3], normal_out: Option<&mut [MjtNum; 3]>
1267    ) -> MjtNum {
1268        self.try_ray_hfield(geom_id, pnt, vec, normal_out).unwrap()
1269    }
1270
1271    /// Intersect ray with hfield, returning the distance or -1.0 if no intersection.
1272    ///
1273    /// # Errors
1274    /// Returns [`MjDataError::IndexOutOfBounds`] if `geom_id >= ngeom`.
1275    ///
1276    /// Use [`MjData::ray_hfield`] for a panicking alternative.
1277    pub fn try_ray_hfield(
1278        &self, geom_id: usize, pnt: &[MjtNum; 3], vec: &[MjtNum; 3], normal_out: Option<&mut [MjtNum; 3]>
1279    ) -> Result<MjtNum, MjDataError> {
1280        let ngeom = self.model.ffi().ngeom as usize;
1281        if geom_id >= ngeom {
1282            return Err(MjDataError::IndexOutOfBounds { kind: "geom_id", id: geom_id, upper: ngeom });
1283        }
1284        Ok(unsafe {
1285            mj_rayHfield(self.model.ffi(), self.ffi(), geom_id as i32, pnt, vec, normal_out.map_or(ptr::null_mut(), |x| x))
1286        })
1287    }
1288
1289    /// Intersect ray with mesh.
1290    /// Returns the distance to the intersection, or -1.0 if no intersection.
1291    ///
1292    /// # Panics
1293    /// Panics if `geom_id` is out of bounds (must be `0 <= geom_id < ngeom`).
1294    ///
1295    /// Use [`MjData::try_ray_mesh`] for a fallible alternative.
1296    pub fn ray_mesh(
1297        &mut self, geom_id: usize, pnt: &[MjtNum; 3], vec: &[MjtNum; 3], normal_out: Option<&mut [MjtNum; 3]>
1298    ) -> MjtNum {
1299        self.try_ray_mesh(geom_id, pnt, vec, normal_out).unwrap()
1300    }
1301
1302    /// Intersect ray with mesh, returning the distance or -1.0 if no intersection.
1303    ///
1304    /// # Errors
1305    /// Returns [`MjDataError::IndexOutOfBounds`] if `geom_id >= ngeom`.
1306    ///
1307    /// Use [`MjData::ray_mesh`] for a panicking alternative.
1308    pub fn try_ray_mesh(
1309        &mut self, geom_id: usize, pnt: &[MjtNum; 3], vec: &[MjtNum; 3], normal_out: Option<&mut [MjtNum; 3]>
1310    ) -> Result<MjtNum, MjDataError> {
1311        let ngeom = self.model.ffi().ngeom as usize;
1312        if geom_id >= ngeom {
1313            return Err(MjDataError::IndexOutOfBounds { kind: "geom_id", id: geom_id, upper: ngeom });
1314        }
1315        Ok(unsafe {
1316            mj_rayMesh(self.model.ffi(), self.ffi(), geom_id as i32, pnt, vec, normal_out.map_or(ptr::null_mut(), |x| x))
1317        })
1318    }
1319
1320    /// Apply Cartesian force and torque to a point on a body, and add the result to `qfrc_target`.
1321    ///
1322    /// # Errors
1323    /// Returns [`MjDataError::IndexOutOfBounds`] if `body` is not a valid body
1324    /// index, or [`MjDataError::BufferTooSmall`] if `qfrc_target` is shorter
1325    /// than `nv`.
1326    pub fn apply_ft(
1327        &mut self,
1328        force: &[MjtNum; 3],
1329        torque: &[MjtNum; 3],
1330        point: &[MjtNum; 3],
1331        body: usize,
1332        qfrc_target: &mut [MjtNum],
1333    ) -> Result<(), MjDataError> {
1334        let nbody = self.model.ffi().nbody;
1335        if body >= nbody as usize {
1336            return Err(MjDataError::IndexOutOfBounds {
1337                kind: "body",
1338                id: body,
1339                upper: nbody as usize,
1340            });
1341        }
1342        let nv = self.model.ffi().nv as usize;
1343        if qfrc_target.len() < nv {
1344            return Err(MjDataError::BufferTooSmall {
1345                name: "qfrc_target",
1346                got: qfrc_target.len(),
1347                needed: nv,
1348            });
1349        }
1350        unsafe {
1351            mj_applyFT(self.model.ffi(), self.ffi_mut(), force, torque, point, body as i32, qfrc_target.as_mut_ptr());
1352        }
1353        Ok(())
1354    }
1355
1356    /// Reads data's state into `destination`. The `spec` parameter is a bit mask of [`MjtState`] elements,
1357    /// which controls what state gets copied. The `destination` parameter is a mutable
1358    /// slice to the location into which the state will be written.
1359    /// This is a wrapper around [`mj_getState`].
1360    ///
1361    /// # Note
1362    /// The `destination` buffer is allowed to be larger than the
1363    /// actual state length, and may thus contain old information.
1364    /// Only the first `state_size` elements of `destination` are updated by this function;
1365    /// any remaining elements in the buffer are left unchanged. This was done for possible
1366    /// performance improvements, where one array may hold different parts of simulation state
1367    /// at different times.
1368    ///
1369    /// You can use the returned number of [`MjtNum`] elements written to `destination`
1370    /// to create a subslice containing only the updated information.
1371    ///
1372    /// # Returns
1373    /// Number of [`MjtNum`] elements written to `destination`.
1374    ///
1375    /// # Panics
1376    /// A panic will occur if `destination` is smaller than [`MjModel::state_size`] with `spec` passed as parameter.
1377    /// Use [`MjData::try_read_state_into`] for a fallible alternative.
1378    pub fn read_state_into(&self, spec: u32, destination: &mut [MjtNum]) -> usize {
1379        self.try_read_state_into(spec, destination)
1380            .unwrap()
1381    }
1382
1383    /// Fallible version of [`MjData::read_state_into`].
1384    ///
1385    /// # Errors
1386    /// Returns [`MjDataError::BufferTooSmall`] if `destination` is smaller than
1387    /// the state size required by `spec`.
1388    ///
1389    /// On success, returns the number of [`MjtNum`] elements written.
1390    pub fn try_read_state_into(&self, spec: u32, destination: &mut [MjtNum]) -> Result<usize, MjDataError> {
1391        let state_size = self.model.state_size(spec);
1392        if destination.len() < state_size {
1393            return Err(MjDataError::BufferTooSmall {
1394                name: "destination",
1395                got: destination.len(),
1396                needed: state_size,
1397            });
1398        }
1399        unsafe {
1400            mj_getState(self.model.ffi(), self.ffi(), destination.as_mut_ptr(), spec as i32);
1401        }
1402        Ok(state_size)
1403    }
1404
1405    /// Same as [`MjData::read_state_into`], except it allocates
1406    /// and returns new boxed data containing the state.
1407    pub fn state(&self, spec: u32) -> Box<[MjtNum]> {
1408        let mut destination = vec![0.0; self.model.state_size(spec)].into_boxed_slice();
1409        Self::read_state_into(self, spec, &mut destination);
1410        destination
1411    }
1412
1413    /// Same as [`MjData::read_state_into`], except it allocates
1414    /// and returns new boxed data containing the state.
1415    #[deprecated(since = "3.0.0", note = "use `state` instead")]
1416    pub fn get_state(&self, spec: u32) -> Box<[MjtNum]> {
1417        self.state(spec)
1418    }
1419
1420    /// Sets the `state` to [`MjData`]. This is a wrapper around [`mj_setState`].
1421    /// The `state` is an array containing the state to write, based on the `spec`
1422    /// bitmask of elements [`MjtState`].
1423    ///
1424    /// # Note
1425    /// The size of `state` is allowed to be larger. This was done to allow a preallocated
1426    /// buffer to store any possible state based on `spec`, without having to query the size
1427    /// every time. This benefits performance in some cases.
1428    ///
1429    /// # Errors
1430    /// Returns [`MjDataError::BufferTooSmall`] if `state` is smaller than the
1431    /// length required by `spec`.
1432    pub fn set_state(&mut self, state: &[MjtNum], spec: u32) -> Result<(), MjDataError> {
1433        let required_len = self.model.state_size(spec);
1434        if state.len() < required_len {
1435            return Err(MjDataError::BufferTooSmall {
1436                name: "state",
1437                got: state.len(),
1438                needed: required_len,
1439            });
1440        }
1441        unsafe {
1442            mj_setState(self.model.ffi(), self.ffi_mut(), state.as_ptr(), spec as i32);
1443        }
1444        Ok(())
1445    }
1446
1447
1448    /// Copy [`MjData`] to `destination`, skipping large computed arrays not required for
1449    /// visualization: mass matrices and constraint arrays (`efc_*`, `iefc_*`, including
1450    /// constraint Jacobians).
1451    /// This is a wrapper for [`mjv_copyData`].
1452    ///
1453    /// # Errors
1454    /// Returns [`MjDataError::SignatureMismatch`] if `destination` was created
1455    /// from a different model.
1456    pub fn copy_visual_to<N: Deref<Target = MjModel>>(&self, destination: &mut MjData<N>) -> Result<(), MjDataError> {
1457        let src_sig = self.model.signature();
1458        let dst_sig = destination.model.signature();
1459        if src_sig != dst_sig {
1460            return Err(MjDataError::SignatureMismatch {
1461                source: src_sig,
1462                destination: dst_sig,
1463            });
1464        }
1465        unsafe {
1466            mjv_copyData(destination.ffi_mut(), self.model.ffi(), self.ffi());
1467        }
1468        Ok(())
1469    }
1470
1471    /// Copy [`MjData`] to `destination` in full.
1472    /// This is a wrapper for [`mj_copyData`].
1473    ///
1474    /// # Errors
1475    /// Returns [`MjDataError::SignatureMismatch`] if `destination` was created
1476    /// from a different model.
1477    pub fn copy_to<N: Deref<Target = MjModel>>(&self, destination: &mut MjData<N>) -> Result<(), MjDataError> {
1478        let src_sig = self.model.signature();
1479        let dst_sig = destination.model.signature();
1480        if src_sig != dst_sig {
1481            return Err(MjDataError::SignatureMismatch {
1482                source: src_sig,
1483                destination: dst_sig,
1484            });
1485        }
1486        unsafe {
1487            mj_copyData(destination.ffi_mut(), self.model.ffi(), self.ffi());
1488        }
1489        Ok(())
1490    }
1491
1492    /// Returns a direct mutable pointer to the underlying C data struct.
1493    /// Only for internal use by viewer code that passes the pointer to C++ FFI.
1494    #[cfg(feature = "cpp-viewer")]
1495    pub(crate) fn as_raw_ptr(&self) -> *mut mjData {
1496        self.data.as_ptr()
1497    }
1498}
1499
1500
1501/// Some public attribute methods.
1502impl<M: Deref<Target = MjModel>> MjData<M> {
1503    /// Reference to the wrapped FFI struct.
1504    pub fn ffi(&self) -> &mjData {
1505        // SAFETY: self.data is a valid non-null mjData pointer for the lifetime of self
1506        // (struct invariant).
1507        unsafe { self.data.as_ref() }
1508    }
1509
1510    /// Mutable reference to the wrapped FFI struct.
1511    ///
1512    /// # Safety
1513    /// Modifying the underlying FFI struct directly can break the invariants
1514    /// upheld by the `mujoco-rs` wrappers and cause undefined behavior.
1515    pub unsafe fn ffi_mut(&mut self) -> &mut mjData {
1516        unsafe { self.data.as_mut() }
1517    }
1518
1519    /// Returns a reference to data's [`MjModel`].
1520    ///
1521    /// See also [`model_mut`](MjData::model_mut) for mutable access
1522    /// (requires `M: DerefMut<Target = MjModel>`).
1523    pub fn model(&self) -> &MjModel {
1524        &self.model
1525    }
1526
1527    /// Returns an immutable reference to the model physics options.
1528    pub fn model_opt(&self) -> &MjOption {
1529        self.model.opt()
1530    }
1531
1532    /// Returns an immutable reference to the model visualization options.
1533    pub fn model_vis(&self) -> &MjVisual {
1534        self.model.vis()
1535    }
1536
1537    /// Returns an immutable reference to the model statistics.
1538    pub fn model_stat(&self) -> &MjStatistic {
1539        self.model.stat()
1540    }
1541
1542    /// Returns a clone of the stored model.
1543    /// Unlike [`model`](Self::model), this returns
1544    /// the inferred `M` type (cloned).
1545    pub fn model_clone(&self) -> M where M: Clone {
1546        self.model.clone()
1547    }
1548
1549    getter_setter! {get, [
1550        [ffi] narena: MjtSize; "size of the arena in bytes (inclusive of the stack).";
1551        [ffi] nbuffer: MjtSize; "size of main buffer in bytes.";
1552        [ffi] nplugin: i32; "number of plugin instances.";
1553        [ffi] maxuse_stack: MjtSize; "maximum stack allocation in bytes (mutable).";
1554        [ffi] maxuse_arena: MjtSize; "maximum arena allocation in bytes.";
1555        [ffi] maxuse_con: i32; "maximum number of contacts.";
1556        [ffi] maxuse_efc: i32; "maximum number of scalar constraints.";
1557        [ffi] ncon: i32; "number of detected contacts.";
1558        [ffi] ne: i32; "number of equality constraints.";
1559        [ffi] nf: i32; "number of friction constraints.";
1560        [ffi] nl: i32; "number of limit constraints.";
1561        [ffi] nefc: i32; "number of constraints.";
1562        [ffi] nJ: i32; "number of non-zeros in constraint Jacobian.";
1563        [ffi] nY: i32; "number of non-zeros in constraint inverse inertia square root.";
1564        [ffi] nA: i32; "number of non-zeros in constraint inverse inertia matrix.";
1565        [ffi] nisland: i32; "number of detected constraint islands.";
1566        [ffi] nidof: i32; "number of dofs in all islands.";
1567        [ffi] ntree_awake: i32; "number of awake trees.";
1568        [ffi] nbody_awake: i32; "number of awake dynamic and static bodies.";
1569        [ffi] nparent_awake: i32; "number of bodies with awake parents.";
1570        [ffi] nv_awake: i32; "number of awake dofs.";
1571        [ffi] signature: u64; "compilation signature.";
1572    ]}
1573
1574    getter_setter! {get, [
1575        [ffi] flg_energypos: MjtBool; "has mj_energyPos been called.";
1576        [ffi] flg_energyvel: MjtBool; "has mj_energyVel been called.";
1577        [ffi] flg_subtreevel: MjtBool; "has mj_subtreeVel been called.";
1578        [ffi] flg_rnepost: MjtBool; "has mj_rnePostConstraint been called.";
1579    ]}
1580
1581    getter_setter! {with, get, set, [[ffi, ffi_mut] time: MjtNum; "simulation time.";]}
1582
1583    getter_setter! {with, get, [
1584        [ffi, ffi_mut] energy: &[MjtNum; 2]; "potential, kinetic energy.";
1585    ]}
1586
1587    getter_setter! {
1588        get, [
1589            [ffi] (allow_mut = false) maxuse_threadstack: &[MjtSize; mjMAXTHREAD as usize]; "maximum stack allocation per thread in bytes.";
1590            [ffi, ffi_mut] solver: &[MjSolverStat; mjNISLAND as usize * mjNSOLVER as usize]; "solver statistics per island, per iteration.";
1591            [ffi, ffi_mut] solver_niter: &[i32; mjNISLAND as usize]; "number of solver iterations, per island.";
1592            [ffi, ffi_mut] solver_nnz: &[i32; mjNISLAND as usize]; "number of nonzeros in Hessian or efc_AR, per island.";
1593            [ffi, ffi_mut] solver_fwdinv: &[MjtNum; 2]; "forward-inverse comparison: qfrc, efc.";
1594            [ffi, ffi_mut] warning: &[MjWarningStat; MjtWarning::mjNWARNING as usize]; "warning statistics (mutable).";
1595            [ffi, ffi_mut] timer: &[MjTimerStat; MjtTimer::mjNTIMER as usize]; "timer statistics.";
1596        ]
1597    }
1598}
1599
1600impl<M: DerefMut<Target = MjModel>> MjData<M> {
1601    /// Returns a mutable reference to data's [`MjModel`].
1602    ///
1603    /// This is useful for modifying the physics parameters of the model
1604    /// (e.g., timestep, gravity) without having to rebuild the simulation.
1605    ///
1606    /// **Not all model parameters are safe to change at runtime.**
1607    /// See [MuJoCo's documentation](https://mujoco.readthedocs.io/en/3.9.0/programming/simulation.html#mjmodel-changes)
1608    /// for a list of parameters that are safe to change.
1609    ///
1610    /// Only available when the inner model type `M` implements
1611    /// [`DerefMut<Target = MjModel>`](std::ops::DerefMut)
1612    /// (e.g., `Box<MjModel>`, `&mut MjModel`).
1613    /// Shared-ownership types such as `Arc<MjModel>` do not provide mutable
1614    /// access; use [`swap_model`](MjData::swap_model) instead.
1615    /// 
1616    /// # Safety
1617    /// This method is marked unsafe as the owned model can be swapped entirely without any compatibility
1618    /// checks.
1619    /// 
1620    /// It is the caller's responsibility to ensure the internal [`MjModel::signature`] matches the
1621    /// swapped model's signature in case of a swap.
1622    /// 
1623    /// For safe swapping consider [`MjData::swap_model`] or [`MjData::try_swap_model`] for a fallible alternative.
1624    ///
1625    /// # Example
1626    /// ```rust
1627    /// # use mujoco_rs::prelude::{MjModel, MjData};
1628    /// let model = Box::new(MjModel::from_xml_string("<mujoco/>").unwrap());
1629    /// let mut data = MjData::new(model);
1630    /// unsafe { data.model_mut() }.opt_mut().timestep = 0.001;
1631    /// unsafe { data.model_mut() }.opt_mut().gravity[2] = -5.0;
1632    /// ```
1633    pub unsafe fn model_mut(&mut self) -> &mut MjModel {
1634        &mut self.model
1635    }
1636
1637    /// Returns a mutable reference to [`MjModel::opt_mut`] without allowing unsafe
1638    /// modifications to the rest of the [`MjModel`].
1639    /// 
1640    /// Immutable references can be made through [`MjData::model_opt`].
1641    /// 
1642    /// Can be used to modify the physics parameters.
1643    /// # Example
1644    /// ```rust
1645    /// # use mujoco_rs::prelude::{MjModel, MjData};
1646    /// let model = Box::new(MjModel::from_xml_string("<mujoco/>").unwrap());
1647    /// let mut data = MjData::new(model);
1648    /// data.model_opt_mut().timestep = 0.001;
1649    /// data.model_opt_mut().gravity[2] = -5.0;
1650    /// ```
1651    pub fn model_opt_mut(&mut self) -> &mut MjOption {
1652        self.model.opt_mut()
1653    }
1654
1655    /// Returns a mutable reference to [`MjModel::vis_mut`] without allowing unsafe
1656    /// modifications to the rest of the [`MjModel`].
1657    /// 
1658    /// Immutable references can be made through [`MjData::model_vis`].
1659    /// 
1660    /// Can be used to modify the visualization parameters.
1661    /// # Example
1662    /// ```rust
1663    /// # use mujoco_rs::prelude::{MjModel, MjData};
1664    /// let model = Box::new(MjModel::from_xml_string("<mujoco/>").unwrap());
1665    /// let mut data = MjData::new(model);
1666    /// data.model_vis_mut().headlight.ambient = [0.0, 0.0, 0.0];
1667    /// data.model_vis_mut().headlight.active = 1;
1668    /// ```
1669    pub fn model_vis_mut(&mut self) -> &mut MjVisual {
1670        self.model.vis_mut()
1671    }
1672
1673    /// Returns a mutable reference to [`MjModel::stat_mut`] without allowing unsafe
1674    /// modifications to the rest of the [`MjModel`].
1675    /// 
1676    /// Immutable references can be made through [`MjData::model_stat`].
1677    /// 
1678    /// Can be used to modify the model statistics.
1679    /// # Example
1680    /// ```rust
1681    /// # use mujoco_rs::prelude::{MjModel, MjData};
1682    /// let model = Box::new(MjModel::from_xml_string("<mujoco/>").unwrap());
1683    /// let mut data = MjData::new(model);
1684    /// data.model_stat_mut().center = [0.0, 0.0, 0.5];
1685    /// ```
1686    pub fn model_stat_mut(&mut self) -> &mut MjStatistic {
1687        self.model.stat_mut()
1688    }
1689}
1690
1691/// Arrays of dynamic size.
1692impl<M: Deref<Target = MjModel>> MjData<M> {
1693    array_slice_dyn! {
1694        qpos: &[MjtNum; "position"; model.ffi().nq],
1695        qvel: &[MjtNum; "velocity"; model.ffi().nv],
1696        act: &[MjtNum; "actuator activation"; model.ffi().na],
1697        (mut = unsafe) history: &[MjtNum; "history buffer"; model.ffi().nhistory],
1698        qacc_warmstart: &[MjtNum; "acceleration used for warmstart"; model.ffi().nv],
1699        plugin_state: &[MjtNum; "plugin state"; model.ffi().npluginstate],
1700        ctrl: &[MjtNum; "control"; model.ffi().nu],
1701        qfrc_applied: &[MjtNum; "applied generalized force"; model.ffi().nv],
1702        xfrc_applied: &[[MjtNum; 6] [force]; "applied Cartesian force/torque"; model.ffi().nbody],
1703        eq_active: &[MjtBool; "enable/disable constraints"; model.ffi().neq],
1704        mocap_pos: &[[MjtNum; 3] [force]; "positions of mocap bodies"; model.ffi().nmocap],
1705        mocap_quat: &[[MjtNum; 4] [force]; "orientations of mocap bodies"; model.ffi().nmocap],
1706        qacc: &[MjtNum; "acceleration"; model.ffi().nv],
1707        act_dot: &[MjtNum; "time-derivative of actuator activation"; model.ffi().na],
1708        userdata: &[MjtNum; "user data, not touched by engine"; model.ffi().nuserdata],
1709        sensordata: &[MjtNum; "sensor data array"; model.ffi().nsensordata],
1710        (mut = unsafe) tree_asleep: &[i32; "<0: awake; >=0: index cycle of sleeping trees"; model.ffi().ntree],
1711        xpos: &[[MjtNum; 3] [force]; "Cartesian position of body frame"; model.ffi().nbody],
1712        xquat: &[[MjtNum; 4] [force]; "Cartesian orientation of body frame"; model.ffi().nbody],
1713        xmat: &[[MjtNum; 9] [force]; "Cartesian orientation of body frame"; model.ffi().nbody],
1714        xipos: &[[MjtNum; 3] [force]; "Cartesian position of body com"; model.ffi().nbody],
1715        ximat: &[[MjtNum; 9] [force]; "Cartesian orientation of body inertia"; model.ffi().nbody],
1716        xanchor: &[[MjtNum; 3] [force]; "Cartesian position of joint anchor"; model.ffi().njnt],
1717        xaxis: &[[MjtNum; 3] [force]; "Cartesian joint axis"; model.ffi().njnt],
1718        geom_xpos: &[[MjtNum; 3] [force]; "Cartesian geom position"; model.ffi().ngeom],
1719        geom_xmat: &[[MjtNum; 9] [force]; "Cartesian geom orientation"; model.ffi().ngeom],
1720        site_xpos: &[[MjtNum; 3] [force]; "Cartesian site position"; model.ffi().nsite],
1721        site_xmat: &[[MjtNum; 9] [force]; "Cartesian site orientation"; model.ffi().nsite],
1722        cam_xpos: &[[MjtNum; 3] [force]; "Cartesian camera position"; model.ffi().ncam],
1723        cam_xmat: &[[MjtNum; 9] [force]; "Cartesian camera orientation"; model.ffi().ncam],
1724        light_xpos: &[[MjtNum; 3] [force]; "Cartesian light position"; model.ffi().nlight],
1725        light_xdir: &[[MjtNum; 3] [force]; "Cartesian light direction"; model.ffi().nlight],
1726        subtree_com: &[[MjtNum; 3] [force]; "center of mass of each subtree"; model.ffi().nbody],
1727        cdof: &[[MjtNum; 6] [force]; "com-based motion axis of each dof (rot:lin)"; model.ffi().nv],
1728        cinert: &[[MjtNum; 10] [force]; "com-based body inertia and mass"; model.ffi().nbody],
1729        flexvert_xpos: &[[MjtNum; 3] [force]; "Cartesian flex vertex positions"; model.ffi().nflexvert],
1730        flexelem_aabb: &[[MjtNum; 6] [force]; "flex element bounding boxes (center, size)"; model.ffi().nflexelem],
1731        flexedge_J: &[MjtNum; "flex edge Jacobian"; model.ffi().nJfe],
1732        flexedge_length: &[MjtNum; "flex edge lengths"; model.ffi().nflexedge],
1733        flexvert_J: &[[MjtNum; 2] [force]; "flex vertex Jacobian"; model.ffi().nJfv],
1734        flexvert_length: &[[MjtNum; 2] [force]; "flex vertex lengths"; model.ffi().nflexvert],
1735        bvh_aabb_dyn: &[[MjtNum; 6] [force]; "global bounding box (center, size)"; model.ffi().nbvhdynamic],
1736        (mut = unsafe) ten_wrapadr: &[i32; "start address of tendon's path"; model.ffi().ntendon],
1737        (mut = unsafe) ten_wrapnum: &[i32; "number of wrap points in path"; model.ffi().ntendon],
1738        ten_J: &[MjtNum; "tendon Jacobian"; model.ffi().nJten],
1739        ten_length: &[MjtNum; "tendon lengths"; model.ffi().ntendon],
1740        (mut = unsafe) wrap_obj: &[[i32; 2] [force]; "geom id; -1: site; -2: pulley"; model.ffi().nwrap],
1741        wrap_xpos: &[[MjtNum; 6] [force]; "Cartesian 3D points in all paths"; model.ffi().nwrap],
1742        actuator_length: &[MjtNum; "actuator lengths"; model.ffi().nu],
1743        (mut = unsafe) moment_rownnz: &[i32; "number of non-zeros in actuator_moment row"; model.ffi().nu],
1744        (mut = unsafe) moment_rowadr: &[i32; "row start address in colind array"; model.ffi().nu],
1745        (mut = unsafe) moment_colind: &[i32; "column indices in sparse Jacobian"; model.ffi().nJmom],
1746        actuator_moment: &[MjtNum; "actuator moments"; model.ffi().nJmom],
1747        crb: &[[MjtNum; 10] [force]; "com-based composite inertia and mass"; model.ffi().nbody],
1748        qM: &[MjtNum; "inertia (sparse)"; model.ffi().nM],
1749        M: &[MjtNum; "reduced inertia (compressed sparse row)"; model.ffi().nC],
1750        qLD: &[MjtNum; "L'*D*L factorization of M (sparse)"; model.ffi().nC],
1751        qLDiagInv: &[MjtNum; "1/diag(D)"; model.ffi().nv],
1752        bvh_active: &[MjtBool; "was bounding volume checked for collision"; model.ffi().nbvh],
1753        tree_awake: &[i32; "is tree awake; 0: asleep; 1: awake"; model.ffi().ntree],
1754        body_awake: &[MjtSleepState [force]; "body sleep state"; model.ffi().nbody],
1755        (mut = unsafe) body_awake_ind: &[i32; "indices of awake and static bodies"; model.ffi().nbody],
1756        (mut = unsafe) parent_awake_ind: &[i32; "indices of bodies with awake or static parents"; model.ffi().nbody],
1757        (mut = unsafe) dof_awake_ind: &[i32; "indices of awake dofs"; model.ffi().nv],
1758        flexedge_velocity: &[MjtNum; "flex edge velocities"; model.ffi().nflexedge],
1759        ten_velocity: &[MjtNum; "tendon velocities"; model.ffi().ntendon],
1760        actuator_velocity: &[MjtNum; "actuator velocities"; model.ffi().nu],
1761        cvel: &[[MjtNum; 6] [force]; "com-based velocity (rot:lin)"; model.ffi().nbody],
1762        cdof_dot: &[[MjtNum; 6] [force]; "time-derivative of cdof (rot:lin)"; model.ffi().nv],
1763        qfrc_bias: &[MjtNum; "C(qpos,qvel)"; model.ffi().nv],
1764        qfrc_spring: &[MjtNum; "passive spring force"; model.ffi().nv],
1765        qfrc_damper: &[MjtNum; "passive damper force"; model.ffi().nv],
1766        qfrc_gravcomp: &[MjtNum; "passive gravity compensation force"; model.ffi().nv],
1767        qfrc_fluid: &[MjtNum; "passive fluid force"; model.ffi().nv],
1768        qfrc_passive: &[MjtNum; "total passive force"; model.ffi().nv],
1769        subtree_linvel: &[[MjtNum; 3] [force]; "linear velocity of subtree com"; model.ffi().nbody],
1770        subtree_angmom: &[[MjtNum; 3] [force]; "angular momentum about subtree com"; model.ffi().nbody],
1771        qH: &[MjtNum; "L'*D*L factorization of modified M"; model.ffi().nC],
1772        qHDiagInv: &[MjtNum; "1/diag(D) of modified M"; model.ffi().nv],
1773        qDeriv: &[MjtNum; "d (passive + actuator - bias) / d qvel"; model.ffi().nD],
1774        qLU: &[MjtNum; "sparse LU of (qM - dt*qDeriv)"; model.ffi().nD],
1775        actuator_force: &[MjtNum; "actuator force in actuation space"; model.ffi().nu],
1776        qfrc_actuator: &[MjtNum; "actuator force"; model.ffi().nv],
1777        qfrc_smooth: &[MjtNum; "net unconstrained force"; model.ffi().nv],
1778        qacc_smooth: &[MjtNum; "unconstrained acceleration"; model.ffi().nv],
1779        qfrc_constraint: &[MjtNum; "constraint force"; model.ffi().nv],
1780        qfrc_inverse: &[MjtNum; "net external force; should equal qfrc_applied + J'*xfrc_applied + qfrc_actuator"; model.ffi().nv],
1781        cacc: &[[MjtNum; 6] [force]; "com-based acceleration"; model.ffi().nbody],
1782        cfrc_int: &[[MjtNum; 6] [force]; "com-based interaction force with parent"; model.ffi().nbody],
1783        cfrc_ext: &[[MjtNum; 6] [force]; "com-based external force on body"; model.ffi().nbody],
1784        (mut = unsafe) contact: &[MjContact; "array of all detected contacts"; ffi().ncon],
1785        (mut = unsafe) efc_type: &[MjtConstraint [force]; "constraint type"; ffi().nefc],
1786        (mut = unsafe) efc_id: &[i32; "id of object of specified type"; ffi().nefc],
1787        (mut = unsafe) efc_J_rownnz: &[i32; "number of non-zeros in constraint Jacobian row"; ffi().nefc],
1788        (mut = unsafe) efc_J_rowadr: &[i32; "row start address in colind array"; ffi().nefc],
1789        (mut = unsafe) efc_J_rowsuper: &[i32; "number of subsequent rows in supernode"; ffi().nefc],
1790        (mut = unsafe) efc_J_colind: &[i32; "column indices in constraint Jacobian"; ffi().nJ],
1791        efc_J: &[MjtNum; "constraint Jacobian"; ffi().nJ],
1792        efc_pos: &[MjtNum; "constraint position (equality, contact)"; ffi().nefc],
1793        efc_margin: &[MjtNum; "inclusion margin (contact)"; ffi().nefc],
1794        efc_frictionloss: &[MjtNum; "frictionloss (friction)"; ffi().nefc],
1795        efc_diagApprox: &[MjtNum; "approximation to diagonal of A"; ffi().nefc],
1796        efc_KBIP: &[[MjtNum; 4] [force]; "stiffness, damping, impedance, imp'"; ffi().nefc],
1797        efc_D: &[MjtNum; "constraint mass"; ffi().nefc],
1798        efc_R: &[MjtNum; "inverse constraint mass"; ffi().nefc],
1799        (mut = unsafe) tendon_efcadr: &[i32; "first efc address involving tendon; -1: none"; model.ffi().ntendon],
1800        (mut = unsafe) tree_island: &[i32; "island id of this tree; -1: none"; model.ffi().ntree],
1801        (mut = unsafe) island_ntree: &[i32; "number of trees in this island"; ffi().nisland],
1802        (mut = unsafe) island_itreeadr: &[i32; "island start address in itree vector"; ffi().nisland],
1803        (mut = unsafe) map_itree2tree: &[i32; "map from itree to tree"; model.ffi().ntree],
1804        (mut = unsafe) dof_island: &[i32; "island id of this dof; -1: none"; model.ffi().nv],
1805        (mut = unsafe) island_nv: &[i32; "number of dofs in this island"; ffi().nisland],
1806        (mut = unsafe) island_idofadr: &[i32; "island start address in idof vector"; ffi().nisland],
1807        (mut = unsafe) island_dofadr: &[i32; "island start address in dof vector"; ffi().nisland],
1808        (mut = unsafe) map_dof2idof: &[i32; "map from dof to idof"; model.ffi().nv],
1809        (mut = unsafe) map_idof2dof: &[i32; "map from idof to dof;  >= nidof: unconstrained"; model.ffi().nv],
1810        ifrc_smooth: &[MjtNum; "net unconstrained force"; ffi().nidof],
1811        iacc_smooth: &[MjtNum; "unconstrained acceleration"; ffi().nidof],
1812        (mut = unsafe) iM_rownnz: &[i32; "inertia: non-zeros in each row"; ffi().nidof],
1813        (mut = unsafe) iM_rowadr: &[i32; "inertia: address of each row in iM_colind"; ffi().nidof],
1814        (mut = unsafe) iM_colind: &[i32; "inertia: column indices of non-zeros"; model.ffi().nC],
1815        iM: &[MjtNum; "total inertia (sparse)"; model.ffi().nC],
1816        iLD: &[MjtNum; "L'*D*L factorization of M (sparse)"; model.ffi().nC],
1817        iLDiagInv: &[MjtNum; "1/diag(D)"; ffi().nidof],
1818        iacc: &[MjtNum; "acceleration"; ffi().nidof],
1819        (mut = unsafe) efc_island: &[i32; "island id of this constraint"; ffi().nefc],
1820        (mut = unsafe) island_ne: &[i32; "number of equality constraints in island"; ffi().nisland],
1821        (mut = unsafe) island_nf: &[i32; "number of friction constraints in island"; ffi().nisland],
1822        (mut = unsafe) island_nefc: &[i32; "number of constraints in island"; ffi().nisland],
1823        (mut = unsafe) island_iefcadr: &[i32; "start address in iefc vector"; ffi().nisland],
1824        (mut = unsafe) map_efc2iefc: &[i32; "map from efc to iefc"; ffi().nefc],
1825        (mut = unsafe) map_iefc2efc: &[i32; "map from iefc to efc"; ffi().nefc],
1826        (mut = unsafe) iefc_type: &[MjtConstraint [force]; "constraint type"; ffi().nefc],
1827        (mut = unsafe) iefc_id: &[i32; "id of object of specified type"; ffi().nefc],
1828        (mut = unsafe) iefc_J_rownnz: &[i32; "number of non-zeros in constraint Jacobian row"; ffi().nefc],
1829        (mut = unsafe) iefc_J_rowadr: &[i32; "row start address in colind array"; ffi().nefc],
1830        (mut = unsafe) iefc_J_rowsuper: &[i32; "number of subsequent rows in supernode"; ffi().nefc],
1831        (mut = unsafe) iefc_J_colind: &[i32; "column indices in constraint Jacobian"; ffi().nJ],
1832        iefc_J: &[MjtNum; "constraint Jacobian"; ffi().nJ],
1833        iefc_frictionloss: &[MjtNum; "frictionloss (friction)"; ffi().nefc],
1834        iefc_D: &[MjtNum; "constraint mass"; ffi().nefc],
1835        iefc_R: &[MjtNum; "inverse constraint mass"; ffi().nefc],
1836        (mut = unsafe) efc_Y_rownnz: &[i32; "number of non-zeros in Y row"; ffi().nefc],
1837        (mut = unsafe) efc_Y_rowadr: &[i32; "row start address in Y colind array"; ffi().nefc],
1838        (mut = unsafe) efc_Y_colind: &[i32; "column indices in sparse Y"; ffi().nY],
1839        efc_Y: &[MjtNum; "whitened Jacobian Y = J*M^(-1/2)"; ffi().nY],
1840        (mut = unsafe) efc_AR_rownnz: &[i32; "number of non-zeros in AR"; ffi().nefc],
1841        (mut = unsafe) efc_AR_rowadr: &[i32; "row start address in colind array"; ffi().nefc],
1842        (mut = unsafe) efc_AR_colind: &[i32; "column indices in sparse AR"; ffi().nA],
1843        efc_AR: &[MjtNum; "J*inv(M)*J' + R"; ffi().nA],
1844        efc_vel: &[MjtNum; "velocity in constraint space: J*qvel"; ffi().nefc],
1845        efc_aref: &[MjtNum; "reference pseudo-acceleration"; ffi().nefc],
1846        efc_b: &[MjtNum; "linear cost term: J*qacc_smooth - aref"; ffi().nefc],
1847        iefc_aref: &[MjtNum; "reference pseudo-acceleration"; ffi().nefc],
1848        iefc_state: &[MjtConstraintState [force]; "constraint state"; ffi().nefc],
1849        iefc_force: &[MjtNum; "constraint force in constraint space"; ffi().nefc],
1850        efc_state: &[MjtConstraintState [force]; "constraint state"; ffi().nefc],
1851        efc_force: &[MjtNum; "constraint force in constraint space"; ffi().nefc],
1852        ifrc_constraint: &[MjtNum; "constraint force"; ffi().nidof]
1853    }
1854}
1855
1856impl<M: Deref<Target = MjModel>> Drop for MjData<M> {
1857    fn drop(&mut self) {
1858        // SAFETY: self.data is a valid non-null mjData pointer; called exactly once in Drop.
1859        unsafe {
1860            mj_deleteData(self.data.as_ptr());
1861        }
1862    }
1863}
1864
1865impl<M: Deref<Target = MjModel> + Clone> Clone for MjData<M> {
1866    /// # Panics
1867    /// Panics if MuJoCo fails to allocate the cloned data.
1868    /// Use [`MjData::try_clone`] for a fallible alternative.
1869    fn clone(&self) -> Self {
1870        self.try_clone().expect("not enough space to clone data")
1871    }
1872}
1873
1874impl<M: Deref<Target = MjModel> + Clone> MjData<M> {
1875    /// Fallible version of [`Clone::clone`].
1876    ///
1877    /// # Errors
1878    /// Returns [`MjDataError::AllocationFailed`] if MuJoCo fails to allocate
1879    /// the copy.
1880    pub fn try_clone(&self) -> Result<Self, MjDataError> {
1881        let raw = unsafe { mj_copyData(ptr::null_mut(), self.model.ffi(), self.ffi()) };
1882        NonNull::new(raw)
1883            .map(|data| Self { data, model: self.model.clone() })
1884            .ok_or(MjDataError::AllocationFailed)
1885    }
1886}
1887
1888info_with_view!(Data, actuator,
1889    [ctrl: MjtNum,
1890     [actuator_] length: MjtNum,
1891     [actuator_] velocity: MjtNum,
1892     [actuator_] force: MjtNum],
1893    [],
1894    [act: MjtNum], M: Deref<Target = MjModel>);
1895
1896info_with_view!(Data, body,
1897    [xfrc_applied: MjtNum,
1898     xpos: MjtNum,
1899     xquat: MjtNum,
1900     xmat: MjtNum,
1901     xipos: MjtNum,
1902     ximat: MjtNum,
1903     subtree_com: MjtNum,
1904     cinert: MjtNum,
1905     crb: MjtNum,
1906     cvel: MjtNum,
1907     subtree_linvel: MjtNum,
1908     subtree_angmom: MjtNum,
1909     cacc: MjtNum,
1910     cfrc_int: MjtNum,
1911     cfrc_ext: MjtNum],
1912    [[body_] awake: MjtSleepState [force]],
1913    [], M: Deref<Target = MjModel>);
1914
1915info_with_view!(Data, camera,
1916    [[cam_] xpos: MjtNum,
1917     [cam_] xmat: MjtNum],
1918    [],
1919    [], M: Deref<Target = MjModel>);
1920
1921info_with_view!(Data, geom,
1922    [[geom_] xpos: MjtNum,
1923     [geom_] xmat: MjtNum],
1924    [],
1925    [], M: Deref<Target = MjModel>);
1926
1927info_with_view!(Data, joint,
1928    [qpos: MjtNum,
1929     qvel: MjtNum,
1930     qacc_warmstart: MjtNum,
1931     qfrc_applied: MjtNum,
1932     qacc: MjtNum,
1933     xanchor: MjtNum,
1934     xaxis: MjtNum,
1935     qLDiagInv: MjtNum,
1936     qfrc_bias: MjtNum,
1937     qfrc_spring: MjtNum,
1938     qfrc_damper: MjtNum,
1939     qfrc_gravcomp: MjtNum,
1940     qfrc_fluid: MjtNum,
1941     qfrc_passive: MjtNum,
1942     qfrc_actuator: MjtNum,
1943     qfrc_smooth: MjtNum,
1944     qacc_smooth: MjtNum,
1945     qfrc_constraint: MjtNum,
1946     qfrc_inverse: MjtNum],
1947    [],
1948    [], M: Deref<Target = MjModel>);
1949
1950info_with_view!(Data, light,
1951    [[light_] xpos: MjtNum,
1952     [light_] xdir: MjtNum],
1953    [],
1954    [], M: Deref<Target = MjModel>);
1955
1956info_with_view!(Data, sensor,
1957    [[sensor] data: MjtNum],
1958    [],
1959    [], M: Deref<Target = MjModel>);
1960
1961info_with_view!(Data, site,
1962    [[site_] xpos: MjtNum,
1963     [site_] xmat: MjtNum],
1964    [],
1965    [], M: Deref<Target = MjModel>);
1966
1967info_with_view!(Data, tendon,
1968    [[ten_] J: MjtNum,
1969     [ten_] length: MjtNum,
1970     [ten_] velocity: MjtNum],
1971    [[ten_] wrapadr: i32,
1972     [ten_] wrapnum: i32,
1973     [tendon_] efcadr: i32],
1974    [], M: Deref<Target = MjModel>);
1975
1976/**************************************************************************************************/
1977// Unit tests
1978/**************************************************************************************************/
1979
1980#[cfg(test)]
1981// The loop indices are needed for FFI pointer arithmetic (e.g. `ptr.add(i * stride + j)`).
1982#[allow(clippy::needless_range_loop)]
1983mod test {
1984    use crate::assert_relative_eq;
1985    use crate::prelude::*;
1986    use super::*;
1987
1988    const MODEL: &str = "
1989<mujoco>
1990  <asset>
1991    <mesh name=\"cube\" vertex=\"-0.5 -0.5 -0.5  0.5 -0.5 -0.5  -0.5  0.5 -0.5  0.5  0.5 -0.5  -0.5 -0.5  0.5  0.5 -0.5  0.5  -0.5  0.5  0.5  0.5  0.5  0.5\"/>
1992    <hfield name=\"terrain\" nrow=\"10\" ncol=\"10\" size=\"10 10 .1 .1\"/>
1993  </asset>
1994  <worldbody>
1995    <light ambient=\"0.2 0.2 0.2\"/>
1996    <body name=\"ball\" pos=\".2 .2 .1\">
1997        <geom name=\"green_sphere\" size=\".1\" rgba=\"0 1 0 1\" solref=\"0.004 1.0\"/>
1998        <joint name=\"ball\" type=\"free\"/>
1999    </body>
2000
2001    <body name=\"ball2\" pos=\".7 .2 .1\">
2002        <geom name=\"green_sphere2\" size=\".1\" rgba=\"0 1 0 1\" solref=\"0.004 1.0\"/>
2003        <joint name=\"ball2\" type=\"free\"/>
2004    </body>
2005
2006    <geom name=\"floor1\" type=\"plane\" size=\"10 10 1\" solref=\"0.004 1.0\"/>
2007    <geom name=\"mesh_cube\" type=\"mesh\" mesh=\"cube\" pos=\"2 2 0.5\"/>
2008    <geom name=\"hfield_terrain\" type=\"hfield\" hfield=\"terrain\" pos=\"-2 -2 0\"/>
2009  </worldbody>
2010  <actuator>
2011    <motor name=\"motor_ball\" joint=\"ball\"/>
2012  </actuator>
2013</mujoco>";
2014
2015
2016    #[test]
2017    fn test_joint_view() {
2018        let model = MjModel::from_xml_string(MODEL).unwrap();
2019        let mut data = model.make_data();
2020        let joint_info = data.joint("ball").unwrap();
2021        let body_info = data.body("ball").unwrap();
2022
2023        for _ in 0..10 {
2024            data.step();
2025        }
2026
2027        /* The ball should start in a still position */
2028        let mut joint_view = joint_info.view(&data);
2029        assert_relative_eq!(joint_view.qvel[0], 0.0, epsilon=1e-9);  // vx
2030        assert_relative_eq!(joint_view.qvel[1], 0.0, epsilon=1e-9);  // vy
2031        // assert_relative_eq!(view.qvel[2], 0.0);  // vz Ignore due to slight instability of the model.
2032        assert_relative_eq!(joint_view.qvel[3], 0.0, epsilon=1e-9);  // wx
2033        assert_relative_eq!(joint_view.qvel[4], 0.0, epsilon=1e-9);  // wy
2034        assert_relative_eq!(joint_view.qvel[5], 0.0, epsilon=1e-9);  // wz
2035
2036        /* Give the ball some velocity */
2037        let mut joint_view_mut = joint_info.view_mut(&mut data);
2038        joint_view_mut.qvel[0] = 0.5;  // vx = 0.5 m/s
2039        joint_view_mut.qvel[4] = 0.5 / 0.1;  // wy = 0.5 m/s / 0.1 m
2040
2041        let initial_qpos: [MjtNum; 3] = joint_view_mut.qpos[..3].try_into().unwrap();  // initial x, y and z.
2042        data.step();
2043
2044        /* Test if the ball is moving in the x direction and rotating around y. */
2045        joint_view = joint_info.view(&data);
2046        assert_eq!(joint_view.qfrc_spring.len(), joint_view.qvel.len());
2047        assert_eq!(joint_view.qfrc_damper.len(), joint_view.qvel.len());
2048        assert_eq!(joint_view.qfrc_gravcomp.len(), joint_view.qvel.len());
2049        assert_eq!(joint_view.qfrc_fluid.len(), joint_view.qvel.len());
2050        joint_view = joint_info.view(&data);
2051        assert_relative_eq!(joint_view.qvel[0], 0.5, epsilon=1e-3);  // vx
2052        assert_relative_eq!(joint_view.qvel[4], 0.5 / 0.1, epsilon=1e-3);  // wy
2053
2054        /* Test correct placement */
2055        let timestep = model.opt().timestep;
2056        assert_relative_eq!(joint_view.qpos[0], initial_qpos[0] + timestep * joint_view.qvel[0], epsilon=1e-9);  // p = p + dp/dt * dt
2057        assert_relative_eq!(joint_view.qpos[1], initial_qpos[1] + timestep * joint_view.qvel[1], epsilon=1e-9);
2058        assert_relative_eq!(joint_view.qpos[2], initial_qpos[2] + timestep * joint_view.qvel[2], epsilon=1e-9);
2059
2060        /* Test consistency with the body */
2061        data.step1();  // update derived variables.
2062
2063        joint_view = joint_info.view(&data);
2064        let body_view = body_info.view(&data);
2065        /* Consistency in position */
2066        assert_relative_eq!(joint_view.qpos[0], body_view.xpos[0], epsilon=1e-9);  // same position.
2067        assert_relative_eq!(joint_view.qpos[1], body_view.xpos[1], epsilon=1e-9);
2068        assert_relative_eq!(joint_view.qpos[2], body_view.xpos[2], epsilon=1e-9);
2069
2070        assert_relative_eq!(joint_view.qpos[3], body_view.xquat[0], epsilon=1e-9);  // same orientation.
2071        assert_relative_eq!(joint_view.qpos[4], body_view.xquat[1], epsilon=1e-9);
2072        assert_relative_eq!(joint_view.qpos[5], body_view.xquat[2], epsilon=1e-9);
2073        assert_relative_eq!(joint_view.qpos[6], body_view.xquat[3], epsilon=1e-9);
2074
2075        /* Consistency in velocity */
2076        assert_relative_eq!(joint_view.qvel[0], body_view.cvel[3], epsilon=1e-9);  // same position velocity.
2077        assert_relative_eq!(joint_view.qvel[1], body_view.cvel[4], epsilon=1e-9);
2078        assert_relative_eq!(joint_view.qvel[2], body_view.cvel[5], epsilon=1e-9);
2079
2080        assert_relative_eq!(joint_view.qvel[3], body_view.cvel[0], epsilon=1e-9);  // same rotational velocity.
2081        assert_relative_eq!(joint_view.qvel[4], body_view.cvel[1], epsilon=1e-9);
2082        assert_relative_eq!(joint_view.qvel[5], body_view.cvel[2], epsilon=1e-9);
2083    }
2084
2085    #[test]
2086    fn test_actuator_view() {
2087        let model = MjModel::from_xml_string(MODEL).unwrap();
2088        let data = model.make_data();
2089        let actuator_info = data.actuator("motor_ball").unwrap();
2090
2091        let actuator_view = actuator_info.view(&data);
2092        assert_eq!(actuator_view.length.len(), 1);
2093        assert_eq!(actuator_view.velocity.len(), 1);
2094        assert_eq!(actuator_view.force.len(), 1);
2095        assert!(actuator_view.act.is_none());
2096
2097        // Test if indexing corresponds to exact data structure mapping
2098        unsafe {
2099            assert_relative_eq!(actuator_view.length[0], *data.ffi().actuator_length.add(actuator_info.id), epsilon=1e-9);
2100            assert_relative_eq!(actuator_view.velocity[0], *data.ffi().actuator_velocity.add(actuator_info.id), epsilon=1e-9);
2101            assert_relative_eq!(actuator_view.force[0], *data.ffi().actuator_force.add(actuator_info.id), epsilon=1e-9);
2102        }
2103    }
2104
2105    #[test]
2106    fn test_body_view() {
2107        let model = MjModel::from_xml_string(MODEL).unwrap();
2108        let mut data = model.make_data();
2109        let body_info = data.body("ball2").unwrap();
2110        let mut cvel;
2111
2112        data.step1();
2113
2114        for _ in 0..10 {
2115            data.step2();
2116            data.step1();  // step() and step2() update before integration, thus we need to manually update non-state variables.
2117        }
2118
2119        // The ball should start in a still position.
2120        // Use a loose epsilon because physics simulation results can differ by small
2121        // floating-point amounts across architectures (e.g. x86_64 vs aarch64).
2122        cvel = body_info.view(&data).cvel;
2123        assert_relative_eq!(cvel[0], 0.0, epsilon=1e-5);
2124        assert_relative_eq!(cvel[1], 0.0, epsilon=1e-5);
2125        assert_relative_eq!(cvel[2], 0.0, epsilon=1e-5);
2126        assert_relative_eq!(cvel[3], 0.0, epsilon=1e-5);
2127        assert_relative_eq!(cvel[4], 0.0, epsilon=1e-5);
2128        // assert_relative_eq!(cvel[5], 0.0);  // Ignore due to slight instability of the model.
2129
2130        // Give the ball some velocity
2131        body_info.view_mut(&mut data).xfrc_applied[0] = 5.0;
2132        data.step2();
2133        data.step1();
2134
2135        let view = body_info.view(&data);
2136        cvel = view.cvel;
2137        println!("{:?}", cvel);
2138        assert_relative_eq!(cvel[0], 0.0, epsilon=1e-9);
2139        assert!(cvel[1] > 0.0);  // wy should be positive when rolling with positive vx.
2140        assert_relative_eq!(cvel[2], 0.0, epsilon=1e-9);
2141        assert!(cvel[3] > 0.0);  // vx should point in the direction of the applied force.
2142        // assert_relative_eq!(cvel[5], 0.0);  // vz should be 0, but we don't test it due to jumpiness (instability) of the ball.
2143
2144        assert_relative_eq!(view.xfrc_applied[0], 5.0, epsilon=1e-9); // the original force should stay applied.
2145
2146        data.step2();
2147        data.step1();
2148    }
2149
2150    #[test]
2151    fn test_copy_reset_variants() {
2152        let model = MjModel::from_xml_string(MODEL).unwrap();
2153        let mut data = model.make_data();
2154
2155        // Test reset variants
2156        data.reset();
2157        // SAFETY: no accessor with a validity invariant (bvh_active, body_awake)
2158        // is called before the data is dropped.
2159        unsafe { data.reset_debug(7) };
2160        // MODEL has no keyframes so use reset_keyframe and check OOB behaviour.
2161        assert!(data.reset_keyframe(0).is_err());
2162    }
2163
2164    #[test]
2165    fn test_dynamics_and_sensors() {
2166        let model = MjModel::from_xml_string(MODEL).unwrap();
2167        let mut data = model.make_data();
2168
2169        // Simulation pipeline components
2170        data.fwd_position();
2171        data.fwd_velocity();
2172        data.fwd_actuation();
2173        data.fwd_acceleration();
2174        data.fwd_constraint();
2175
2176        data.euler();
2177        data.runge_kutta(4);
2178        // data.implicit();  // integrator isn't implicit in the model => skip this check
2179
2180        data.inv_position();
2181        data.inv_velocity();
2182        data.inv_constraint();
2183        data.compare_fwd_inv();
2184
2185        // Sensors
2186        data.sensor_pos();
2187        data.sensor_vel();
2188        data.sensor_acc();
2189
2190        data.energy_pos();
2191        data.energy_vel();
2192
2193        data.check_pos();
2194        data.check_vel();
2195        data.check_acc();
2196
2197        data.kinematics();
2198        data.com_pos();
2199        data.camlight();
2200        data.flex_comp();
2201        data.tendon_comp();
2202        data.transmission();
2203        data.crb_comp();
2204        data.make_m();
2205        data.factor_m();
2206        data.com_vel();
2207        data.passive();
2208        data.subtree_vel();
2209    }
2210
2211
2212    #[test]
2213    fn test_rne_and_collision_pipeline() {
2214        let model = MjModel::from_xml_string(MODEL).unwrap();
2215        let mut data = model.make_data();
2216        for _ in 0..5 {
2217            data.step();
2218        }
2219
2220        // mj_rne returns a scalar as result
2221        data.rne(true);
2222
2223        data.rne_post_constraint();
2224
2225        // Collision and constraint pipeline
2226        data.collision();
2227        data.make_constraint();
2228        data.island();
2229        data.project_constraint();
2230        data.reference_constraint();
2231
2232        let nefc = data.nefc() as usize;
2233        assert!(nefc > 0, "expected at least one effective constraint after stepping");
2234        let jar = vec![0.0; nefc];
2235        let mut cost = 0.0;
2236        data.constraint_update(&jar, None, false).unwrap();
2237        data.constraint_update(&jar, Some(&mut cost), true).unwrap();
2238    }
2239
2240    #[test]
2241    fn test_add_contact() {
2242        let model = MjModel::from_xml_string(MODEL).unwrap();
2243        let mut data = model.make_data();
2244
2245        // Add a dummy contact. `add_contact` is `unsafe`: the caller guarantees the contact is
2246        // valid for the model (a fully-zeroed contact is in range here).
2247        let dummy_contact: MjContact = bytemuck::Zeroable::zeroed();
2248        unsafe { data.add_contact(&dummy_contact).unwrap(); }
2249        assert_eq!(data.ncon(), 1, "contact count should reflect the added contact");
2250    }
2251
2252    #[test]
2253    fn test_jacobian() {
2254        let model = MjModel::from_xml_string(MODEL).unwrap();
2255        let mut data = model.make_data();
2256
2257        let nv = data.model.ffi().nv as usize;
2258        let expected_len = 3 * nv;
2259
2260        // Use a small offset point relative to the joint origin
2261        let point = [0.1, 0.0, 0.0];
2262
2263        let ball_body_id = model.body("ball").unwrap().id;
2264
2265        // Test global point Jacobian
2266        let (jacp, jacr) = data.jac(true, true, &point, ball_body_id);
2267        assert_eq!(jacp.len(), expected_len);
2268        assert_eq!(jacr.len(), expected_len);
2269
2270        // Test body frame Jacobian
2271        let (jacp_body, jacr_body) = data.jac_body(true, true, ball_body_id);
2272        assert_eq!(jacp_body.len(), expected_len);
2273        assert_eq!(jacr_body.len(), expected_len);
2274
2275        // Test body COM Jacobian
2276        let (jacp_com, jacr_com) = data.jac_body_com(true, true, ball_body_id);
2277        assert_eq!(jacp_com.len(), expected_len);
2278        assert_eq!(jacr_com.len(), expected_len);
2279
2280        // Test subtree COM Jacobian (translational only)
2281        let jac_subtree = data.jac_subtree_com(0);
2282        assert_eq!(jac_subtree.len(), expected_len);
2283
2284        // Test geom Jacobian
2285        let green_geom_id = model.geom("green_sphere").unwrap().id;
2286        let (jacp_geom, jacr_geom) = data.jac_geom(true, true, green_geom_id);
2287        assert_eq!(jacp_geom.len(), expected_len);
2288        assert_eq!(jacr_geom.len(), expected_len);
2289
2290        // Test site Jacobian - only if sites exist
2291        if model.ffi().nsite > 0 {
2292            let site_id = 0usize;
2293            let (jacp_site, jacr_site) = data.jac_site(true, true, site_id);
2294            assert_eq!(jacp_site.len(), expected_len);
2295            assert_eq!(jacr_site.len(), expected_len);
2296        }
2297
2298        // Test flags set to false produce empty Vec
2299        let (jacp_none, jacr_none) = data.jac(false, false, &[0.0; 3], ball_body_id);
2300        assert!(jacp_none.is_empty());
2301        assert!(jacr_none.is_empty());
2302    }
2303
2304    #[test]
2305    fn test_angmom_and_object_dynamics() {
2306        let model = MjModel::from_xml_string(MODEL).unwrap();
2307        let mut data = model.make_data();
2308
2309        let mat = data.angmom_mat(0);
2310        assert_eq!(mat.len(), (3 * data.model.ffi().nv as usize));
2311
2312        let vel = data.object_velocity(MjtObj::mjOBJ_BODY, 0, true);
2313        assert_eq!(vel.len(), 6);
2314
2315        let acc = data.object_acceleration(MjtObj::mjOBJ_BODY, 0, false);
2316        assert_eq!(acc.len(), 6);
2317    }
2318
2319    #[test]
2320    fn test_geom_distance_and_transforms() {
2321        let model = MjModel::from_xml_string(MODEL).unwrap();
2322        let mut data = model.make_data();
2323        data.step();
2324
2325        // Test actual distance between two different geoms (green_sphere and green_sphere2).
2326        // green_sphere is at (.2, .2, .1) and green_sphere2 is at (.7, .2, .1), both with radius 0.1.
2327        // Expected distance ~= 0.5 - 2*0.1 = 0.3 (center distance minus both radii).
2328        let geom0_id = model.name_to_id(MjtObj::mjOBJ_GEOM, "green_sphere").unwrap();
2329        let geom1_id = model.name_to_id(MjtObj::mjOBJ_GEOM, "green_sphere2").unwrap();
2330
2331        let mut ft = [0.0; 6];
2332        let dist = data.geom_distance(geom0_id, geom1_id, 1.0, Some(&mut ft));
2333        assert!(dist > 0.0, "distance between separate geoms should be positive, got {dist}");
2334        assert!(dist < 1.0, "distance should be less than distmax, got {dist}");
2335        assert_relative_eq!(dist, 0.3, epsilon=1e-3);
2336        // fromto should be populated: first 3 = nearest point on geom0, last 3 = nearest point on geom1
2337        let ft_norm = ft.iter().map(|x| x * x).sum::<MjtNum>().sqrt();
2338        assert!(ft_norm > 0.0, "fromto should be non-zero for non-overlapping geoms");
2339
2340        let pos = [0.0; 3];
2341        let quat = [1.0, 0.0, 0.0, 0.0];
2342        let (xpos, xmat) = data.local_to_global(&pos, &quat, 0, MjtSameFrame::mjSAMEFRAME_NONE);
2343        assert_eq!(xpos.len(), 3);
2344        assert_eq!(xmat.len(), 9);
2345
2346        let ray_vecs = [[1.0, 0.0, 0.0], [1.0, 0.0, 0.0], [1.0, 0.0, 0.0]];
2347        let rays = data.multi_ray(&pos, &ray_vecs, None, false, None, 10.0, None);
2348        assert_eq!(rays.0.len(), 3);
2349        assert_eq!(rays.1.len(), 3);
2350
2351        let (_geomid, dist) = data.ray(&pos, &[1.0, 0.0, 0.0], None, true, None, None);
2352        assert!(dist.is_finite());
2353
2354        // ray API with normal output (optional parameter)
2355        let mut normal = [0.0; 3];
2356        let (_geomid2, dist2) = data.ray(&pos, &[1.0, 0.0, 0.0], None, true, None, Some(&mut normal));
2357        assert!(dist2.is_finite());
2358        let norm_len = (normal[0]*normal[0] + normal[1]*normal[1] + normal[2]*normal[2]).sqrt();
2359        if dist2 >= 0.0 {
2360            // hit - normal should be non-zero
2361            assert!(norm_len > 0.0);
2362        } else {
2363            // no hit - normal buffer is unchanged / zeroed
2364            assert_eq!(normal, [0.0; 3]);
2365        }
2366
2367        let mut normals_buf = vec![[0.0; 3]; ray_vecs.len()];
2368        let (gids, dists) = data.multi_ray(&pos, &ray_vecs, None, false, None, 10.0, Some(&mut normals_buf));
2369        assert_eq!(gids.len(), normals_buf.len());
2370        assert_eq!(dists.len(), normals_buf.len());
2371        for (d, n) in dists.iter().zip(normals_buf.iter()) {
2372            let l = (n[0]*n[0] + n[1]*n[1] + n[2]*n[2]).sqrt();
2373            if *d >= 0.0 {
2374                assert!(l > 0.0);
2375            } else {
2376                assert_eq!(*n, [0.0; 3]);
2377            }
2378        }
2379    }
2380
2381    #[test]
2382    fn test_constraint_update_checks_jar_length() {
2383        let model = MjModel::from_xml_string(MODEL).unwrap();
2384        let mut data = model.make_data();
2385
2386        // Need to step to generate contact constraints
2387        // Multiple steps ensure collisions are properly detected and compiled
2388        for _ in 0..5 {
2389            data.step();
2390        }
2391
2392        // After stepping with a contact-rich model, nefc should be > 0
2393        let nefc = data.ffi().nefc as usize;
2394        assert!(nefc > 0, "Expected nefc > 0 after stepping with contact model, got {}", nefc);
2395
2396        // correct length should not panic
2397        let jar = vec![0.0; nefc];
2398        data.constraint_update(&jar, None, false).unwrap();
2399
2400        // wrong length should return Err
2401        let bad_jar = vec![0.0; 1];
2402        let result = data.constraint_update(&bad_jar, None, false);
2403        assert!(result.is_err());
2404    }
2405
2406    #[test]
2407    fn test_init_history_ctrl_and_sensor() {
2408        const HIST_MODEL: &str = r#"
2409<mujoco>
2410  <option timestep="0.01"/>
2411  <worldbody>
2412    <body name="body">
2413      <joint name="slide" type="slide"/>
2414      <geom size="0.1"/>
2415    </body>
2416  </worldbody>
2417  <actuator>
2418    <motor name="motor0" joint="slide" delay="0.05" nsample="6"/>
2419  </actuator>
2420  <sensor>
2421    <jointpos name="jointpos0" joint="slide" delay="0.025" interp="linear" nsample="4"/>
2422  </sensor>
2423</mujoco>
2424"#;
2425
2426        let model = MjModel::from_xml_string(HIST_MODEL).unwrap();
2427        let mut data = model.make_data();
2428
2429        let times_ctrl: Vec<MjtNum> = (0..6).map(|i| i as MjtNum * 0.01).collect();
2430        let values_ctrl = vec![1.2345; 6];
2431        data.init_ctrl_history(0, Some(&times_ctrl), &values_ctrl).unwrap();
2432
2433        // read back via safe wrapper: exact-match should return provided value
2434        let val = data.read_ctrl(0, times_ctrl[2], 0);
2435        assert_relative_eq!(val, values_ctrl[2], epsilon=1e-12);
2436
2437        // sensor history via wrapper
2438        let times_sens: Vec<MjtNum> = (0..4).map(|i| i as MjtNum * 0.01).collect();
2439        // sensor dim for jointpos is 1
2440        let values_sens = vec![std::f64::consts::E; 4];
2441        data.init_sensor_history(0, Some(&times_sens), &values_sens, 0.0).unwrap();
2442
2443        let got = data.read_sensor_fixed::<1>(0, times_sens[1], 0);
2444        assert_eq!(got.len(), 1);
2445        assert_relative_eq!(got[0], values_sens[1], epsilon=1e-12);
2446
2447        // also test interpolation path (time between samples)
2448        let interp_res = data.read_sensor_fixed::<1>(0, 0.005, 1);
2449        assert_eq!(interp_res.len(), 1);
2450        // values are identical here, but ensure we get a value
2451        assert_relative_eq!(interp_res[0], values_sens[0], epsilon=1e-12);
2452    }
2453
2454    #[test]
2455    fn test_fwd_kinematics_and_mul_wrappers() {
2456        let model = MjModel::from_xml_string(MODEL).unwrap();
2457        let mut data = model.make_data();
2458
2459        let joint_info = data.joint("ball").unwrap();
2460        {
2461            let mut jv = joint_info.view_mut(&mut data);
2462            jv.qpos[0] = 0.42;  // set body x
2463            jv.qpos[1] = 0.43;  // set body y
2464            jv.qpos[2] = 0.44;  // set body z
2465            jv.qpos[3] = 1.0;   // unit quaternion
2466            jv.qpos[4] = 0.0;
2467            jv.qpos[5] = 0.0;
2468            jv.qpos[6] = 0.0;
2469        }
2470        data.forward_kinematics();
2471        let body_view = data.body("ball").unwrap().view(&data);
2472        assert_relative_eq!(body_view.xpos[0], 0.42, epsilon=1e-9);
2473        assert_relative_eq!(body_view.xpos[1], 0.43, epsilon=1e-9);
2474        assert_relative_eq!(body_view.xpos[2], 0.44, epsilon=1e-9);
2475    }
2476
2477    #[test]
2478    fn test_qpos_view() {
2479        const JOINT_BALL_DOF: usize = 7;
2480        const BALL_INDEX: usize = 1;
2481        const DOF_TO_MODIFY: usize = 2;
2482        const MODIFIED_VALUE: f64 = 15.0;
2483
2484        let model = MjModel::from_xml_string(MODEL).unwrap();
2485        let name = model.id_to_name(MjtObj::mjOBJ_JOINT, BALL_INDEX).unwrap();
2486
2487        let mut data = MjData::new(&model);
2488        let ball2_joint_info = data.joint(name).unwrap();
2489        ball2_joint_info.view_mut(&mut data).qpos[DOF_TO_MODIFY] = MODIFIED_VALUE;
2490
2491        assert_eq!(data.qpos()[JOINT_BALL_DOF * BALL_INDEX + DOF_TO_MODIFY], MODIFIED_VALUE);
2492    }
2493
2494    #[test]
2495    fn test_contacts() {
2496        let model = MjModel::from_xml_string(MODEL).unwrap();
2497        let mut data = MjData::new(&model);
2498        let ptr = unsafe { data.ffi_mut().contact };
2499        assert!(ptr.is_aligned());
2500        assert!(!ptr.is_null());
2501        assert!(data.contact().is_empty());
2502        data.step();
2503
2504        assert!(!data.contact().is_empty());
2505    }
2506
2507    #[test]
2508    fn test_init_ctrl_history_all_combinations() {
2509        const HIST_MODEL: &str = r#"
2510<mujoco>
2511  <worldbody>
2512    <body name="body">
2513      <joint name="slide" type="slide"/>
2514      <geom size="0.1"/>
2515    </body>
2516  </worldbody>
2517  <actuator>
2518    <motor name="motor0" joint="slide" delay="0.05" nsample="6"/>
2519  </actuator>
2520</mujoco>
2521"#;
2522
2523        let model = MjModel::from_xml_string(HIST_MODEL).unwrap();
2524        let mut data = model.make_data();
2525
2526        let times: Vec<MjtNum> = (0..6).map(|i| i as MjtNum * 0.01).collect();
2527        let values = vec![1.2345; 6];
2528
2529        // success: times Some / None
2530        assert!(data.init_ctrl_history(0, Some(&times), &values).is_ok());
2531        assert!(data.init_ctrl_history(0, None, &values).is_ok());
2532
2533        // times length mismatch -> LengthMismatch
2534        let bad_times = vec![0.0f64];
2535        let err = data.init_ctrl_history(0, Some(&bad_times), &values).unwrap_err();
2536        assert!(matches!(err, MjDataError::LengthMismatch { name: "times", .. }));
2537
2538        // values length mismatch -> LengthMismatch
2539        let bad_values = vec![1.0; 5];
2540        let err = data.init_ctrl_history(0, Some(&times), &bad_values).unwrap_err();
2541        assert!(matches!(err, MjDataError::LengthMismatch { name: "values", .. }));
2542
2543        // invalid actuator id -> IndexOutOfBounds
2544        let err = data.init_ctrl_history(99, Some(&times), &values).unwrap_err();
2545        assert!(matches!(err, MjDataError::IndexOutOfBounds { kind: "actuator_id", .. }));
2546
2547        // read_ctrl invalid id -> IndexOutOfBounds
2548        let err = data.try_read_ctrl(99, times[0], 0).unwrap_err();
2549        assert!(matches!(err, MjDataError::IndexOutOfBounds { kind: "actuator_id", .. }));
2550
2551        // actuator exists but has no history buffer -> NoHistoryBuffer
2552        const NO_HIST_ACT_MODEL: &str = r#"
2553<mujoco>
2554  <worldbody>
2555    <body>
2556      <joint name="slide" type="slide"/>
2557      <geom size="0.1"/>
2558    </body>
2559  </worldbody>
2560  <actuator>
2561    <motor name="motor0" joint="slide"/>
2562  </actuator>
2563</mujoco>
2564"#;
2565        let model2 = MjModel::from_xml_string(NO_HIST_ACT_MODEL).unwrap();
2566        let mut data2 = model2.make_data();
2567        let err = data2.init_ctrl_history(0, Some(&times), &values).unwrap_err();
2568        assert!(matches!(err, MjDataError::NoHistoryBuffer { kind: "actuator", id: 0 }));
2569    }
2570
2571    #[test]
2572    fn test_init_sensor_history_all_combinations() {
2573        const HIST_SENSOR_MODEL: &str = r#"
2574<mujoco>
2575  <worldbody>
2576    <body name="body">
2577      <joint name="slide" type="slide"/>
2578      <geom size="0.1"/>
2579    </body>
2580  </worldbody>
2581  <sensor>
2582    <jointpos name="jointpos0" joint="slide" delay="0.025" interp="linear" nsample="4"/>
2583  </sensor>
2584</mujoco>
2585"#;
2586
2587        let model = MjModel::from_xml_string(HIST_SENSOR_MODEL).unwrap();
2588        let mut data = model.make_data();
2589
2590        let times_sens: Vec<MjtNum> = (0..4).map(|i| i as MjtNum * 0.01).collect();
2591        let values_sens = vec![std::f64::consts::E; 4]; // dim == 1 for jointpos
2592
2593        // success: times Some / None
2594        assert!(data.init_sensor_history(0, Some(&times_sens), &values_sens, 0.0).is_ok());
2595        assert!(data.init_sensor_history(0, None, &values_sens, 0.0).is_ok());
2596
2597        // times length mismatch -> LengthMismatch
2598        let bad_times = vec![0.0f64];
2599        let err = data.init_sensor_history(0, Some(&bad_times), &values_sens, 0.0).unwrap_err();
2600        assert!(matches!(err, MjDataError::LengthMismatch { name: "times", .. }));
2601
2602        // values length mismatch -> LengthMismatch
2603        let bad_values = vec![std::f64::consts::PI; 3];
2604        let err = data.init_sensor_history(0, Some(&times_sens), &bad_values, 0.0).unwrap_err();
2605        assert!(matches!(err, MjDataError::LengthMismatch { name: "values", .. }));
2606
2607        // invalid sensor id -> IndexOutOfBounds
2608        let err = data.init_sensor_history(99, Some(&times_sens), &values_sens, 0.0).unwrap_err();
2609        assert!(matches!(err, MjDataError::IndexOutOfBounds { kind: "sensor_id", .. }));
2610
2611        // read_sensor invalid id -> IndexOutOfBounds
2612        let err: Result<[MjtNum; 1], MjDataError> = data.try_read_sensor_fixed::<1>(99, times_sens[0], 0);
2613        assert!(matches!(err.unwrap_err(), MjDataError::IndexOutOfBounds { kind: "sensor_id", .. }));
2614
2615        // sensor exists but has no history buffer -> NoHistoryBuffer
2616        const NO_HIST_SENS_MODEL: &str = r#"
2617<mujoco>
2618  <worldbody>
2619    <body>
2620      <joint name="slide" type="slide"/>
2621      <geom size="0.1"/>
2622    </body>
2623  </worldbody>
2624  <sensor>
2625    <jointpos name="jointpos0" joint="slide"/>
2626  </sensor>
2627</mujoco>
2628"#;
2629        let model2 = MjModel::from_xml_string(NO_HIST_SENS_MODEL).unwrap();
2630        let mut data2 = model2.make_data();
2631        let err = data2.init_sensor_history(0, Some(&times_sens), &values_sens, 0.0).unwrap_err();
2632        assert!(matches!(err, MjDataError::NoHistoryBuffer { kind: "sensor", id: 0 }));
2633    }
2634
2635    #[test]
2636    fn test_read_sensor_variants() {
2637        // Model with a delayed sensor (history enabled) so we can test both
2638        // Cow::Borrowed (exact time match) and Cow::Owned (interpolation) paths.
2639        const HIST_MODEL: &str = r#"
2640<mujoco>
2641  <option timestep="0.01"/>
2642  <worldbody>
2643    <body>
2644      <joint name="slide" type="slide"/>
2645      <geom size="0.1"/>
2646    </body>
2647  </worldbody>
2648  <sensor>
2649    <jointpos name="jp" joint="slide" delay="0.03" interp="linear" nsample="4"/>
2650  </sensor>
2651</mujoco>
2652"#;
2653        let model = MjModel::from_xml_string(HIST_MODEL).unwrap();
2654        let mut data = model.make_data();
2655        let delay = 0.03;
2656
2657        // Seed the history buffer with known distinct values.
2658        let hist_times: Vec<_> = (0..4).map(|i| i as MjtNum * 0.01).collect();
2659        let values = vec![10.0, 20.0, 30.0, 40.0]; // dim==1 for jointpos
2660        data.init_sensor_history(0, Some(&hist_times), &values, 0.0).unwrap();
2661
2662        // mj_readSensor internally reads at (time - delay), so to read history
2663        // entry at hist_times[i] we must pass time = hist_times[i] + delay.
2664
2665        // exact match -> Cow::Borrowed
2666        let query_time = hist_times[2] + delay; // 0.02 + 0.03 = 0.05
2667        let cow = data.read_sensor(0, query_time, 0);
2668        assert_eq!(cow.len(), 1);
2669        assert_relative_eq!(cow[0], 30.0, epsilon = 1e-12);
2670        assert!(matches!(cow, std::borrow::Cow::Borrowed(_)),
2671                "exact match should yield Cow::Borrowed");
2672
2673        // interpolation -> Cow::Owned
2674        // midpoint between hist_times[1]=0.01 and hist_times[2]=0.02 -> internal time 0.015
2675        let interp_query = (hist_times[1] + hist_times[2]) / 2.0 + delay; // 0.045
2676        let cow_interp = data.read_sensor(0, interp_query, 1);
2677        assert_eq!(cow_interp.len(), 1);
2678        assert_relative_eq!(cow_interp[0], 25.0, epsilon = 1e-6); // linear interp of 20 and 30
2679        assert!(matches!(cow_interp, std::borrow::Cow::Owned(_)),
2680                "interpolation should yield Cow::Owned");
2681
2682        // read_sensor_fixed<N>: exact match (stack array)
2683        let arr_exact: [f64; 1] = data.read_sensor_fixed(0, query_time, 0);
2684        assert_relative_eq!(arr_exact[0], 30.0, epsilon = 1e-12);
2685
2686        // read_sensor_fixed<N>: interpolation (stack array)
2687        let arr_interp: [f64; 1] = data.read_sensor_fixed(0, interp_query, 1);
2688        assert_relative_eq!(arr_interp[0], 25.0, epsilon = 1e-6);
2689
2690        // read_sensor_fixed<N>: wrong N -> Err(LengthMismatch)
2691        let err: Result<[MjtNum; 3], MjDataError> = data.try_read_sensor_fixed::<3>(0, query_time, 0);
2692        assert!(matches!(err.unwrap_err(), MjDataError::LengthMismatch { name: "N", .. }));
2693
2694        // read_sensor_into: exact match
2695        let mut buf = [0.0; 1];
2696        data.read_sensor_into(0, hist_times[0] + delay, 0, &mut buf).unwrap();
2697        assert_relative_eq!(buf[0], 10.0, epsilon = 1e-12);
2698
2699        // read_sensor_into: interpolation
2700        let mut buf2 = [0.0; 1];
2701        data.read_sensor_into(0, interp_query, 1, &mut buf2).unwrap();
2702        assert_relative_eq!(buf2[0], 25.0, epsilon = 1e-6);
2703
2704        // read_sensor_into: buffer too small -> Err(LengthMismatch)
2705        let mut tiny: [MjtNum; 0] = [];
2706        let err = data.read_sensor_into(0, hist_times[0] + delay, 0, &mut tiny).unwrap_err();
2707        assert!(matches!(err, MjDataError::LengthMismatch { name: "dst", .. }));
2708
2709        // read_sensor_into: buffer too large -> Err(LengthMismatch)
2710        let mut big = [0.0; 4];
2711        let err = data.read_sensor_into(0, hist_times[3] + delay, 0, &mut big).unwrap_err();
2712        assert!(matches!(err, MjDataError::LengthMismatch { name: "dst", .. }));
2713
2714        // invalid sensor id -> IndexOutOfBounds for all methods
2715        let err: Result<[MjtNum; 1], MjDataError> = data.try_read_sensor_fixed::<1>(99, 0.0, 0);
2716        assert!(matches!(err.unwrap_err(), MjDataError::IndexOutOfBounds { kind: "sensor_id", .. }));
2717        let err = data.try_read_sensor(99, 0.0, 0).unwrap_err();
2718        assert!(matches!(err, MjDataError::IndexOutOfBounds { kind: "sensor_id", .. }));
2719        let err = data.read_sensor_into(99, 0.0, 0, &mut buf).unwrap_err();
2720        assert!(matches!(err, MjDataError::IndexOutOfBounds { kind: "sensor_id", .. }));
2721
2722        // read_sensor_fixed<N>, read_sensor, and read_sensor_into agree for all history times
2723        for &t in &hist_times {
2724            let query = t + delay;
2725            let arr = data.read_sensor_fixed::<1>(0, query, 0);
2726            let cow_val = data.read_sensor(0, query, 0);
2727            let mut into_val = [0.0; 1];
2728            data.read_sensor_into(0, query, 0, &mut into_val).unwrap();
2729            assert_relative_eq!(arr[0], cow_val[0], epsilon = 1e-12);
2730            assert_relative_eq!(arr[0], into_val[0], epsilon = 1e-12);
2731        }
2732    }
2733
2734    #[test]
2735    fn test_multi_ray_zero_rays() {
2736        let model = MjModel::from_xml_string(MODEL).unwrap();
2737        let mut data = model.make_data();
2738        let pos = [0.0; 3];
2739        let ray_vecs: Vec<[MjtNum; 3]> = Vec::new();
2740
2741        // ensure calling with zero rays returns empty vectors and does not crash
2742        let (gids, dists) = data.multi_ray(&pos, &ray_vecs, None, false, None, 10.0, None);
2743        assert!(gids.is_empty());
2744        assert!(dists.is_empty());
2745    }
2746
2747    #[test]
2748    fn test_multi_ray_normals_length_mismatch() {
2749        let model = MjModel::from_xml_string(MODEL).unwrap();
2750        let mut data = model.make_data();
2751        let pos = [0.0; 3];
2752        let ray_vecs = [[1.0, 0.0, 0.0], [1.0, 0.0, 0.0], [1.0, 0.0, 0.0]];
2753        let mut bad_normals = vec![[0.0; 3]; 2]; // length 2 != 3
2754
2755        let res = data.try_multi_ray(&pos, &ray_vecs, None, false, None, 10.0, Some(&mut bad_normals));
2756        assert!(res.is_err());
2757        assert!(matches!(res.unwrap_err(), MjDataError::LengthMismatch { name: "normals_out", .. }));
2758    }
2759
2760    #[test]
2761    fn test_copy_state_from_data() {
2762        let model = MjModel::from_xml_string(MODEL).unwrap();
2763        let mut data1 = model.make_data();
2764        let mut data2 = model.make_data();
2765
2766        data1.set_time(1.23);
2767        data2.copy_state_from_data(&data1, MjtState::mjSTATE_TIME as u32).unwrap();
2768
2769        assert_eq!(data2.time(), 1.23);
2770    }
2771
2772    #[test]
2773    #[should_panic]
2774    fn test_ray_flex() {
2775        let model = MjModel::from_xml_string(MODEL).unwrap();
2776        let data = model.make_data();
2777        let pos = [0.0; 3];
2778        let vec = [1.0, 0.0, 0.0];
2779
2780        // Model has no flexes, so any flexid is out of bounds.
2781        data.ray_flex(0, false, false, false, false, 0, &pos, &vec, None, None);
2782    }
2783
2784    #[test]
2785    fn test_ray_mesh_hfield() {
2786        let model = MjModel::from_xml_string(MODEL).unwrap();
2787        let mut data = model.make_data();
2788
2789        let mesh_id = model.geom("mesh_cube").unwrap().id;
2790        let hfield_id = model.geom("hfield_terrain").unwrap().id;
2791
2792        data.forward_kinematics();
2793
2794        // Ray should hit mesh (centered at 2,2,0.5, size 1x1x1)
2795        // Top surface of the mesh is at z=0.5 + 0.5 = 1.0.
2796        // Ray starts at z=5.0 and goes straight down [0, 0, -1].
2797        // Intersection should be at exactly distance 4.0.
2798        let mesh_dist = data.ray_mesh(mesh_id, &[2.0, 2.0, 5.0], &[0.0, 0.0, -1.0], None);
2799        assert_relative_eq!(mesh_dist, 4.0, epsilon=1e-5);
2800
2801        // Ray should hit hfield (centered at -2,-2,0)
2802        // Default hfield with no data acts as a plane at z=0.
2803        // Intersection should be at exactly distance 5.0.
2804        let hfield_dist = data.ray_hfield(hfield_id, &[-2.0, -2.0, 5.0], &[0.0, 0.0, -1.0], None);
2805        assert_relative_eq!(hfield_dist, 5.0, epsilon=1e-5);
2806    }
2807
2808    #[test]
2809    fn test_apply_ft() {
2810        let model = MjModel::from_xml_string(MODEL).unwrap();
2811        let mut data = model.make_data();
2812        let nv = model.nv() as usize;
2813        let body_id = model.body("ball").unwrap().id;
2814        let mut qfrc = vec![0.0; nv];
2815
2816        data.forward();
2817
2818        // Apply force/torque at the ball's center of mass (pos = [0.2, 0.2, 0.1]) in global frame
2819        let force = [1.5, 2.5, 3.5];
2820        let torque = [0.1, 0.2, 0.3];
2821        let point = [0.2, 0.2, 0.1];
2822
2823        data.apply_ft(&force, &torque, &point, body_id, &mut qfrc).unwrap();
2824
2825        // The "ball" has a free joint.
2826        // In MuJoCo, for a free joint, the first 3 DOFs are translation (linear),
2827        // and the next 3 are the rotational DOFs.
2828        // Since we applied it exactly at the COM, there should be no induced torque from the force position.
2829        let dof_adr = model.body_dofadr()[body_id] as usize;
2830        assert!((qfrc[dof_adr] - 1.5).abs() < 1e-5);
2831        assert!((qfrc[dof_adr + 1] - 2.5).abs() < 1e-5);
2832        assert!((qfrc[dof_adr + 2] - 3.5).abs() < 1e-5);
2833        assert!((qfrc[dof_adr + 3] - 0.1).abs() < 1e-5);
2834        assert!((qfrc[dof_adr + 4] - 0.2).abs() < 1e-5);
2835        assert!((qfrc[dof_adr + 5] - 0.3).abs() < 1e-5);
2836    }
2837
2838    #[test]
2839    #[should_panic(expected = "model signature mismatch")]
2840    fn test_signature_mismatch_panics() {
2841        let model1 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body></worldbody></mujoco>").unwrap();
2842        let model2 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body><body name='extra'/></worldbody></mujoco>").unwrap();
2843
2844        let data1 = model1.make_data();
2845        let joint_info1 = data1.joint("j1").unwrap();
2846
2847        // This should panic because joint_info1 was created from model1, but we are viewing it with model2/data2
2848        let data2 = model2.make_data();
2849        let _view = joint_info1.view(&data2);
2850    }
2851
2852    #[test]
2853    #[should_panic(expected = "model signature mismatch")]
2854    fn test_signature_mismatch_reversed_joints() {
2855        let model1 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body><body name='b2'><joint name='j2' type='ball'/><geom size='0.1' mass='1'/></body></worldbody></mujoco>").unwrap();
2856        let model2 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j2' type='ball'/><geom size='0.1' mass='1'/></body><body name='b2'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body></worldbody></mujoco>").unwrap();
2857
2858        let data1 = model1.make_data();
2859        let joint_info1 = data1.joint("j1").unwrap();
2860
2861        // This should panic because the kinematic tree is structurally different
2862        let data2 = model2.make_data();
2863        let _view = joint_info1.view(&data2);
2864    }
2865
2866    #[test]
2867    #[should_panic(expected = "model signature mismatch")]
2868    fn test_signature_mismatch_view_mut_panics() {
2869        let model1 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body></worldbody></mujoco>").unwrap();
2870        let model2 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body><body name='extra'/></worldbody></mujoco>").unwrap();
2871
2872        let data1 = model1.make_data();
2873        let joint_info1 = data1.joint("j1").unwrap();
2874
2875        let mut data2 = model2.make_data();
2876        let _view = joint_info1.view_mut(&mut data2);
2877    }
2878
2879    #[test]
2880    fn test_try_view_signature_mismatch() {
2881        let model1 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body></worldbody></mujoco>").unwrap();
2882        let model2 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body><body name='extra'/></worldbody></mujoco>").unwrap();
2883
2884        let data1 = model1.make_data();
2885        let joint_info1 = data1.joint("j1").unwrap();
2886        let mut data2 = model2.make_data();
2887
2888        let err = joint_info1.try_view(&data2).unwrap_err();
2889        match err {
2890            MjDataError::SignatureMismatch { source, destination } => {
2891                assert_eq!(source, data1.signature());
2892                assert_eq!(destination, data2.signature());
2893            }
2894            other => panic!("expected SignatureMismatch, got {other:?}"),
2895        }
2896
2897        let err = joint_info1.try_view_mut(&mut data2).unwrap_err();
2898        match err {
2899            MjDataError::SignatureMismatch { source, destination } => {
2900                assert_eq!(source, data1.signature());
2901                assert_eq!(destination, data2.signature());
2902            }
2903            other => panic!("expected SignatureMismatch, got {other:?}"),
2904        }
2905    }
2906
2907    #[test]
2908    fn test_signature_match_physics_param_change() {
2909        let model1 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='1'/></body></worldbody></mujoco>").unwrap();
2910        let model2 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint name='j1' type='free'/><geom size='0.1' mass='2'/></body></worldbody></mujoco>").unwrap();
2911
2912        let data1 = model1.make_data();
2913        let joint_info1 = data1.joint("j1").unwrap();
2914
2915        // This should NOT panic because only physics parameters changed, the tree is the same
2916        let data2 = model2.make_data();
2917        let _view = joint_info1.view(&data2);
2918    }
2919
2920    #[test]
2921    fn test_act_mixed_stateful_stateless() {
2922        // muscle at id=0 (stateful, actnum=1), motor at id=1 (stateless, actnum=0)
2923        // This tests mj_view_indices! with na path: actadr[0]=0, actadr[1]=-1
2924        // If bug exists: end_addr = (-1i32) as usize = usize::MAX -> overflow
2925        let xml = "<mujoco><option timestep=\"0.002\"/>\
2926<worldbody><body name=\"b\"><joint name=\"j1\" type=\"slide\" range=\"-1 1\" limited=\"true\"/>\
2927<joint name=\"j2\" type=\"slide\"/><geom size=\"0.1\" mass=\"1\"/></body></worldbody>\
2928<actuator><muscle name=\"m1\" joint=\"j1\" lengthrange=\"0 1\"/><motor name=\"m2\" joint=\"j2\"/></actuator></mujoco>";
2929        let model = MjModel::from_xml_string(xml).unwrap();
2930        let data = model.make_data();
2931        let actadr = model.actuator_actadr();
2932        let actnum = model.actuator_actnum();
2933        eprintln!("actadr[0]={} actadr[1]={}", actadr[0], actadr[1]);
2934        eprintln!("actnum[0]={} actnum[1]={}", actnum[0], actnum[1]);
2935        // muscle (m1) should have an act view with exactly actnum[0] elements
2936        let info_m1 = data.actuator("m1").unwrap();
2937        let view_m1 = info_m1.view(&data);
2938        let act_m1 = view_m1.act.as_ref().expect("muscle must have an act view (bug: overflow sets it to None/garbage)");
2939        assert_eq!(act_m1.len(), actnum[0] as usize,
2940            "muscle act len wrong: expected {} got {} (overflow bug?)", actnum[0], act_m1.len());
2941        // motor (m2) should have no act view
2942        let info_m2 = data.actuator("m2").unwrap();
2943        let view_m2 = info_m2.view(&data);
2944        assert!(view_m2.act.is_none(), "motor must have no act view");
2945    }
2946
2947    /// Tests `mj_view_indices!` with mixed joint types (free/ball/slide),
2948    /// verifying that qpos and qvel view lengths match per-joint DOF counts.
2949    #[test]
2950    fn test_view_indices_mixed_joint_types() {
2951        const MIXED_MODEL: &str = "
2952<mujoco>
2953  <worldbody>
2954    <body name='b_free'>
2955      <joint name='j_free' type='free'/>
2956      <geom size='0.1' mass='1'/>
2957    </body>
2958    <body name='b_ball'>
2959      <joint name='j_ball' type='ball'/>
2960      <geom size='0.1' mass='1'/>
2961    </body>
2962    <body name='b_slide'>
2963      <joint name='j_slide' type='slide'/>
2964      <geom size='0.1' mass='1'/>
2965    </body>
2966  </worldbody>
2967</mujoco>";
2968
2969        let model = MjModel::from_xml_string(MIXED_MODEL).unwrap();
2970        let data = model.make_data();
2971
2972        // free: 7 qpos, 6 qvel; ball: 4 qpos, 3 qvel; slide: 1 qpos, 1 qvel
2973        let jfree = data.joint("j_free").unwrap();
2974        let jball = data.joint("j_ball").unwrap();
2975        let jslide = data.joint("j_slide").unwrap();
2976
2977        let vfree = jfree.view(&data);
2978        let vball = jball.view(&data);
2979        let vslide = jslide.view(&data);
2980
2981        assert_eq!(vfree.qpos.len(), 7);
2982        assert_eq!(vfree.qvel.len(), 6);
2983        assert_eq!(vball.qpos.len(), 4);
2984        assert_eq!(vball.qvel.len(), 3);
2985        assert_eq!(vslide.qpos.len(), 1);
2986        assert_eq!(vslide.qvel.len(), 1);
2987
2988        // Total should equal model nq and nv
2989        assert_eq!(model.ffi().nq as usize, 7 + 4 + 1);
2990        assert_eq!(model.ffi().nv as usize, 6 + 3 + 1);
2991    }
2992
2993    /// Tests `info_method!` stride correctness for body data views:
2994    /// xpos=3, xmat=9, xquat=4, cinert=10, cvel=6.
2995    #[test]
2996    fn test_body_data_view_stride_lengths() {
2997        let model = MjModel::from_xml_string(MODEL).unwrap();
2998        let data = model.make_data();
2999
3000        let ball = data.body("ball").unwrap();
3001        let ball2 = data.body("ball2").unwrap();
3002
3003        let v1 = ball.view(&data);
3004        let v2 = ball2.view(&data);
3005
3006        // Stride correctness
3007        assert_eq!(v1.xpos.len(), 3);
3008        assert_eq!(v1.xmat.len(), 9);
3009        assert_eq!(v1.xquat.len(), 4);
3010        assert_eq!(v1.cinert.len(), 10);
3011        assert_eq!(v1.cvel.len(), 6);
3012
3013        // Non-aliasing: different bodies must have distinct slices
3014        assert_ne!(v1.xpos.as_ptr(), v2.xpos.as_ptr());
3015        assert_ne!(v1.cvel.as_ptr(), v2.cvel.as_ptr());
3016    }
3017
3018    /// Tests `getter_setter!` for MjtNum time: set, get, and builder roundtrip.
3019    #[test]
3020    fn test_time_getter_setter_roundtrip() {
3021        let model = MjModel::from_xml_string(MODEL).unwrap();
3022        let mut data = model.make_data();
3023
3024        assert_relative_eq!(data.time(), 0.0, epsilon = 1e-15);
3025
3026        data.set_time(std::f64::consts::PI);
3027        assert_relative_eq!(data.time(), std::f64::consts::PI, epsilon = 1e-15);
3028
3029        let data2 = model.make_data().with_time(std::f64::consts::E);
3030        assert_relative_eq!(data2.time(), std::f64::consts::E, epsilon = 1e-15);
3031    }
3032
3033    /// Tests that `jac` returns `IndexOutOfBounds` for invalid body IDs.
3034    #[test]
3035    fn test_jac_invalid_body_id() {
3036        let model = MjModel::from_xml_string(MODEL).unwrap();
3037        let data = model.make_data();
3038        let point = [0.0; 3];
3039
3040        // Too-large ID
3041        let err = data.try_jac(true, true, &point, 9999).unwrap_err();
3042        assert!(matches!(err, MjDataError::IndexOutOfBounds { kind: "body_id", .. }));
3043    }
3044
3045    /// Tests that `object_velocity` returns `UnsupportedObjectType` for unsupported types
3046    /// and `IndexOutOfBounds` for out-of-range IDs.
3047    #[test]
3048    fn test_object_velocity_error_paths() {
3049        let model = MjModel::from_xml_string(MODEL).unwrap();
3050        let data = model.make_data();
3051
3052        // Unsupported type (mjOBJ_JOINT is not in the match arms)
3053        let err = data.try_object_velocity(MjtObj::mjOBJ_JOINT, 0, false).unwrap_err();
3054        assert!(matches!(err, MjDataError::UnsupportedObjectType(_)));
3055
3056        // Out-of-range body ID
3057        let err = data.try_object_velocity(MjtObj::mjOBJ_BODY, 9999, false).unwrap_err();
3058        assert!(matches!(err, MjDataError::IndexOutOfBounds { kind: "obj_id", .. }));
3059    }
3060
3061    /// Tests that state flags select only their subset: setting QPOS must not clobber qvel.
3062    #[test]
3063    fn test_state_spec_flags_select_subsets() {
3064        let model = MjModel::from_xml_string(MODEL).unwrap();
3065        let mut data = model.make_data();
3066
3067        // Give data some known non-zero qvel
3068        let jinfo = data.joint("ball").unwrap();
3069        jinfo.view_mut(&mut data).qvel[0] = 42.0;
3070        let original_qvel0 = jinfo.view(&data).qvel[0];
3071
3072        // Now overwrite only QPOS from a fresh data instance
3073        let fresh = model.make_data();
3074        data.copy_state_from_data(&fresh, MjtState::mjSTATE_QPOS as u32).unwrap();
3075
3076        // qvel should be untouched
3077        assert_relative_eq!(jinfo.view(&data).qvel[0], original_qvel0, epsilon = 1e-15);
3078    }
3079
3080    /// Tests `copy_state_from_data` returns `SignatureMismatch` for mismatched models.
3081    #[test]
3082    fn test_copy_state_signature_mismatch() {
3083        let model1 = MjModel::from_xml_string("<mujoco><worldbody><body><joint type='free'/><geom size='0.1'/></body></worldbody></mujoco>").unwrap();
3084        let model2 = MjModel::from_xml_string("<mujoco><worldbody><body><joint type='slide'/><geom size='0.1'/></body></worldbody></mujoco>").unwrap();
3085
3086        let data1 = model1.make_data();
3087        let mut data2 = model2.make_data();
3088
3089        let err = data2.copy_state_from_data(&data1, MjtState::mjSTATE_FULLPHYSICS as u32).unwrap_err();
3090        match err {
3091            MjDataError::SignatureMismatch { source, destination } => {
3092                assert_ne!(source, destination);
3093            }
3094            other => panic!("expected SignatureMismatch, got {:?}", other),
3095        }
3096    }
3097
3098    /// Tests `copy_state_from_data` with full physics: time, qpos, qvel all match.
3099    #[test]
3100    fn test_copy_state_full_physics() {
3101        let model = MjModel::from_xml_string(MODEL).unwrap();
3102        let mut data1 = model.make_data();
3103        let mut data2 = model.make_data();
3104
3105        // Evolve data1
3106        data1.set_time(1.0);
3107        data1.joint("ball").unwrap().view_mut(&mut data1).qpos[0] = 5.0;
3108        data1.joint("ball").unwrap().view_mut(&mut data1).qvel[0] = 3.0;
3109
3110        data2.copy_state_from_data(&data1, MjtState::mjSTATE_FULLPHYSICS as u32).unwrap();
3111
3112        assert_relative_eq!(data2.time(), 1.0, epsilon = 1e-15);
3113        assert_relative_eq!(data2.qpos()[0], 5.0, epsilon = 1e-15);
3114        assert_relative_eq!(data2.qvel()[0], 3.0, epsilon = 1e-15);
3115    }
3116
3117    /**************************************************************************/
3118    // Force-cast macro correctness tests
3119    /**************************************************************************/
3120
3121    /// A richer model for force-cast tests: free joint, slide joint, equalities,
3122    /// mocap body, tendon, multiple geom types, sensors, contacts.
3123    const FORCE_MODEL: &str = "
3124<mujoco>
3125  <worldbody>
3126    <body name='b_free' pos='1 2 3'>
3127        <joint name='j_free' type='free'/>
3128        <geom name='g_sphere' type='sphere' size='0.1' mass='1'/>
3129    </body>
3130
3131    <body name='b_slide' pos='0 0 5'>
3132        <joint name='j_slide' type='slide' axis='0 0 1' range='-1 1' limited='true'/>
3133        <geom name='g_box' type='box' size='0.1 0.2 0.3' mass='1'/>
3134        <site name='s1' pos='0 0 0' size='0.05'/>
3135    </body>
3136
3137    <body name='b_hinge' pos='0 5 0'>
3138        <joint name='j_hinge' type='hinge' axis='0 1 0'/>
3139        <geom name='g_capsule' type='capsule' size='0.1 0.5' mass='1'/>
3140        <site name='s2' pos='0 0 0' size='0.05'/>
3141    </body>
3142
3143    <body name='mocap_body' mocap='true' pos='10 10 10'>
3144        <geom name='g_mocap' type='sphere' size='0.01' contype='0' conaffinity='0'/>
3145    </body>
3146
3147    <geom name='floor' type='plane' size='50 50 1'/>
3148  </worldbody>
3149
3150  <equality>
3151      <connect name='eq1' body1='b_slide' body2='b_hinge' anchor='0 0 0'/>
3152      <connect name='eq2' body1='b_hinge' body2='b_slide' anchor='1 2 3'/>
3153  </equality>
3154
3155  <tendon>
3156      <spatial name='ten1'>
3157          <site site='s1'/>
3158          <site site='s2'/>
3159      </spatial>
3160  </tendon>
3161
3162  <actuator>
3163      <motor name='motor_slide' joint='j_slide'/>
3164  </actuator>
3165
3166  <sensor>
3167      <touch name='touch_sensor' site='s1'/>
3168  </sensor>
3169</mujoco>";
3170
3171    /// Verifies [force]-cast array grouping: xpos returns &[[MjtNum; 3]]
3172    /// with the correct number of elements and matching raw FFI data.
3173    #[test]
3174    fn test_force_cast_xpos_array_grouping() {
3175        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3176        let mut data = model.make_data();
3177        data.forward();
3178
3179        let nbody = model.ffi().nbody as usize;
3180        let xpos = data.xpos();
3181
3182        // The force-cast from *mut f64 -> *mut [MjtNum; 3] must produce
3183        // exactly nbody elements of [f64; 3].
3184        assert_eq!(xpos.len(), nbody, "xpos slice len must equal nbody");
3185
3186        // Cross-validate every element against the raw FFI pointer.
3187        for i in 0..nbody {
3188            for j in 0..3 {
3189                let ffi_val = unsafe { *data.ffi().xpos.add(i * 3 + j) };
3190                assert_eq!(xpos[i][j], ffi_val,
3191                    "xpos[{}][{}] mismatch: slice={} ffi={}", i, j, xpos[i][j], ffi_val);
3192            }
3193        }
3194    }
3195
3196    /// Verifies [force]-cast for xmat (&[[MjtNum; 9]]) and xquat (&[[MjtNum; 4]]).
3197    #[test]
3198    fn test_force_cast_xmat_xquat_grouping() {
3199        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3200        let mut data = model.make_data();
3201        data.forward();
3202
3203        let nbody = model.ffi().nbody as usize;
3204        let xmat = data.xmat();
3205        let xquat = data.xquat();
3206
3207        assert_eq!(xmat.len(), nbody);
3208        assert_eq!(xquat.len(), nbody);
3209
3210        // xmat stride = 9
3211        for i in 0..nbody {
3212            for j in 0..9 {
3213                let ffi_val = unsafe { *data.ffi().xmat.add(i * 9 + j) };
3214                assert_eq!(xmat[i][j], ffi_val,
3215                    "xmat[{}][{}] mismatch", i, j);
3216            }
3217        }
3218
3219        // xquat stride = 4
3220        for i in 0..nbody {
3221            for j in 0..4 {
3222                let ffi_val = unsafe { *data.ffi().xquat.add(i * 4 + j) };
3223                assert_eq!(xquat[i][j], ffi_val,
3224                    "xquat[{}][{}] mismatch", i, j);
3225            }
3226        }
3227    }
3228
3229    /// Verifies [force]-cast for cinert (&[[MjtNum; 10]]) - the widest array grouping.
3230    #[test]
3231    fn test_force_cast_cinert_10_element_grouping() {
3232        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3233        let mut data = model.make_data();
3234        data.forward();
3235
3236        let nbody = model.ffi().nbody as usize;
3237        let cinert = data.cinert();
3238        assert_eq!(cinert.len(), nbody);
3239
3240        for i in 0..nbody {
3241            for j in 0..10 {
3242                let ffi_val = unsafe { *data.ffi().cinert.add(i * 10 + j) };
3243                assert_eq!(cinert[i][j], ffi_val,
3244                    "cinert[{}][{}] mismatch", i, j);
3245            }
3246        }
3247    }
3248
3249    /// Verifies [force]-cast for cvel (&[[MjtNum; 6]]) and xfrc_applied (&[[MjtNum; 6]]).
3250    #[test]
3251    fn test_force_cast_6_element_groupings() {
3252        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3253        let mut data = model.make_data();
3254        data.forward();
3255
3256        let nbody = model.ffi().nbody as usize;
3257
3258        // cvel: [MjtNum; 6]
3259        let cvel = data.cvel();
3260        assert_eq!(cvel.len(), nbody);
3261        for i in 0..nbody {
3262            for j in 0..6 {
3263                let ffi_val = unsafe { *data.ffi().cvel.add(i * 6 + j) };
3264                assert_eq!(cvel[i][j], ffi_val, "cvel[{}][{}] mismatch", i, j);
3265            }
3266        }
3267
3268        // xfrc_applied: [MjtNum; 6]
3269        let xfrc = data.xfrc_applied();
3270        assert_eq!(xfrc.len(), nbody);
3271        for i in 0..nbody {
3272            for j in 0..6 {
3273                let ffi_val = unsafe { *data.ffi().xfrc_applied.add(i * 6 + j) };
3274                assert_eq!(xfrc[i][j], ffi_val, "xfrc_applied[{}][{}] mismatch", i, j);
3275            }
3276        }
3277    }
3278
3279    /// Verifies [force]-cast for mocap_pos (&[[MjtNum; 3]]) and mocap_quat (&[[MjtNum; 4]]).
3280    #[test]
3281    fn test_force_cast_mocap_arrays() {
3282        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3283        let data = model.make_data();
3284
3285        let nmocap = model.ffi().nmocap as usize;
3286        assert!(nmocap > 0, "test model must have at least one mocap body");
3287
3288        let mocap_pos = data.mocap_pos();
3289        let mocap_quat = data.mocap_quat();
3290
3291        assert_eq!(mocap_pos.len(), nmocap);
3292        assert_eq!(mocap_quat.len(), nmocap);
3293
3294        // The mocap body was placed at pos='10 10 10'
3295        assert_relative_eq!(mocap_pos[0][0], 10.0, epsilon = 1e-9);
3296        assert_relative_eq!(mocap_pos[0][1], 10.0, epsilon = 1e-9);
3297        assert_relative_eq!(mocap_pos[0][2], 10.0, epsilon = 1e-9);
3298
3299        // Default quaternion is identity [1, 0, 0, 0]
3300        assert_relative_eq!(mocap_quat[0][0], 1.0, epsilon = 1e-9);
3301        assert_relative_eq!(mocap_quat[0][1], 0.0, epsilon = 1e-9);
3302        assert_relative_eq!(mocap_quat[0][2], 0.0, epsilon = 1e-9);
3303        assert_relative_eq!(mocap_quat[0][3], 0.0, epsilon = 1e-9);
3304
3305        // Cross-validate with FFI
3306        for i in 0..nmocap {
3307            for j in 0..3 {
3308                assert_eq!(mocap_pos[i][j], unsafe { *data.ffi().mocap_pos.add(i * 3 + j) });
3309            }
3310            for j in 0..4 {
3311                assert_eq!(mocap_quat[i][j], unsafe { *data.ffi().mocap_quat.add(i * 4 + j) });
3312            }
3313        }
3314    }
3315
3316    /// Verifies [force]-cast bool conversion: eq_active (*mut u8 -> *mut bool).
3317    #[test]
3318    fn test_force_cast_eq_active_bool() {
3319        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3320        let mut data = model.make_data();
3321
3322        let neq = model.ffi().neq as usize;
3323        assert_eq!(neq, 2, "test model must have exactly 2 equality constraints");
3324
3325        // Equality constraints are active by default
3326        let eq_active = data.eq_active();
3327        assert_eq!(eq_active.len(), neq);
3328        assert!(eq_active[0]);
3329        assert!(eq_active[1]);
3330
3331        // Cross-validate with raw u8 FFI pointer
3332        for i in 0..neq {
3333            let raw_val = unsafe { *data.ffi().eq_active.add(i) };
3334            assert_eq!(eq_active[i], raw_val,
3335                "eq_active[{}]: bool={} raw={}", i, eq_active[i], raw_val);
3336        }
3337
3338        // Disable one via mutable force-cast
3339        data.eq_active_mut()[0] = false;
3340        assert!(!data.eq_active()[0]);
3341        assert!(data.eq_active()[1]);
3342
3343        // Verify FFI side was actually modified
3344        let raw_val = unsafe { *data.ffi().eq_active.add(0) };
3345        assert!(!raw_val, "disabling eq_active[0] must write false to FFI");
3346    }
3347
3348    /// Verifies [force]-cast mutable roundtrip for xfrc_applied and mocap_pos.
3349    #[test]
3350    fn test_force_cast_mutable_roundtrip() {
3351        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3352        let mut data = model.make_data();
3353
3354        let nbody = model.ffi().nbody as usize;
3355        assert!(nbody > 1);
3356
3357        // Write a known pattern into xfrc_applied via mutable force-cast
3358        let body_idx = 1; // first non-world body
3359        data.xfrc_applied_mut()[body_idx] = [1.0, 2.0, 3.0, 4.0, 5.0, 6.0];
3360
3361        // Read back via immutable force-cast
3362        let xfrc = data.xfrc_applied();
3363        assert_eq!(xfrc[body_idx], [1.0, 2.0, 3.0, 4.0, 5.0, 6.0]);
3364
3365        // Verify all 6 elements individually against raw FFI
3366        for j in 0..6 {
3367            let ffi_val = unsafe { *data.ffi().xfrc_applied.add(body_idx * 6 + j) };
3368            assert_eq!(ffi_val, (j + 1) as f64,
3369                "xfrc_applied FFI[{}] mismatch", j);
3370        }
3371
3372        // Mocap pos write/read roundtrip
3373        let nmocap = model.ffi().nmocap as usize;
3374        if nmocap > 0 {
3375            data.mocap_pos_mut()[0] = [99.0, 88.0, 77.0];
3376            assert_eq!(data.mocap_pos()[0], [99.0, 88.0, 77.0]);
3377            for j in 0..3 {
3378                let ffi_val = unsafe { *data.ffi().mocap_pos.add(j) };
3379                assert_eq!(ffi_val, [99.0, 88.0, 77.0][j]);
3380            }
3381        }
3382    }
3383
3384    /// Verifies force-cast for body view fields (xpos, xquat, xmat, cinert, cvel)
3385    /// have the correct stride and match FFI data.
3386    #[test]
3387    fn test_force_cast_body_view_strides_and_values() {
3388        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3389        let mut data = model.make_data();
3390        data.forward();
3391
3392        let body_info = data.body("b_free").unwrap();
3393        let view = body_info.view(&data);
3394
3395        // Stride correctness (all derived from [force] grouping)
3396        assert_eq!(view.xpos.len(), 3);
3397        assert_eq!(view.xquat.len(), 4);
3398        assert_eq!(view.xmat.len(), 9);
3399        assert_eq!(view.xipos.len(), 3);
3400        assert_eq!(view.ximat.len(), 9);
3401        assert_eq!(view.cinert.len(), 10);
3402        assert_eq!(view.cvel.len(), 6);
3403        assert_eq!(view.xfrc_applied.len(), 6);
3404        assert_eq!(view.crb.len(), 10);
3405        assert_eq!(view.subtree_com.len(), 3);
3406        assert_eq!(view.subtree_linvel.len(), 3);
3407        assert_eq!(view.subtree_angmom.len(), 3);
3408        assert_eq!(view.cacc.len(), 6);
3409        assert_eq!(view.cfrc_int.len(), 6);
3410        assert_eq!(view.cfrc_ext.len(), 6);
3411
3412        // The body was placed at pos='1 2 3' with a free joint;
3413        // after forward(), xpos should reflect position from qpos
3414        let body_id = body_info.id;
3415        for j in 0..3 {
3416            let ffi_val = unsafe { *data.ffi().xpos.add(body_id * 3 + j) };
3417            assert_eq!(view.xpos[j], ffi_val,
3418                "body view xpos[{}] must match FFI xpos", j);
3419        }
3420    }
3421
3422    /// Verifies that the body data view for the world body (id=0) works correctly.
3423    /// Edge case: world body has special status in MuJoCo.
3424    #[test]
3425    fn test_force_cast_world_body_view() {
3426        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3427        let mut data = model.make_data();
3428        data.forward();
3429
3430        // The world body (id=0) has name "world" in MuJoCo >= 3.x
3431        let world_info = data.body("world").unwrap();
3432        assert_eq!(world_info.id, 0);
3433        let view = world_info.view(&data);
3434
3435        // World body xpos = [0, 0, 0]
3436        assert_eq!(view.xpos[..], [0.0, 0.0, 0.0]);
3437        // World body xquat = [1, 0, 0, 0] (identity)
3438        assert_relative_eq!(view.xquat[0], 1.0, epsilon = 1e-9);
3439        assert_relative_eq!(view.xquat[1], 0.0, epsilon = 1e-9);
3440        assert_relative_eq!(view.xquat[2], 0.0, epsilon = 1e-9);
3441        assert_relative_eq!(view.xquat[3], 0.0, epsilon = 1e-9);
3442        // Stride must still be correct
3443        assert_eq!(view.xmat.len(), 9);
3444        assert_eq!(view.cinert.len(), 10);
3445    }
3446
3447    /// Verifies mutable force-cast view roundtrip for body xfrc_applied.
3448    #[test]
3449    fn test_force_cast_body_view_mut_roundtrip() {
3450        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3451        let mut data = model.make_data();
3452
3453        let body_info = data.body("b_free").unwrap();
3454        let body_id = body_info.id;
3455
3456        // Write via view_mut
3457        body_info.view_mut(&mut data).xfrc_applied.copy_from_slice(&[10.0, 20.0, 30.0, 40.0, 50.0, 60.0]);
3458
3459        // Read back via view
3460        let view = body_info.view(&data);
3461        assert_eq!(&view.xfrc_applied[..], &[10.0, 20.0, 30.0, 40.0, 50.0, 60.0]);
3462
3463        // Read back via flat slice
3464        assert_eq!(data.xfrc_applied()[body_id], [10.0, 20.0, 30.0, 40.0, 50.0, 60.0]);
3465
3466        // Read back via FFI
3467        for j in 0..6 {
3468            let ffi_val = unsafe { *data.ffi().xfrc_applied.add(body_id * 6 + j) };
3469            assert_eq!(ffi_val, ((j + 1) * 10) as f64);
3470        }
3471    }
3472
3473    /// Verifies [force]-cast camera/light/geom/site xpos+xmat grouping in data.
3474    #[test]
3475    fn test_force_cast_geom_site_cam_light_data() {
3476        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3477        let mut data = model.make_data();
3478        data.forward();
3479
3480        // Geom xpos: [MjtNum; 3], xmat: [MjtNum; 9]
3481        let ngeom = model.ffi().ngeom as usize;
3482        assert_eq!(data.geom_xpos().len(), ngeom);
3483        assert_eq!(data.geom_xmat().len(), ngeom);
3484        for i in 0..ngeom {
3485            for j in 0..3 {
3486                assert_eq!(data.geom_xpos()[i][j],
3487                    unsafe { *data.ffi().geom_xpos.add(i * 3 + j) });
3488            }
3489            for j in 0..9 {
3490                assert_eq!(data.geom_xmat()[i][j],
3491                    unsafe { *data.ffi().geom_xmat.add(i * 9 + j) });
3492            }
3493        }
3494
3495        // Site xpos: [MjtNum; 3], xmat: [MjtNum; 9]
3496        let nsite = model.ffi().nsite as usize;
3497        assert_eq!(data.site_xpos().len(), nsite);
3498        assert_eq!(data.site_xmat().len(), nsite);
3499        for i in 0..nsite {
3500            for j in 0..3 {
3501                assert_eq!(data.site_xpos()[i][j],
3502                    unsafe { *data.ffi().site_xpos.add(i * 3 + j) });
3503            }
3504        }
3505
3506        // Cam xpos: [MjtNum; 3], xmat: [MjtNum; 9]
3507        let ncam = model.ffi().ncam as usize;
3508        assert_eq!(data.cam_xpos().len(), ncam);
3509        assert_eq!(data.cam_xmat().len(), ncam);
3510
3511        // Light xpos: [MjtNum; 3], xdir: [MjtNum; 3]
3512        let nlight = model.ffi().nlight as usize;
3513        assert_eq!(data.light_xpos().len(), nlight);
3514        assert_eq!(data.light_xdir().len(), nlight);
3515    }
3516
3517    /// Verifies [force]-cast for joint anchor/axis: xanchor (&[[MjtNum; 3]]), xaxis (&[[MjtNum; 3]]).
3518    #[test]
3519    fn test_force_cast_joint_anchor_axis() {
3520        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3521        let mut data = model.make_data();
3522        data.forward();
3523
3524        let njnt = model.ffi().njnt as usize;
3525        let xanchor = data.xanchor();
3526        let xaxis = data.xaxis();
3527
3528        assert_eq!(xanchor.len(), njnt);
3529        assert_eq!(xaxis.len(), njnt);
3530
3531        for i in 0..njnt {
3532            for j in 0..3 {
3533                assert_eq!(xanchor[i][j], unsafe { *data.ffi().xanchor.add(i * 3 + j) });
3534                assert_eq!(xaxis[i][j], unsafe { *data.ffi().xaxis.add(i * 3 + j) });
3535            }
3536        }
3537    }
3538
3539    /// Verifies [force]-cast for cdof (&[[MjtNum; 6]]) and cdof_dot (&[[MjtNum; 6]]).
3540    #[test]
3541    fn test_force_cast_cdof_6_element() {
3542        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3543        let mut data = model.make_data();
3544        data.forward();
3545
3546        let nv = model.ffi().nv as usize;
3547        let cdof = data.cdof();
3548        let cdof_dot = data.cdof_dot();
3549
3550        assert_eq!(cdof.len(), nv);
3551        assert_eq!(cdof_dot.len(), nv);
3552
3553        for i in 0..nv {
3554            for j in 0..6 {
3555                assert_eq!(cdof[i][j], unsafe { *data.ffi().cdof.add(i * 6 + j) });
3556                assert_eq!(cdof_dot[i][j], unsafe { *data.ffi().cdof_dot.add(i * 6 + j) });
3557            }
3558        }
3559    }
3560
3561    /// Verifies [force]-cast for efc_KBIP (&[[MjtNum; 4]]).
3562    /// Requires contacts to produce constraint data.
3563    #[test]
3564    fn test_force_cast_efc_kbip_4_element() {
3565        // Use the main MODEL which has balls falling onto a floor -> contacts
3566        let model = MjModel::from_xml_string(MODEL).unwrap();
3567        let mut data = model.make_data();
3568
3569        // Step a few times to generate contacts
3570        for _ in 0..10 {
3571            data.step();
3572        }
3573
3574        let nefc = data.ffi().nefc as usize;
3575        if nefc > 0 {
3576            let efc_kbip = data.efc_kbip();
3577            assert_eq!(efc_kbip.len(), nefc);
3578            for i in 0..nefc {
3579                for j in 0..4 {
3580                    assert_eq!(efc_kbip[i][j], unsafe { *data.ffi().efc_KBIP.add(i * 4 + j) });
3581                }
3582            }
3583        }
3584    }
3585
3586    /// Verifies [force]-cast enum: efc_type (*mut i32 -> *mut MjtConstraint).
3587    #[test]
3588    fn test_force_cast_efc_type_enum() {
3589        let model = MjModel::from_xml_string(MODEL).unwrap();
3590        let mut data = model.make_data();
3591
3592        for _ in 0..10 {
3593            data.step();
3594        }
3595
3596        let nefc = data.ffi().nefc as usize;
3597        if nefc > 0 {
3598            let efc_type = data.efc_type();
3599            assert_eq!(efc_type.len(), nefc);
3600
3601            for i in 0..nefc {
3602                let raw_i32 = unsafe { *data.ffi().efc_type.add(i) };
3603                let expected: MjtConstraint = unsafe { crate::util::force_cast(raw_i32) };
3604                assert_eq!(efc_type[i], expected,
3605                    "efc_type[{}]: got {:?}, expected {:?} (raw={})", i, efc_type[i], expected, raw_i32);
3606            }
3607        }
3608    }
3609
3610    /// Verifies [force]-cast enum: efc_state (*mut i32 -> *mut MjtConstraintState).
3611    #[test]
3612    fn test_force_cast_efc_state_enum() {
3613        let model = MjModel::from_xml_string(MODEL).unwrap();
3614        let mut data = model.make_data();
3615        data.forward();
3616
3617        let nefc = data.ffi().nefc as usize;
3618        if nefc > 0 {
3619            let efc_state = data.efc_state();
3620            assert_eq!(efc_state.len(), nefc);
3621
3622            for i in 0..nefc {
3623                let raw_i32 = unsafe { *data.ffi().efc_state.add(i) };
3624                let expected: MjtConstraintState = unsafe { crate::util::force_cast(raw_i32) };
3625                assert_eq!(efc_state[i], expected);
3626            }
3627        }
3628    }
3629
3630    /// Verifies [force]-cast enum: body_awake (*mut i32 -> *mut MjtSleepState).
3631    #[test]
3632    fn test_force_cast_body_awake_enum() {
3633        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3634        let mut data = model.make_data();
3635        data.forward();
3636
3637        let nbody = model.ffi().nbody as usize;
3638        let body_awake = data.body_awake();
3639        assert_eq!(body_awake.len(), nbody);
3640
3641        for i in 0..nbody {
3642            let raw_i32 = unsafe { *data.ffi().body_awake.add(i) };
3643            let expected: MjtSleepState = unsafe { crate::util::force_cast(raw_i32) };
3644            assert_eq!(body_awake[i], expected,
3645                "body_awake[{}] mismatch", i);
3646        }
3647    }
3648
3649    /// Verifies [force]-cast for bvh_active (*mut u8 -> *mut bool) and that
3650    /// the result is valid (true or false, no garbage).
3651    #[test]
3652    fn test_force_cast_bvh_active_bool() {
3653        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3654        let mut data = model.make_data();
3655
3656        // Step to populate bvh
3657        data.step();
3658
3659        let nbvh = model.ffi().nbvh as usize;
3660        let bvh_active = data.bvh_active();
3661        assert_eq!(bvh_active.len(), nbvh);
3662
3663        for i in 0..nbvh {
3664            let raw_bool = unsafe { *data.ffi().bvh_active.add(i) };
3665            assert_eq!(bvh_active[i], raw_bool);
3666        }
3667    }
3668
3669    /// Verifies [force]-cast for wrap_obj (&[[i32; 2]]) and wrap_xpos (&[[MjtNum; 6]]).
3670    #[test]
3671    fn test_force_cast_wrap_arrays() {
3672        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3673        let mut data = model.make_data();
3674        data.forward();
3675
3676        let nwrap = model.ffi().nwrap as usize;
3677        let wrap_obj = data.wrap_obj();
3678        let wrap_xpos = data.wrap_xpos();
3679
3680        assert_eq!(wrap_obj.len(), nwrap);
3681        assert_eq!(wrap_xpos.len(), nwrap);
3682
3683        for i in 0..nwrap {
3684            for j in 0..2 {
3685                assert_eq!(wrap_obj[i][j], unsafe { *data.ffi().wrap_obj.add(i * 2 + j) });
3686            }
3687            for j in 0..6 {
3688                assert_eq!(wrap_xpos[i][j], unsafe { *data.ffi().wrap_xpos.add(i * 6 + j) });
3689            }
3690        }
3691    }
3692
3693    /// Verifies [force]-cast for flexvert_J (&[[MjtNum; 2]]) and flexvert_length (&[[MjtNum; 2]]).
3694    /// In a model with no flexes, these should return empty slices.
3695    #[test]
3696    fn test_force_cast_flex_empty_slices() {
3697        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3698        let data = model.make_data();
3699
3700        // Model has no flexes, so these should be empty
3701        assert!(data.flexvert_xpos().is_empty(), "no flex -> empty flexvert_xpos");
3702        assert!(data.flexelem_aabb().is_empty(), "no flex -> empty flexelem_aabb");
3703        assert!(data.flexvert_j().is_empty(), "no flex -> empty flexvert_J");
3704        assert!(data.flexvert_length().is_empty(), "no flex -> empty flexvert_length");
3705        assert!(data.flexedge_j().is_empty(), "no flex -> empty flexedge_J");
3706        assert!(data.flexedge_length().is_empty(), "no flex -> empty flexedge_length");
3707    }
3708
3709    /// Verifies [force]-cast for bvh_aabb_dyn (&[[MjtNum; 6]]).
3710    #[test]
3711    fn test_force_cast_bvh_aabb_dyn() {
3712        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3713        let mut data = model.make_data();
3714        data.forward();
3715
3716        let nbvhdyn = model.ffi().nbvhdynamic as usize;
3717        let aabb_dyn = data.bvh_aabb_dyn();
3718        assert_eq!(aabb_dyn.len(), nbvhdyn);
3719
3720        for i in 0..nbvhdyn {
3721            for j in 0..6 {
3722                assert_eq!(aabb_dyn[i][j], unsafe { *data.ffi().bvh_aabb_dyn.add(i * 6 + j) });
3723            }
3724        }
3725    }
3726
3727    /// Verifies [force]-cast for subtree arrays: subtree_com, subtree_linvel, subtree_angmom
3728    /// all with stride 3.
3729    #[test]
3730    fn test_force_cast_subtree_3_element() {
3731        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3732        let mut data = model.make_data();
3733        data.forward();
3734
3735        let nbody = model.ffi().nbody as usize;
3736
3737        let subtree_com = data.subtree_com();
3738        let subtree_linvel = data.subtree_linvel();
3739        let subtree_angmom = data.subtree_angmom();
3740
3741        assert_eq!(subtree_com.len(), nbody);
3742        assert_eq!(subtree_linvel.len(), nbody);
3743        assert_eq!(subtree_angmom.len(), nbody);
3744
3745        for i in 0..nbody {
3746            for j in 0..3 {
3747                assert_eq!(subtree_com[i][j], unsafe { *data.ffi().subtree_com.add(i * 3 + j) });
3748            }
3749        }
3750    }
3751
3752    /// Verifies [force]-cast consistency: body view xfrc_applied matches flat slice.
3753    /// This catches any stride/offset mismatch between view_creator! and array_slice_dyn!.
3754    #[test]
3755    fn test_force_cast_view_vs_flat_slice_consistency() {
3756        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3757        let mut data = model.make_data();
3758        data.forward();
3759
3760        // Check every named body: view xpos must equal flat xpos slice
3761        let body_names = ["world", "b_free", "b_slide", "b_hinge", "mocap_body"];
3762        for name in &body_names {
3763            let info = data.body(name).unwrap();
3764            let id = info.id;
3765            let view = info.view(&data);
3766            let flat = data.xpos();
3767
3768            for j in 0..3 {
3769                assert_eq!(view.xpos[j], flat[id][j],
3770                    "body {} xpos[{}]: view={} flat={}", id, j, view.xpos[j], flat[id][j]);
3771            }
3772
3773            for j in 0..4 {
3774                assert_eq!(view.xquat[j], data.xquat()[id][j],
3775                    "body {} xquat[{}] mismatch", id, j);
3776            }
3777
3778            for j in 0..10 {
3779                assert_eq!(view.cinert[j], data.cinert()[id][j],
3780                    "body {} cinert[{}] mismatch", id, j);
3781            }
3782        }
3783    }
3784
3785    /// Verifies [force]-cast for the cacc/cfrc_int/cfrc_ext body arrays (stride 6).
3786    #[test]
3787    fn test_force_cast_body_cfrc_arrays() {
3788        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3789        let mut data = model.make_data();
3790        data.forward();
3791
3792        let nbody = model.ffi().nbody as usize;
3793        let cacc = data.cacc();
3794        let cfrc_int = data.cfrc_int();
3795        let cfrc_ext = data.cfrc_ext();
3796
3797        assert_eq!(cacc.len(), nbody);
3798        assert_eq!(cfrc_int.len(), nbody);
3799        assert_eq!(cfrc_ext.len(), nbody);
3800
3801        for i in 0..nbody {
3802            for j in 0..6 {
3803                assert_eq!(cacc[i][j], unsafe { *data.ffi().cacc.add(i * 6 + j) });
3804                assert_eq!(cfrc_int[i][j], unsafe { *data.ffi().cfrc_int.add(i * 6 + j) });
3805                assert_eq!(cfrc_ext[i][j], unsafe { *data.ffi().cfrc_ext.add(i * 6 + j) });
3806            }
3807        }
3808    }
3809
3810    /// Verifies [force]-cast for crb (&[[MjtNum; 10]]).
3811    #[test]
3812    fn test_force_cast_crb_10_element() {
3813        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3814        let mut data = model.make_data();
3815        data.forward();
3816
3817        let nbody = model.ffi().nbody as usize;
3818        let crb = data.crb();
3819        assert_eq!(crb.len(), nbody);
3820
3821        for i in 0..nbody {
3822            for j in 0..10 {
3823                assert_eq!(crb[i][j], unsafe { *data.ffi().crb.add(i * 10 + j) });
3824            }
3825        }
3826    }
3827
3828    /// Minimal model test: a model with zero equalities, zero tendons, zero actuators
3829    /// should produce empty slices for all force-cast fields that depend on those counts.
3830    #[test]
3831    fn test_force_cast_empty_model_edge_case() {
3832        let xml = "<mujoco><worldbody><body><joint type='free'/><geom size='0.1'/></body></worldbody></mujoco>";
3833        let model = MjModel::from_xml_string(xml).unwrap();
3834        let data = model.make_data();
3835
3836        assert_eq!(model.ffi().neq, 0);
3837        assert_eq!(model.ffi().nmocap, 0);
3838        assert_eq!(model.ffi().ntendon, 0);
3839
3840        // Empty force-cast slices
3841        assert!(data.eq_active().is_empty());
3842        assert!(data.mocap_pos().is_empty());
3843        assert!(data.mocap_quat().is_empty());
3844        assert!(data.wrap_obj().is_empty());
3845        assert!(data.wrap_xpos().is_empty());
3846        assert!(data.ten_j().is_empty());
3847        assert!(model.ten_j_colind().is_empty());
3848        assert!(model.ten_j_rownnz().is_empty());
3849        assert!(model.ten_j_rowadr().is_empty());
3850        assert_eq!(model.ffi().nJten, 0);
3851
3852        // But body arrays should still work (nbody >= 1 always: world body)
3853        let nbody = model.ffi().nbody as usize;
3854        assert!(nbody >= 2); // world + one body
3855        assert_eq!(data.xpos().len(), nbody);
3856        assert_eq!(data.xquat().len(), nbody);
3857        assert_eq!(data.cinert().len(), nbody);
3858    }
3859
3860    /// Sparse ten_J and model sparsity fields cross-validated against raw FFI pointers.
3861    #[test]
3862    fn test_sparse_ten_j() {
3863        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3864        let mut data = model.make_data();
3865        data.forward();
3866
3867        let ntendon = model.ffi().ntendon as usize;
3868        let njten = model.ffi().nJten as usize;
3869        assert!(ntendon > 0);
3870        assert!(njten > 0);
3871
3872        let ten_j = data.ten_j();
3873        let ten_j_colind = model.ten_j_colind();
3874        assert_eq!(ten_j.len(), njten);
3875        assert_eq!(ten_j_colind.len(), njten);
3876        assert_eq!(model.ten_j_rownnz().len(), ntendon);
3877        assert_eq!(model.ten_j_rowadr().len(), ntendon);
3878
3879        for i in 0..njten {
3880            assert_eq!(ten_j[i], unsafe { *data.ffi().ten_J.add(i) });
3881            assert_eq!(ten_j_colind[i], unsafe { *model.ffi().ten_J_colind.add(i) });
3882        }
3883    }
3884
3885    /// Checks sparse ten_J against `dir^T * (J_s2 - J_s1)` from jac_site at the
3886    /// default pose and after 50 gravity steps. Both flat and view APIs are tested.
3887    #[test]
3888    fn test_ten_j_vs_jac_site() {
3889        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3890        let mut data = model.make_data();
3891        let nv = model.nv() as usize;
3892
3893        let s1_id = model.name_to_id(MjtObj::mjOBJ_SITE, "s1").unwrap();
3894        let s2_id = model.name_to_id(MjtObj::mjOBJ_SITE, "s2").unwrap();
3895
3896        for config in 0..2 {
3897            if config == 0 {
3898                data.forward();
3899            } else {
3900                for _ in 0..50 { data.step(); }
3901            }
3902
3903            let ten_j = data.ten_j();
3904            let rownnz = model.ten_j_rownnz();
3905            let rowadr = model.ten_j_rowadr();
3906            let colind = model.ten_j_colind();
3907
3908            let (jacp_s1, _) = data.jac_site(true, false, s1_id);
3909            let (jacp_s2, _) = data.jac_site(true, false, s2_id);
3910
3911            let p1 = data.site_xpos()[s1_id];
3912            let p2 = data.site_xpos()[s2_id];
3913            let diff = [p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]];
3914            let length = (diff[0] * diff[0] + diff[1] * diff[1] + diff[2] * diff[2]).sqrt();
3915            assert!(length > 1e-10);
3916            let dir = [diff[0] / length, diff[1] / length, diff[2] / length];
3917
3918            // J_ten[j] = sum_k dir[k] * (J_s2[k,j] - J_s1[k,j])
3919            let mut expected = vec![0.0 as MjtNum; nv];
3920            for j in 0..nv {
3921                for k in 0..3 {
3922                    expected[j] += dir[k] * (jacp_s2[k * nv + j] - jacp_s1[k * nv + j]);
3923                }
3924            }
3925
3926            // Sparse -> dense
3927            let nnz = rownnz[0] as usize;
3928            let adr = rowadr[0] as usize;
3929            assert!(nnz > 0);
3930            let mut actual = vec![0.0 as MjtNum; nv];
3931            for k in 0..nnz {
3932                actual[colind[adr + k] as usize] = ten_j[adr + k];
3933            }
3934
3935            let max_abs = actual.iter().map(|v| v.abs()).fold(0.0f64, f64::max);
3936            assert!(max_abs > 0.1, "config {config}: max |J| = {max_abs}");
3937            for j in 0..nv {
3938                assert_relative_eq!(actual[j], expected[j], epsilon = 1e-10);
3939            }
3940
3941            // Same check via view API
3942            let ten_view = data.tendon("ten1").unwrap().view(&data);
3943            let model_view = model.tendon("ten1").unwrap().view(&model);
3944            let view_nnz = model_view.J_rownnz[0] as usize;
3945            let mut view_dense = vec![0.0 as MjtNum; nv];
3946            for k in 0..view_nnz {
3947                view_dense[model_view.J_colind[k] as usize] = ten_view.J[k];
3948            }
3949            for j in 0..nv {
3950                assert_relative_eq!(view_dense[j], expected[j], epsilon = 1e-10);
3951            }
3952
3953            // Tendon length: view == flat == Euclidean distance
3954            let ten_info = data.tendon("ten1").unwrap();
3955            assert_relative_eq!(ten_view.length[0], data.ten_length()[ten_info.id], epsilon = 1e-15);
3956            assert_relative_eq!(ten_view.length[0], length, epsilon = 1e-10);
3957        }
3958    }
3959
3960    /// Tendon data view's J matches the flat ten_j() sparse array; model view's
3961    /// J_rownnz/J_rowadr/J_colind match their flat counterparts.
3962    #[test]
3963    fn test_tendon_view_j_fields() {
3964        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
3965        let mut data = model.make_data();
3966        data.forward();
3967
3968        let flat_j = data.ten_j();
3969        let flat_rownnz = model.ten_j_rownnz();
3970        let flat_rowadr = model.ten_j_rowadr();
3971        let flat_colind = model.ten_j_colind();
3972
3973        let ten_info = data.tendon("ten1").unwrap();
3974        let ten_view = ten_info.view(&data);
3975        let nnz = flat_rownnz[ten_info.id] as usize;
3976        let adr = flat_rowadr[ten_info.id] as usize;
3977        assert_eq!(ten_view.J.len(), nnz);
3978
3979        let mut any_nonzero = false;
3980        for k in 0..nnz {
3981            assert_eq!(ten_view.J[k], flat_j[adr + k]);
3982            any_nonzero |= ten_view.J[k].abs() > 1e-12;
3983        }
3984        assert!(any_nonzero);
3985
3986        let model_info = model.tendon("ten1").unwrap();
3987        let model_view = model_info.view(&model);
3988        assert_eq!(model_view.J_rownnz[0], flat_rownnz[model_info.id]);
3989        assert_eq!(model_view.J_rowadr[0], flat_rowadr[model_info.id]);
3990        assert_eq!(model_view.J_colind.len(), nnz);
3991        for k in 0..nnz {
3992            assert_eq!(model_view.J_colind[k], flat_colind[adr + k]);
3993        }
3994    }
3995
3996    /// Read-only fields in mutable tendon views can only be mutated via explicit unsafe API.
3997    #[test]
3998    fn test_tendon_data_view_ro_field_unsafe_mutation_api() {
3999        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4000        let mut data = model.make_data();
4001        data.forward();
4002
4003        let tendon_info = data.tendon("ten1").unwrap();
4004        let tendon_id = tendon_info.id;
4005        let original;
4006
4007        {
4008            let tendon_view = tendon_info.view(&data);
4009            assert!(!tendon_view.wrapadr.is_empty(), "expected non-empty tendon wrapadr for FORCE_MODEL::ten1");
4010            original = tendon_view.wrapadr[0];
4011        }
4012
4013        let temporary = if original == i32::MAX { i32::MIN } else { original + 1 };
4014        assert_ne!(temporary, original);
4015
4016        // SAFETY: This intentionally exercises the explicit unsafe mutation
4017        // entrypoint and validates the write via independent flat accessors.
4018        {
4019            let mut tendon_view_mut = tendon_info.view_mut(&mut data);
4020            unsafe {
4021                tendon_view_mut.wrapadr.as_mut_slice()[0] = temporary;
4022            }
4023        }
4024        assert_eq!(data.ten_wrapadr()[tendon_id], temporary);
4025
4026        // SAFETY: Restore original value before any further simulation use.
4027        {
4028            let mut tendon_view_mut = tendon_info.view_mut(&mut data);
4029            unsafe {
4030                tendon_view_mut.wrapadr.as_mut_slice()[0] = original;
4031            }
4032        }
4033
4034        assert_eq!(data.ten_wrapadr()[tendon_id], original);
4035    }
4036
4037    /// Checks `ten_velocity == J_ten @ qvel` with several qvel patterns across
4038    /// evolving simulation states, via both flat and view APIs.
4039    #[test]
4040    fn test_ten_j_velocity_transform() {
4041        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4042        let mut data = model.make_data();
4043        let ntendon = model.ntendon() as usize;
4044        assert!(ntendon > 0);
4045
4046        // nv=8 in FORCE_MODEL: free(6) + slide(1) + hinge(1)
4047        let qvel_patterns: &[&[MjtNum]] = &[
4048            &[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5, -0.7],
4049            &[0.1, -0.2, 0.3, 0.5, -0.1, 0.4, 0.0, 0.0],
4050            &[0.5, 0.0, -0.3, 0.0, 0.0, 0.0, 2.0, 1.0],
4051        ];
4052
4053        for (round, &qv) in qvel_patterns.iter().enumerate() {
4054            if round == 0 {
4055                data.forward();
4056            } else {
4057                for _ in 0..20 { data.step(); }
4058            }
4059
4060            data.qvel_mut().copy_from_slice(qv);
4061            data.forward();
4062
4063            let ten_j = data.ten_j();
4064            let rownnz = model.ten_j_rownnz();
4065            let rowadr = model.ten_j_rowadr();
4066            let colind = model.ten_j_colind();
4067            let qvel = data.qvel();
4068            let ten_vel = data.ten_velocity();
4069
4070            for t in 0..ntendon {
4071                let nnz = rownnz[t] as usize;
4072                let adr = rowadr[t] as usize;
4073                let dot: MjtNum = (0..nnz)
4074                    .map(|k| ten_j[adr + k] * qvel[colind[adr + k] as usize])
4075                    .sum();
4076                assert_relative_eq!(dot, ten_vel[t], epsilon = 1e-10);
4077            }
4078
4079            // Same identity through the view API
4080            let ten_view = data.tendon("ten1").unwrap().view(&data);
4081            let model_view = model.tendon("ten1").unwrap().view(&model);
4082            let view_nnz = model_view.J_rownnz[0] as usize;
4083            let view_dot: MjtNum = (0..view_nnz)
4084                .map(|k| ten_view.J[k] * qvel[model_view.J_colind[k] as usize])
4085                .sum();
4086            assert_relative_eq!(view_dot, ten_view.velocity[0], epsilon = 1e-10);
4087
4088            let ten_info = data.tendon("ten1").unwrap();
4089            assert_relative_eq!(ten_view.velocity[0], ten_vel[ten_info.id], epsilon = 1e-10);
4090        }
4091
4092        let max_vel = data.ten_velocity().iter().map(|v| v.abs()).fold(0.0f64, f64::max);
4093        assert!(max_vel > 0.1, "max |ten_velocity| = {max_vel}");
4094    }
4095
4096    /// Slide (x) + hinge (y) with the hinge site offset from the rotation axis so
4097    /// both DOFs contribute non-trivially. nv = 2, s1 at origin, s2 at (1,0,3).
4098    const TENDON_JAC_MODEL: &str = "
4099<mujoco>
4100  <worldbody>
4101    <body name='b1'>
4102      <joint name='j_slide' type='slide' axis='1 0 0'/>
4103      <geom type='sphere' size='0.1' mass='1'/>
4104      <site name='s1' pos='0 0 0'/>
4105    </body>
4106    <body name='b2' pos='0 0 3'>
4107      <joint name='j_hinge' type='hinge' axis='0 1 0'/>
4108      <geom type='sphere' size='0.1' mass='1'/>
4109      <site name='s2' pos='1 0 0'/>
4110    </body>
4111  </worldbody>
4112  <tendon>
4113    <spatial name='ten1'>
4114      <site site='s1'/>
4115      <site site='s2'/>
4116    </spatial>
4117  </tendon>
4118</mujoco>";
4119
4120    /// Analytical tendon Jacobian verification at three joint-space configurations,
4121    /// testing per-DOF and combined velocity transforms via both flat and view APIs.
4122    #[test]
4123    fn test_ten_j_numerical_correctness() {
4124        let model = MjModel::from_xml_string(TENDON_JAC_MODEL).unwrap();
4125        let mut data = model.make_data();
4126        let nv = model.nv() as usize;
4127        assert_eq!(nv, 2);
4128
4129        let s1_id = model.name_to_id(MjtObj::mjOBJ_SITE, "s1").unwrap();
4130        let s2_id = model.name_to_id(MjtObj::mjOBJ_SITE, "s2").unwrap();
4131
4132        let to_dense = |data: &MjData<_>, model: &MjModel| -> Vec<MjtNum> {
4133            let ten_j = data.ten_j();
4134            let nnz = model.ten_j_rownnz()[0] as usize;
4135            let adr = model.ten_j_rowadr()[0] as usize;
4136            let colind = model.ten_j_colind();
4137            let mut dense = vec![0.0 as MjtNum; nv];
4138            for k in 0..nnz {
4139                dense[colind[adr + k] as usize] = ten_j[adr + k];
4140            }
4141            dense
4142        };
4143
4144        let to_dense_view = |data: &MjData<_>, model: &MjModel| -> Vec<MjtNum> {
4145            let ten_view = data.tendon("ten1").unwrap().view(data);
4146            let model_view = model.tendon("ten1").unwrap().view(model);
4147            let view_nnz = model_view.J_rownnz[0] as usize;
4148            let mut dense = vec![0.0 as MjtNum; nv];
4149            for k in 0..view_nnz {
4150                dense[model_view.J_colind[k] as usize] = ten_view.J[k];
4151            }
4152            dense
4153        };
4154
4155        // J_ten[j] = dir . (J_s2[:,j] - J_s1[:,j])
4156        let from_jac_site = |data: &MjData<_>| -> Vec<MjtNum> {
4157            let p1 = data.site_xpos()[s1_id];
4158            let p2 = data.site_xpos()[s2_id];
4159            let d = [p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]];
4160            let len = (d[0] * d[0] + d[1] * d[1] + d[2] * d[2]).sqrt();
4161            let dir = [d[0] / len, d[1] / len, d[2] / len];
4162            let (jp1, _) = data.jac_site(true, false, s1_id);
4163            let (jp2, _) = data.jac_site(true, false, s2_id);
4164            let mut expected = vec![0.0 as MjtNum; nv];
4165            for j in 0..nv {
4166                let mut v: MjtNum = 0.0;
4167                for k in 0..3 {
4168                    v += dir[k] * (jp2[k * nv + j] - jp1[k * nv + j]);
4169                }
4170                expected[j] = v;
4171            }
4172            expected
4173        };
4174
4175        let check_j = |data: &MjData<_>, expected: &[MjtNum; 2]| {
4176            let dense = to_dense(data, &model);
4177            let dense_v = to_dense_view(data, &model);
4178            let from_jac = from_jac_site(data);
4179            for j in 0..nv {
4180                assert_relative_eq!(dense[j], expected[j], epsilon = 1e-10);
4181                assert_relative_eq!(dense_v[j], expected[j], epsilon = 1e-10);
4182                assert_relative_eq!(from_jac[j], expected[j], epsilon = 1e-10);
4183            }
4184        };
4185
4186        let check_vel = |data: &MjData<_>, expected: MjtNum| {
4187            assert_relative_eq!(data.ten_velocity()[0], expected, epsilon = 1e-10);
4188            let v = data.tendon("ten1").unwrap().view(data);
4189            assert_relative_eq!(v.velocity[0], expected, epsilon = 1e-10);
4190        };
4191
4192        // Default config: s1=(0,0,0), s2=(1,0,3), dir=(1,0,3)/sqrt(10)
4193        // Slide (x): J[0] = dir.(-1,0,0) = -1/sqrt(10)
4194        // Hinge (y at pivot (0,0,3)): r=(1,0,0), omega x r = (0,0,-1), J[1] = -3/sqrt(10)
4195        data.forward();
4196        let sqrt10 = 10.0f64.sqrt();
4197        check_j(&data, &[-1.0 / sqrt10, -3.0 / sqrt10]);
4198
4199        data.qvel_mut().copy_from_slice(&[1.0, 0.0]);
4200        data.forward();
4201        check_vel(&data, -1.0 / sqrt10);
4202
4203        data.qvel_mut().copy_from_slice(&[0.0, 1.0]);
4204        data.forward();
4205        check_vel(&data, -3.0 / sqrt10);
4206
4207        // qvel=(2,-0.5) -> vel = -2/sqrt10 + 1.5/sqrt10 = -0.5/sqrt10
4208        data.qvel_mut().copy_from_slice(&[2.0, -0.5]);
4209        data.forward();
4210        check_vel(&data, -0.5 / sqrt10);
4211
4212        // Hinge at pi/4: s2 = (cos, 0, 3-sin), r = (cos, 0, -sin)
4213        // omega x r = (0,1,0) x (cos,0,-sin) = (-sin, 0, -cos)
4214        let a = std::f64::consts::FRAC_PI_4;
4215        let (c, s) = (a.cos(), a.sin());
4216        data.qpos_mut()[1] = a;
4217        data.qvel_mut().copy_from_slice(&[0.0; 2]);
4218        data.forward();
4219
4220        let len2 = (c * c + (3.0 - s) * (3.0 - s)).sqrt();
4221        let dir2 = [c / len2, 0.0, (3.0 - s) / len2];
4222        let j_slide = -dir2[0];
4223        let j_hinge = dir2[0] * (-s) + dir2[2] * (-c);
4224        check_j(&data, &[j_slide, j_hinge]);
4225        assert!(j_slide.abs() > 0.05);
4226        assert!(j_hinge.abs() > 0.05);
4227
4228        data.qvel_mut().copy_from_slice(&[1.0, 0.0]);
4229        data.forward();
4230        check_vel(&data, j_slide);
4231
4232        data.qvel_mut().copy_from_slice(&[0.0, 1.0]);
4233        data.forward();
4234        check_vel(&data, j_hinge);
4235
4236        data.qvel_mut().copy_from_slice(&[-1.0, 3.0]);
4237        data.forward();
4238        check_vel(&data, -j_slide + 3.0 * j_hinge);
4239
4240        // Hinge at -pi/3 + slide at 0.5: s1=(0.5,0,0),
4241        // s2=(cos(-pi/3), 0, 3-sin(-pi/3)), r=(c3, 0, -s3)
4242        let a3 = -std::f64::consts::FRAC_PI_3;
4243        let (c3, s3) = (a3.cos(), a3.sin());
4244        data.qpos_mut().copy_from_slice(&[0.5, a3]);
4245        data.qvel_mut().copy_from_slice(&[0.0; 2]);
4246        data.forward();
4247
4248        let dx3 = c3 - 0.5;
4249        let dz3 = 3.0 - s3;
4250        let len3 = (dx3 * dx3 + dz3 * dz3).sqrt();
4251        let dir3 = [dx3 / len3, 0.0, dz3 / len3];
4252        let j_slide3 = -dir3[0];
4253        let j_hinge3 = dir3[0] * (-s3) + dir3[2] * (-c3);
4254        check_j(&data, &[j_slide3, j_hinge3]);
4255
4256        data.qvel_mut().copy_from_slice(&[1.7, -2.3]);
4257        data.forward();
4258        check_vel(&data, j_slide3 * 1.7 + j_hinge3 * (-2.3));
4259    }
4260
4261    /// Verifies [force]-cast for iefc_type and iefc_state (island-reordered constraint arrays).
4262    #[test]
4263    fn test_force_cast_island_efc_enums() {
4264        let model = MjModel::from_xml_string(MODEL).unwrap();
4265        let mut data = model.make_data();
4266
4267        for _ in 0..10 {
4268            data.step();
4269        }
4270
4271        let nefc = data.ffi().nefc as usize;
4272        if nefc > 0 {
4273            let iefc_type = data.iefc_type();
4274            let iefc_state = data.iefc_state();
4275
4276            assert_eq!(iefc_type.len(), nefc);
4277            assert_eq!(iefc_state.len(), nefc);
4278
4279            for i in 0..nefc {
4280                let raw_type = unsafe { *data.ffi().iefc_type.add(i) };
4281                let raw_state = unsafe { *data.ffi().iefc_state.add(i) };
4282                let expected_type: MjtConstraint = unsafe { crate::util::force_cast(raw_type) };
4283                let expected_state: MjtConstraintState = unsafe { crate::util::force_cast(raw_state) };
4284                assert_eq!(iefc_type[i], expected_type);
4285                assert_eq!(iefc_state[i], expected_state);
4286            }
4287        }
4288    }
4289
4290    /// Verifies [force]-cast non-aliasing: adjacent bodies' xpos slices must not overlap.
4291    #[test]
4292    fn test_force_cast_non_aliasing_adjacent_bodies() {
4293        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4294        let mut data = model.make_data();
4295        data.forward();
4296
4297        let b_free = data.body("b_free").unwrap();
4298        let b_slide = data.body("b_slide").unwrap();
4299
4300        let v_free = b_free.view(&data);
4301        let v_slide = b_slide.view(&data);
4302
4303        // Pointers must differ
4304        assert_ne!(v_free.xpos.as_ptr(), v_slide.xpos.as_ptr(),
4305            "adjacent bodies must have non-overlapping xpos");
4306        assert_ne!(v_free.cinert.as_ptr(), v_slide.cinert.as_ptr(),
4307            "adjacent bodies must have non-overlapping cinert");
4308        assert_ne!(v_free.cvel.as_ptr(), v_slide.cvel.as_ptr(),
4309            "adjacent bodies must have non-overlapping cvel");
4310
4311        // Pointer difference must equal exactly one stride
4312        let xpos_diff = unsafe { v_slide.xpos.as_ptr().offset_from(v_free.xpos.as_ptr()) };
4313        let id_diff = b_slide.id as isize - b_free.id as isize;
4314        assert_eq!(xpos_diff, id_diff * 3, "xpos pointer gap must be stride*id_diff = 3*{}", id_diff);
4315
4316        let cinert_diff = unsafe { v_slide.cinert.as_ptr().offset_from(v_free.cinert.as_ptr()) };
4317        assert_eq!(cinert_diff, id_diff * 10, "cinert pointer gap must be 10*{}", id_diff);
4318    }
4319
4320    /**************************************************************************/
4321    // Multi-timestep force-cast divergence tests
4322    /**************************************************************************/
4323
4324    /// Simulates multiple timesteps and verifies that force-cast xpos, qpos, qvel
4325    /// arrays diverge from initial state while remaining consistent with FFI.
4326    /// This exercises the force-cast pointer arithmetic across changing data.
4327    #[test]
4328    fn test_force_cast_multi_step_xpos_qpos_diverge() {
4329        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4330        let mut data = model.make_data();
4331        data.forward();
4332
4333        let nbody = model.ffi().nbody as usize;
4334        let nq = model.ffi().nq as usize;
4335        let nv = model.ffi().nv as usize;
4336
4337        // Snapshot initial values
4338        let init_xpos: Vec<[MjtNum; 3]> = data.xpos().to_vec();
4339        let init_qpos: Vec<MjtNum> = data.qpos().to_vec();
4340        let init_qvel: Vec<MjtNum> = data.qvel().to_vec();
4341
4342        assert_eq!(init_xpos.len(), nbody);
4343        assert_eq!(init_qpos.len(), nq);
4344        assert_eq!(init_qvel.len(), nv);
4345
4346        // Step 100 times -- gravity should cause free body to fall
4347        for _ in 0..100 {
4348            data.step();
4349        }
4350
4351        let post_xpos = data.xpos();
4352        let post_qpos = data.qpos();
4353        let post_qvel = data.qvel();
4354
4355        assert_eq!(post_xpos.len(), nbody);
4356        assert_eq!(post_qpos.len(), nq);
4357        assert_eq!(post_qvel.len(), nv);
4358
4359        // b_free should have fallen (z position decreased under gravity)
4360        let b_free = data.body("b_free").unwrap();
4361        assert!(post_xpos[b_free.id][2] < init_xpos[b_free.id][2],
4362            "free body should have fallen: init_z={}, post_z={}",
4363            init_xpos[b_free.id][2], post_xpos[b_free.id][2]);
4364
4365        // qpos should differ from initial
4366        assert_ne!(post_qpos, &init_qpos[..], "qpos must change after 100 steps");
4367
4368        // qvel should differ from zero (gravity accelerates bodies)
4369        let any_nonzero_vel = post_qvel.iter().any(|v| v.abs() > 1e-12);
4370        assert!(any_nonzero_vel, "qvel must have nonzero entries after gravity steps");
4371
4372        // Cross-validate post-step xpos with FFI
4373        for i in 0..nbody {
4374            for j in 0..3 {
4375                assert_eq!(post_xpos[i][j], unsafe { *data.ffi().xpos.add(i * 3 + j) },
4376                    "xpos[{}][{}] FFI mismatch after stepping", i, j);
4377            }
4378        }
4379
4380        // Cross-validate post-step qvel with FFI
4381        for i in 0..nv {
4382            assert_eq!(post_qvel[i], unsafe { *data.ffi().qvel.add(i) },
4383                "qvel[{}] FFI mismatch after stepping", i);
4384        }
4385    }
4386
4387    /// Simulates with an actuator active and verifies force-cast arrays (ctrl, qfrc_actuator,
4388    /// actuator_force) reflect the control input after multiple steps.
4389    #[test]
4390    fn test_force_cast_multi_step_actuator_ctrl() {
4391        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4392        let mut data = model.make_data();
4393
4394        // Apply control to the slide actuator
4395        data.ctrl_mut()[0] = 5.0;
4396
4397        // Step a few times to let forces propagate
4398        for _ in 0..20 {
4399            data.step();
4400        }
4401
4402        let nu = model.ffi().nu as usize;
4403        let ctrl = data.ctrl();
4404        assert_eq!(ctrl.len(), nu);
4405        assert_eq!(ctrl[0], 5.0);
4406
4407        // actuator_force should be nonzero
4408        let act_force = data.actuator_force();
4409        assert_eq!(act_force.len(), nu);
4410        assert!(act_force[0].abs() > 1e-12,
4411            "actuator_force should be nonzero with ctrl=5.0, got {}", act_force[0]);
4412
4413        // FFI cross-validation
4414        assert_eq!(act_force[0], unsafe { *data.ffi().actuator_force });
4415
4416        // qfrc_actuator should be nonzero (force applied to joint)
4417        let nv = model.ffi().nv as usize;
4418        let qfrc = data.qfrc_actuator();
4419        assert_eq!(qfrc.len(), nv);
4420        let any_nonzero = qfrc.iter().any(|v| v.abs() > 1e-12);
4421        assert!(any_nonzero, "qfrc_actuator must reflect the actuator force");
4422    }
4423
4424    /// Steps multiple times with gravity & contacts, then verifies enum force-casts
4425    /// (efc_type, efc_state) and array groupings (efc_KBIP, contact xpos/frame)
4426    /// reflect the evolved simulation state and remain FFI-consistent.
4427    #[test]
4428    fn test_force_cast_multi_step_constraints_evolve() {
4429        // MODEL has many objects that create contacts
4430        let model = MjModel::from_xml_string(MODEL).unwrap();
4431        let mut data = model.make_data();
4432
4433        // Step enough for contacts to form and constraints to be generated
4434        for _ in 0..50 {
4435            data.step();
4436        }
4437
4438        let nefc = data.ffi().nefc as usize;
4439        let ncon = data.ffi().ncon as usize;
4440
4441        // With a rich model and 50 steps, we expect contacts
4442        // (not guaranteed in every model, but MODEL has spheres falling on a plane)
4443        if ncon > 0 {
4444            // Contact positions (xpos) should have changed
4445            let contacts = data.contact();
4446            assert_eq!(contacts.len(), ncon);
4447            for c in contacts {
4448                // Each contact's pos is a [f64; 3]
4449                let pos_nonzero = c.pos.iter().any(|v| v.abs() > 1e-12);
4450                assert!(pos_nonzero, "contact pos should be nonzero for an active contact");
4451            }
4452        }
4453
4454        if nefc > 0 {
4455            let efc_type = data.efc_type();
4456            let efc_state = data.efc_state();
4457            assert_eq!(efc_type.len(), nefc);
4458            assert_eq!(efc_state.len(), nefc);
4459
4460            // FFI cross-validation post-step
4461            for i in 0..nefc {
4462                let raw_type = unsafe { *data.ffi().efc_type.add(i) };
4463                let raw_state = unsafe { *data.ffi().efc_state.add(i) };
4464                assert_eq!(efc_type[i], unsafe { crate::util::force_cast::<_, MjtConstraint>(raw_type) });
4465                assert_eq!(efc_state[i], unsafe { crate::util::force_cast::<_, MjtConstraintState>(raw_state) });
4466            }
4467
4468            // efc_KBIP should be populated
4469            let kbip = data.efc_kbip();
4470            assert_eq!(kbip.len(), nefc);
4471            for i in 0..nefc {
4472                for j in 0..4 {
4473                    assert_eq!(kbip[i][j], unsafe { *data.ffi().efc_KBIP.add(i * 4 + j) });
4474                }
4475            }
4476        }
4477    }
4478
4479    /// Runs many timesteps and verifies that body views (via info_with_view!)
4480    /// remain consistent with flat slice accessors at each step.
4481    /// This tests that force-cast pointers track the mutating mjData correctly.
4482    #[test]
4483    fn test_force_cast_view_consistency_across_steps() {
4484        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4485        let mut data = model.make_data();
4486
4487        let body_names = ["world", "b_free", "b_slide", "b_hinge", "mocap_body"];
4488
4489        for step_idx in 0..30 {
4490            data.step();
4491
4492            let xpos_flat = data.xpos();
4493            let xquat_flat = data.xquat();
4494            let cvel_flat = data.cvel();
4495            let cinert_flat = data.cinert();
4496
4497            for name in &body_names {
4498                let info = data.body(name).unwrap();
4499                let view = info.view(&data);
4500                let id = info.id;
4501
4502                // xpos from view must match flat slice
4503                assert_eq!(&view.xpos[..], &xpos_flat[id][..],
4504                    "xpos mismatch at step {} body '{}'", step_idx, name);
4505
4506                // xquat from view must match flat slice
4507                assert_eq!(&view.xquat[..], &xquat_flat[id][..],
4508                    "xquat mismatch at step {} body '{}'", step_idx, name);
4509
4510                // cvel from view must match flat slice
4511                assert_eq!(&view.cvel[..], &cvel_flat[id][..],
4512                    "cvel mismatch at step {} body '{}'", step_idx, name);
4513
4514                // cinert from view must match flat slice
4515                assert_eq!(&view.cinert[..], &cinert_flat[id][..],
4516                    "cinert mismatch at step {} body '{}'", step_idx, name);
4517            }
4518        }
4519    }
4520
4521    /// Steps with applied external forces via force-cast mutable array, verifies
4522    /// that the force affects simulation state across multiple timesteps.
4523    #[test]
4524    fn test_force_cast_multi_step_xfrc_applied_effect() {
4525        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4526        let mut data = model.make_data();
4527
4528        let b_free = data.body("b_free").unwrap();
4529        let b_free_id = b_free.id;
4530
4531        // Baseline: step without applied force
4532        data.forward();
4533        let baseline_xpos = data.xpos()[b_free_id];
4534
4535        // Reset and apply upward force to counteract gravity
4536        data.reset();
4537        // Apply a strong upward force: [fx, fy, fz, torque_x, torque_y, torque_z]
4538        data.xfrc_applied_mut()[b_free_id] = [0.0, 0.0, 100.0, 0.0, 0.0, 0.0];
4539
4540        for _ in 0..50 {
4541            data.step();
4542        }
4543
4544        let forced_xpos = data.xpos()[b_free_id];
4545
4546        // With an upward force of 100N on a 1kg mass, z should increase
4547        assert!(forced_xpos[2] > baseline_xpos[2],
4548            "Upward force should raise body: baseline_z={}, forced_z={}",
4549            baseline_xpos[2], forced_xpos[2]);
4550
4551        // FFI cross-validation at this point
4552        for j in 0..3 {
4553            assert_eq!(forced_xpos[j], unsafe { *data.ffi().xpos.add(b_free_id * 3 + j) });
4554        }
4555
4556        // xfrc_applied should still hold our value
4557        assert_eq!(data.xfrc_applied()[b_free_id], [0.0, 0.0, 100.0, 0.0, 0.0, 0.0]);
4558    }
4559
4560    /// Simulates, mutates mocap position mid-simulation via force-cast mutable array,
4561    /// and verifies the change is reflected in subsequent forward passes.
4562    #[test]
4563    fn test_force_cast_multi_step_mocap_mutation() {
4564        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4565        let mut data = model.make_data();
4566        data.forward();
4567
4568        let nmocap = model.ffi().nmocap as usize;
4569        assert!(nmocap > 0, "model should have at least one mocap body");
4570
4571        // Check initial
4572        let init_pos = data.mocap_pos()[0];
4573        assert_eq!(init_pos, [10.0, 10.0, 10.0]);
4574
4575        // Step a few times
4576        for _ in 0..10 {
4577            data.step();
4578        }
4579
4580        // Mutate mocap position mid-simulation
4581        data.mocap_pos_mut()[0] = [20.0, 30.0, 40.0];
4582        data.forward();
4583
4584        assert_eq!(data.mocap_pos()[0], [20.0, 30.0, 40.0]);
4585        // FFI cross-validation
4586        for j in 0..3 {
4587            assert_eq!(unsafe { *data.ffi().mocap_pos.add(j) }, [20.0, 30.0, 40.0][j]);
4588        }
4589
4590        // Mutate again and step further
4591        data.mocap_pos_mut()[0] = [-5.0, -5.0, -5.0];
4592        for _ in 0..10 {
4593            data.step();
4594        }
4595        assert_eq!(data.mocap_pos()[0], [-5.0, -5.0, -5.0]);
4596    }
4597
4598    /// Verifies that sensor data changes across multiple simulation steps.
4599    /// Exercises the force-cast sensordata flat array after physics evolves.
4600    #[test]
4601    fn test_force_cast_multi_step_sensor_data_evolves() {
4602        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4603        let mut data = model.make_data();
4604
4605        data.forward();
4606        let init_qpos: Vec<MjtNum> = data.qpos().to_vec();
4607
4608        // Apply a downward force via force-cast xfrc_applied
4609        let b_slide = data.body("b_slide").unwrap();
4610        data.xfrc_applied_mut()[b_slide.id] = [0.0, 0.0, -50.0, 0.0, 0.0, 0.0];
4611
4612        for _ in 0..100 {
4613            data.step();
4614        }
4615
4616        // Positions should have evolved under applied force
4617        let post_qpos = data.qpos();
4618        assert_ne!(post_qpos, init_qpos.as_slice(),
4619            "qpos did not evolve after 100 steps with applied force");
4620
4621        // Sensor FFI cross-validation
4622        let nsensordata = model.ffi().nsensordata as usize;
4623        let post_sensor = data.sensordata();
4624        assert_eq!(post_sensor.len(), nsensordata);
4625        for i in 0..nsensordata {
4626            assert_eq!(post_sensor[i], unsafe { *data.ffi().sensordata.add(i) },
4627                "sensordata[{}] FFI mismatch", i);
4628        }
4629    }
4630
4631    /// Multi-step test with eq_active force-cast bool: disable an equality
4632    /// constraint mid-simulation, verify dynamics change.
4633    #[test]
4634    fn test_force_cast_multi_step_eq_active_toggle() {
4635        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4636        let mut data = model.make_data();
4637
4638        // Step with constraint active
4639        for _ in 0..20 {
4640            data.step();
4641        }
4642        let pos_with_eq = data.xpos().to_vec();
4643
4644        // Reset, disable equality constraint, step again
4645        data.reset();
4646        data.eq_active_mut()[0] = false;
4647        data.eq_active_mut()[1] = false;
4648
4649        for _ in 0..20 {
4650            data.step();
4651        }
4652        let pos_without_eq = data.xpos().to_vec();
4653
4654        // The positions should differ since the constraints are disabled
4655        let b_slide = data.body("b_slide").unwrap();
4656        let diff: MjtNum = (0..3)
4657            .map(|j| (pos_with_eq[b_slide.id][j] - pos_without_eq[b_slide.id][j]).abs())
4658            .sum();
4659
4660        // At least some difference expected from disabling the equality constraint
4661        // (may be subtle depending on model dynamics, but should not be zero)
4662        assert!(diff > 1e-15 || {
4663            // If b_slide didn't move much, check b_hinge (the other constrained body)
4664            let b_hinge = data.body("b_hinge").unwrap();
4665            (0..3)
4666                .map(|j| (pos_with_eq[b_hinge.id][j] - pos_without_eq[b_hinge.id][j]).abs())
4667                .sum::<MjtNum>() > 1e-15
4668        }, "disabling equality constraints should change positions");
4669
4670        // FFI cross-validation for eq_active
4671        assert!(!data.eq_active()[0]);
4672        assert!(!data.eq_active()[1]);
4673        assert!(!unsafe { *data.ffi().eq_active });
4674        assert!(!unsafe { *data.ffi().eq_active.add(1) });
4675    }
4676
4677    /// Runs step1() + step2() split stepping and verifies force-cast arrays
4678    /// remain consistent with FFI between sub-steps.
4679    #[test]
4680    fn test_force_cast_split_step_consistency() {
4681        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4682        let mut data = model.make_data();
4683
4684        let nbody = model.ffi().nbody as usize;
4685
4686        for _ in 0..15 {
4687            data.step1();
4688
4689            // After step1: positions and velocities are computed
4690            let mid_xpos = data.xpos();
4691            assert_eq!(mid_xpos.len(), nbody);
4692            for i in 0..nbody {
4693                for j in 0..3 {
4694                    assert_eq!(mid_xpos[i][j], unsafe { *data.ffi().xpos.add(i * 3 + j) },
4695                        "xpos[{}][{}] FFI mismatch after step1", i, j);
4696                }
4697            }
4698
4699            data.step2();
4700
4701            // After step2: integration is complete
4702            let post_xpos = data.xpos();
4703            for i in 0..nbody {
4704                for j in 0..3 {
4705                    assert_eq!(post_xpos[i][j], unsafe { *data.ffi().xpos.add(i * 3 + j) },
4706                        "xpos[{}][{}] FFI mismatch after step2", i, j);
4707                }
4708            }
4709        }
4710    }
4711
4712    /// Steps the simulation, copies state via state/set_state, steps further,
4713    /// and verifies force-cast arrays reflect the correct state at each point.
4714    #[test]
4715    fn test_force_cast_multi_step_state_save_restore() {
4716        use crate::wrappers::mj_data::MjtState;
4717
4718        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4719        let mut data = model.make_data();
4720
4721        // Step 30 times
4722        for _ in 0..30 {
4723            data.step();
4724        }
4725        // Synchronize derived quantities (xpos, etc.) with current qpos
4726        data.forward();
4727
4728        // Save state
4729        let saved_state = data.state(MjtState::mjSTATE_FULLPHYSICS as u32);
4730        let saved_xpos: Vec<[MjtNum; 3]> = data.xpos().to_vec();
4731        let saved_qpos: Vec<MjtNum> = data.qpos().to_vec();
4732
4733        // Step 30 more times (state diverges)
4734        for _ in 0..30 {
4735            data.step();
4736        }
4737        let diverged_xpos: Vec<[MjtNum; 3]> = data.xpos().to_vec();
4738        assert_ne!(diverged_xpos, saved_xpos, "state should diverge after more steps");
4739
4740        // Restore state
4741        data.set_state(&saved_state, MjtState::mjSTATE_FULLPHYSICS as u32).unwrap();
4742        data.forward();
4743
4744        // Primary state (qpos) should be exactly restored
4745        let restored_qpos = data.qpos();
4746        for i in 0..saved_qpos.len() {
4747            assert_eq!(restored_qpos[i], saved_qpos[i],
4748                "qpos[{}] should match saved state after restore", i);
4749        }
4750
4751        // Derived quantity (xpos) should be approximately restored
4752        // (forward() recomputes from scratch, minor floating-point differences possible)
4753        let restored_xpos = data.xpos();
4754        for i in 0..saved_xpos.len() {
4755            for j in 0..3 {
4756                assert!(
4757                    (restored_xpos[i][j] - saved_xpos[i][j]).abs() < 1e-10,
4758                    "xpos[{}][{}] should approximately match saved state: got {} vs {}",
4759                    i, j, restored_xpos[i][j], saved_xpos[i][j]
4760                );
4761            }
4762        }
4763    }
4764
4765    /// Multi-step test that verifies kinematic quantities (xmat, xipos, ximat)
4766    /// change across steps and stay FFI-consistent via force-cast.
4767    #[test]
4768    fn test_force_cast_multi_step_kinematics_evolve() {
4769        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4770        let mut data = model.make_data();
4771
4772        // Apply an off-center force to induce rotation on the free body.
4773        let b_free = data.body("b_free").unwrap();
4774        data.xfrc_applied_mut()[b_free.id] = [1.0, 0.0, 0.0, 0.0, 0.5, 0.0];
4775        data.forward();
4776
4777        let nbody = model.ffi().nbody as usize;
4778        let init_xmat: Vec<[MjtNum; 9]> = data.xmat().to_vec();
4779        let init_xipos: Vec<[MjtNum; 3]> = data.xipos().to_vec();
4780
4781        // Step 50 times with the off-center force
4782        for _ in 0..50 {
4783            data.step();
4784        }
4785
4786        let post_xmat = data.xmat();
4787        let post_xipos = data.xipos();
4788
4789        assert_eq!(post_xmat.len(), nbody);
4790        assert_eq!(post_xipos.len(), nbody);
4791
4792        // Free body xipos should change (it falls and translates)
4793        let pos_changed = (0..3).any(|j| (post_xipos[b_free.id][j] - init_xipos[b_free.id][j]).abs() > 1e-6);
4794        assert!(pos_changed, "free body xipos should change as it moves");
4795
4796        // Free body xmat should change (off-center force induces rotation)
4797        let mat_changed = (0..9).any(|j| (post_xmat[b_free.id][j] - init_xmat[b_free.id][j]).abs() > 1e-12);
4798        assert!(mat_changed, "free body xmat should change with off-center force");
4799
4800        // FFI cross-validation
4801        for i in 0..nbody {
4802            for j in 0..9 {
4803                assert_eq!(post_xmat[i][j], unsafe { *data.ffi().xmat.add(i * 9 + j) });
4804            }
4805            for j in 0..3 {
4806                assert_eq!(post_xipos[i][j], unsafe { *data.ffi().xipos.add(i * 3 + j) });
4807            }
4808        }
4809    }
4810
4811    /// Runs simulation and verifies dynamic subtree quantities (subtree_com,
4812    /// subtree_linvel, subtree_angmom) change and match FFI after stepping.
4813    #[test]
4814    fn test_force_cast_multi_step_subtree_dynamics() {
4815        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4816        let mut data = model.make_data();
4817        data.forward();
4818
4819        let nbody = model.ffi().nbody as usize;
4820        let init_subtree_com: Vec<[MjtNum; 3]> = data.subtree_com().to_vec();
4821
4822        for _ in 0..60 {
4823            data.step();
4824        }
4825
4826        let post_subtree_com = data.subtree_com();
4827        let post_subtree_linvel = data.subtree_linvel();
4828        let post_subtree_angmom = data.subtree_angmom();
4829
4830        assert_eq!(post_subtree_com.len(), nbody);
4831        assert_eq!(post_subtree_linvel.len(), nbody);
4832        assert_eq!(post_subtree_angmom.len(), nbody);
4833
4834        // World subtree_com should change (bodies are falling)
4835        let world_com_diff: MjtNum = (0..3)
4836            .map(|j| (post_subtree_com[0][j] - init_subtree_com[0][j]).abs())
4837            .sum();
4838        assert!(world_com_diff > 1e-6,
4839            "world subtree_com should shift as bodies fall");
4840
4841        // FFI cross-validation
4842        for i in 0..nbody {
4843            for j in 0..3 {
4844                assert_eq!(post_subtree_com[i][j], unsafe { *data.ffi().subtree_com.add(i * 3 + j) });
4845                assert_eq!(post_subtree_linvel[i][j], unsafe { *data.ffi().subtree_linvel.add(i * 3 + j) });
4846                assert_eq!(post_subtree_angmom[i][j], unsafe { *data.ffi().subtree_angmom.add(i * 3 + j) });
4847            }
4848        }
4849    }
4850
4851    /// Test swap of [`MjModel`] borrowed by [`MjData`].
4852    #[test]
4853    fn test_model_swap() {
4854        const OLD_TIMESTEP: f64 = 0.002;
4855        const NEW_TIMESTEP: f64 = 0.1;
4856
4857        let mut model_template = Box::new(MjSpec::new().compile().unwrap());
4858        model_template.opt_mut().timestep = OLD_TIMESTEP;
4859
4860        let model = model_template.clone();
4861        let mut data = MjData::new(model);
4862
4863        model_template.opt_mut().timestep = NEW_TIMESTEP;
4864        model_template = data.swap_model(model_template);
4865        assert_eq!(model_template.opt().timestep, OLD_TIMESTEP);
4866        assert_eq!(data.model().opt().timestep, NEW_TIMESTEP);
4867    }
4868
4869    /// Exercises the `nsensordata` arm of `mj_model_nx_to_mapping!` and
4870    /// `mj_model_nx_to_nitem!` by calling `data.sensor("jp")` on a model
4871    /// that contains a single `jointpos` sensor.
4872    #[test]
4873    fn test_sensor_info_nsensordata_arm() {
4874        const SENSOR_MODEL: &str = r#"<mujoco>
4875  <worldbody>
4876    <body>
4877      <joint name="hinge" type="hinge"/>
4878      <geom size="0.1"/>
4879    </body>
4880  </worldbody>
4881  <sensor>
4882    <jointpos name="jp" joint="hinge"/>
4883  </sensor>
4884</mujoco>"#;
4885        let model = MjModel::from_xml_string(SENSOR_MODEL).expect("model load failed");
4886        let data = model.make_data();
4887        let info = data.sensor("jp").expect("sensor 'jp' not found");
4888        let view = info.view(&data);
4889        // A jointpos sensor outputs exactly 1 scalar value.
4890        assert_eq!(view.data.len(), 1, "jointpos sensor must produce 1 sensordata element");
4891    }
4892
4893    /// Exercises `getter_setter!` arm 2 (`get, [... & $type ...]`) and arm 17
4894    /// (`with, get, [...]`) via `MjData::energy()`, which returns `&[MjtNum; 2]`.
4895    #[test]
4896    fn test_energy_ref_getter_arms_2_and_17() {
4897        let model = MjModel::from_xml_string(MODEL).expect("model load failed");
4898        let mut data = model.make_data();
4899        data.energy_pos();
4900        data.energy_vel();
4901        let energy: &[MjtNum; 2] = data.energy();
4902        assert_eq!(energy.len(), 2);
4903        assert!(energy[0].is_finite(), "potential energy must be finite");
4904        assert!(energy[1].is_finite(), "kinetic energy must be finite");
4905    }
4906
4907    /// Exercises the `eval_or_expand! @eval true` path via `MjData::energy_mut()`,
4908    /// which is generated inside `getter_setter!` arm 2 when `allow_mut` is absent
4909    /// (defaults to true).
4910    #[test]
4911    fn test_energy_mut_eval_or_expand_true() {
4912        let model = MjModel::from_xml_string(MODEL).expect("model load failed");
4913        let mut data = model.make_data();
4914        data.energy_pos();
4915        let energy_mut: &mut [MjtNum; 2] = data.energy_mut();
4916        energy_mut[0] = 1.23;
4917        assert!(
4918            (data.energy()[0] - 1.23).abs() < 1e-12,
4919            "written energy value must be readable back"
4920        );
4921    }
4922
4923    /// Verifies that the body view `awake` field returns a single-element slice
4924    /// that matches the corresponding entry in `data.body_awake()`.
4925    #[test]
4926    fn test_body_view_awake_field() {
4927        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4928        let mut data = model.make_data();
4929        data.forward();
4930
4931        let body_info = data.body("b_free").unwrap();
4932        let view = body_info.view(&data);
4933
4934        /* Verify field dimensions */
4935        assert_eq!(view.awake.len(), 1);
4936
4937        /* Verify alignment with the top-level array slice */
4938        assert_eq!(view.awake[0], data.body_awake()[body_info.id]);
4939    }
4940
4941    /// Verifies that the tendon view `efcadr` field returns a single-element slice
4942    /// that matches the corresponding entry in `data.tendon_efcadr()`.
4943    #[test]
4944    fn test_tendon_view_efcadr_field() {
4945        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4946        let mut data = model.make_data();
4947        data.forward();
4948
4949        let tendon_info = data.tendon("ten1").unwrap();
4950        let view = tendon_info.view(&data);
4951
4952        /* Verify field dimensions */
4953        assert_eq!(view.efcadr.len(), 1);
4954
4955        /* Verify alignment with the top-level array slice */
4956        assert_eq!(view.efcadr[0], data.tendon_efcadr()[tendon_info.id]);
4957    }
4958
4959    /// Verifies that `dof_island`, `map_dof2idof`, and `dof_awake_ind` all have
4960    /// length `nv` and are backed by the correct FFI pointers.
4961    #[test]
4962    fn test_dof_island_map_dof2idof_dof_awake_ind_lengths() {
4963        let model = MjModel::from_xml_string(FORCE_MODEL).unwrap();
4964        let mut data = model.make_data();
4965        data.forward();
4966
4967        let nv = model.ffi().nv as usize;
4968
4969        assert_eq!(data.dof_island().len(), nv);
4970        assert_eq!(data.map_dof2idof().len(), nv);
4971        assert_eq!(data.dof_awake_ind().len(), nv);
4972
4973        for i in 0..nv {
4974            assert_eq!(data.dof_island()[i], unsafe { *data.ffi().dof_island.add(i) });
4975            assert_eq!(data.map_dof2idof()[i], unsafe { *data.ffi().map_dof2idof.add(i) });
4976            assert_eq!(data.dof_awake_ind()[i], unsafe { *data.ffi().dof_awake_ind.add(i) });
4977        }
4978    }
4979
4980    /// Exercises the `eval_or_expand! @eval false` path via
4981    /// `MjData::maxuse_threadstack()`, which uses `(allow_mut = false)` and
4982    /// therefore suppresses the `_mut` accessor.
4983    #[test]
4984    fn test_maxuse_threadstack_eval_or_expand_false() {
4985        let model = MjModel::from_xml_string(MODEL).expect("model load failed");
4986        let data = model.make_data();
4987        let stack: &[MjtSize; crate::mujoco_c::mjMAXTHREAD as usize] = data.maxuse_threadstack();
4988        assert_eq!(
4989            stack.len(),
4990            crate::mujoco_c::mjMAXTHREAD as usize,
4991            "maxuse_threadstack must have mjMAXTHREAD elements"
4992        );
4993    }
4994}