Skip to main content

mujoco_rs/wrappers/
mj_data.rs

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