mujoco_rs/wrappers/
mj_data.rs

1use super::mj_model::{MjModel, MjtSameFrame, MjtObj, MjtStage};
2use super::mj_statistic::{MjWarningStat, MjTimerStat};
3use super::mj_auxiliary::MjContact;
4use super::mj_primitive::*;
5use crate::mujoco_c::*;
6
7use std::io::{self, Error, ErrorKind};
8use std::ffi::CString;
9use std::ptr;
10
11use crate::{mj_view_indices, mj_model_nx_to_mapping, mj_model_nx_to_nitem};
12use crate::{view_creator, fixed_size_info_method, info_with_view};
13
14/*******************************************/
15// Types
16
17
18pub type MjtState = mjtState;
19/*******************************************/
20
21
22/**************************************************************************************************/
23// MjData
24/**************************************************************************************************/
25
26/// Wrapper around the ``mjData`` struct.
27/// Provides lifetime guarantees as well as automatic cleanup.
28pub struct MjData<'a> {
29    data: *mut mjData,
30    model: &'a MjModel
31}
32
33// Allow usage in threaded contexts as the data won't be shared anywhere outside Rust,
34// except in the C++ code.
35unsafe impl Send for MjData<'_> {}
36unsafe impl Sync for MjData<'_> {}
37
38
39impl<'a> MjData<'a> {
40    /// Constructor for a new MjData. This should is called from MjModel.
41    pub fn new(model: &'a MjModel) -> Self {
42        unsafe {
43            Self {
44                data: mj_makeData(model.ffi()),
45                model: model,
46            }
47        }
48    }
49
50    /// Reference to the wrapped FFI struct.
51    pub fn ffi(&self) -> &mjData {
52        unsafe { self.data.as_ref().unwrap() }
53    }
54
55    /// Mutable reference to the wrapped FFI struct.
56    pub unsafe fn ffi_mut(&mut self) -> &mut mjData {
57        unsafe { self.data.as_mut().unwrap() }
58    }
59
60    /// Returns a reference to data's [`MjModel`].
61    /// This is used for checking whether the correct
62    /// data is used in `update_x(data)` methods.
63    pub(crate) fn model(&self) -> &MjModel {
64        self.model
65    }
66
67    /// Returns a slice of detected contacts.
68    /// To obtain the contact force, call [`MjData::contact_force`].
69    pub fn contacts(&self) -> &[MjContact] {
70        unsafe {
71            std::slice::from_raw_parts((*self.data).contact, (*self.data).ncon as usize)
72        }
73    }
74
75    fixed_size_info_method! { Data, model.ffi(), body, [xfrc_applied: 6, xpos: 3, xquat: 4, xmat: 9, xipos: 3, ximat: 9, subtree_com: 3, cinert: 10, crb: 10, cvel: 6, subtree_linvel: 3, subtree_angmom: 3, cacc: 6, cfrc_int: 6, cfrc_ext: 6] }
76    fixed_size_info_method! { Data, model.ffi(), camera, [xpos: 3, xmat: 9] }
77    fixed_size_info_method! { Data, model.ffi(), geom, [xpos: 3, xmat: 9] }
78    fixed_size_info_method! { Data, model.ffi(), site, [xpos: 3, xmat: 9] }
79    fixed_size_info_method! { Data, model.ffi(), light, [xpos: 3, xdir: 3] }
80
81    /// Obtains a [`MjActuatorDataInfo`] struct containing information about the name, id, and
82    /// indices required for obtaining a slice view to the correct locations in [`MjData`].
83    /// The actual view can be obtained via [`MjActuatorDataInfo::view`].
84    pub fn actuator(&self, name: &str) -> Option<MjActuatorDataInfo> {
85        let c_name = CString::new(name).unwrap();
86        let id = unsafe { mj_name2id(self.model.ffi(), MjtObj::mjOBJ_ACTUATOR as i32, c_name.as_ptr())};
87        if id == -1 {  // not found
88            return None;
89        }
90
91        let ctrl;
92        let act;
93        let model_ffi = self.model.ffi();
94        unsafe {
95            ctrl = (id as usize, 1);
96            act = mj_view_indices!(id as usize, model_ffi.actuator_actadr, model_ffi.nu as usize, model_ffi.na as usize);
97        }
98
99        Some(MjActuatorDataInfo { name: name.to_string(), id: id as usize, ctrl, act})
100    }
101
102    /// Obtains a [`MjJointDataInfo`] struct containing information about the name, id, and
103    /// indices required for obtaining a slice view to the correct locations in [`MjData`].
104    /// The actual view can be obtained via [`MjJointDataInfo::view`].
105    pub fn joint(&self, name: &str) -> Option<MjJointDataInfo> {
106        let c_name = CString::new(name).unwrap();
107        let id = unsafe { mj_name2id(self.model.ffi(), MjtObj::mjOBJ_JOINT as i32, c_name.as_ptr())};
108        if id == -1 {  // not found
109            return None;
110        }
111        let model_ffi = self.model.ffi();
112        let id = id as usize;
113        unsafe {
114            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);
115            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);
116
117            // $id:expr, $addr_map:expr, $njnt:expr, $max_n:expr
118            let qpos = nq_range;
119            let qvel = nv_range;
120            let qacc_warmstart = nv_range;
121            let qfrc_applied = nv_range;
122            let qacc = nv_range;
123            let xanchor = (id * 3, 3);
124            let xaxis = (id * 3, 3);
125            #[allow(non_snake_case)]
126            let qLDiagInv = nv_range;
127            let qfrc_bias = nv_range;
128            let qfrc_passive = nv_range;
129            let qfrc_actuator = nv_range;
130            let qfrc_smooth = nv_range;
131            let qacc_smooth = nv_range;
132            let qfrc_constraint = nv_range;
133            let qfrc_inverse = nv_range;
134            
135            let qfrc_spring = nv_range;
136            let qfrc_damper = nv_range;
137            let qfrc_gravcomp = nv_range;
138            let qfrc_fluid = nv_range;
139            /* Special case attributes, used for some internal calculation */
140            // cdof
141            // cdof_dot
142
143            Some(MjJointDataInfo {name: name.to_string(), id: id as usize,
144                qpos, qvel, qacc_warmstart, qfrc_applied, qacc, xanchor, xaxis, qLDiagInv, qfrc_bias,
145                qfrc_spring, qfrc_damper, qfrc_gravcomp, qfrc_fluid, qfrc_passive,
146                qfrc_actuator, qfrc_smooth, qacc_smooth, qfrc_constraint, qfrc_inverse
147            })
148        }
149    }
150
151    /// Obtains a [`MjSensorDataInfo`] struct containing information about the name, id, and
152    /// indices required for obtaining a slice view to the correct locations in [`MjData`].
153    /// The actual view can be obtained via [`MjSensorDataInfo::view`].
154    pub fn sensor(&self, name: &str) -> Option<MjSensorDataInfo> {
155        let c_name = CString::new(name).unwrap();
156        let id = unsafe { mj_name2id(self.model.ffi(), MjtObj::mjOBJ_SENSOR as i32, c_name.as_ptr())};
157        if id == -1 {  // not found
158            return None;
159        }
160        let model_ffi = self.model.ffi();
161        let id = id as usize;
162
163        unsafe {
164            let data = mj_view_indices!(id, mj_model_nx_to_mapping!(model_ffi, nsensordata), mj_model_nx_to_nitem!(model_ffi, nsensordata), model_ffi.nsensordata);
165            Some(MjSensorDataInfo { id, name: name.to_string(), data })
166        }
167    }
168
169
170    /// Obtains a [`MjTendonDataInfo`] struct containing information about the name, id, and
171    /// indices required for obtaining a slice view to the correct locations in [`MjData`].
172    /// The actual view can be obtained via [`MjTendonDataInfo::view`].
173    #[allow(non_snake_case)]
174    pub fn tendon(&self, name: &str) -> Option<MjTendonDataInfo> {
175        let c_name = CString::new(name).unwrap();
176        let id = unsafe { mj_name2id(self.model.ffi(), MjtObj::mjOBJ_TENDON as i32, c_name.as_ptr())};
177        if id == -1 {  // not found
178            return None;
179        }
180
181        let model_ffi = self.model.ffi();
182        let id = id as usize;
183        let nv = model_ffi.nv as usize;
184        let wrapadr = (id, 1);
185        let wrapnum = (id, 1);
186        let J_rownnz = (id, 1);
187        let J_rowadr = (id, 1);
188        let J_colind = (id * nv, nv);
189        let length = (id, 1);
190        let J = (id * nv, nv);
191        let velocity = (id, 1);
192
193        Some(MjTendonDataInfo { id, name: name.to_string(), wrapadr, wrapnum, J_rownnz, J_rowadr, J_colind, length, J, velocity })
194    }
195
196    /// Steps the MuJoCo simulation.
197    pub fn step(&mut self) {
198        unsafe {
199            mj_step(self.model.ffi(), self.ffi_mut());
200        }
201    }
202
203    /// Calculates new dynamics. This is a wrapper around `mj_step1`.
204    pub fn step1(&mut self) {
205        unsafe {
206            mj_step1(self.model.ffi(), self.ffi_mut());
207        }
208    }
209
210    /// Calculates the rest after dynamics and integrates in time.
211    /// This is a wrapper around `mj_step2`.
212    pub fn step2(&mut self) {
213        unsafe {
214            mj_step2(self.model.ffi(), self.ffi_mut());
215        }
216    }
217
218    /// Forward dynamics: same as mj_step but do not integrate in time.
219    /// This is a wrapper around `mj_forward`.
220    pub fn forward(&mut self) {
221        unsafe { 
222            mj_forward(self.model.ffi(), self.ffi_mut());
223        }
224    }
225
226    /// [`MjData::forward`] dynamics with skip.
227    /// This is a wrapper around `mj_forwardSkip`.
228    pub fn forward_skip(&mut self, skipstage: MjtStage, skipsensor: bool) {
229        unsafe { 
230            mj_forwardSkip(self.model.ffi(), self.ffi_mut(), skipstage as i32, skipsensor as i32);
231        }
232    }
233
234    /// Inverse dynamics: qacc must be set before calling ([`MjData::forward`]).
235    /// This is a wrapper around `mj_inverse`.
236    pub fn inverse(&mut self) {
237        unsafe {
238            mj_inverse(self.model.ffi(), self.ffi_mut());
239        }
240    }
241
242    /// [`MjData::inverse`] dynamics with skip; skipstage is [`MjtStage`].
243    /// This is a wrapper around `mj_inverseSkip`.
244    pub fn inverse_skip(&mut self, skipstage: MjtStage, skipsensor: bool) {
245        unsafe {
246            mj_inverseSkip(self.model.ffi(), self.ffi_mut(), skipstage as i32, skipsensor as i32);
247        }
248    }
249
250    /// Calculates the contact force for the given `contact_id`.
251    /// The `contact_id` matches the index of the contact when iterating
252    /// via [`MjData::contacts`].
253    /// Calls `mj_contactForce` internally.
254    pub fn contact_force(&self, contact_id: usize) -> [MjtNum; 6] {
255        let mut force = [0.0; 6];
256        unsafe {
257            mj_contactForce(
258                self.model.ffi(), self.data,
259                contact_id as i32, force.as_mut_ptr()
260            );
261        }
262        force
263    }
264
265    /* Partially auto-generated */
266
267    /// Reset data to defaults.
268    pub fn reset(&mut self) {
269        unsafe { mj_resetData(self.model.ffi(), self.ffi_mut()) }
270    }
271
272    /// Reset data to defaults, fill everything else with debug_value.
273    pub fn reset_debug(&mut self, debug_value: u8) {
274        unsafe { mj_resetDataDebug(self.model.ffi(), self.ffi_mut(), debug_value) }
275    }
276
277    /// Reset data. If 0 <= key < nkey, set fields from specified keyframe.
278    pub fn reset_keyframe(&mut self, key: i32) {
279        unsafe { mj_resetDataKeyframe(self.model.ffi(), self.ffi_mut(), key) }
280    }
281
282    /// Print mjData to text file, specifying format.
283    /// float_format must be a valid printf-style format string for a single float value
284    pub fn print_formatted(&self, filename: &str, float_format: &str) {
285        let c_filename = CString::new(filename).unwrap();
286        let c_float_format = CString::new(float_format).unwrap();
287        unsafe { mj_printFormattedData(self.model.ffi(), self.ffi(), c_filename.as_ptr(), c_float_format.as_ptr()) }
288    }
289
290    /// Print data to text file.
291    pub fn print(&self, filename: &str) {
292        let c_filename = CString::new(filename).unwrap();
293        unsafe { mj_printData(self.model.ffi(), self.ffi(), c_filename.as_ptr()) }
294    }
295
296    /// Run position-dependent computations.
297    pub fn fwd_position(&mut self) {
298        unsafe { mj_fwdPosition(self.model.ffi(), self.ffi_mut()) }
299    }
300
301    /// Run velocity-dependent computations.
302    pub fn fwd_velocity(&mut self) {
303        unsafe { mj_fwdVelocity(self.model.ffi(), self.ffi_mut()) }
304    }
305
306    /// Compute actuator force qfrc_actuator.
307    pub fn fwd_actuation(&mut self) {
308        unsafe { mj_fwdActuation(self.model.ffi(), self.ffi_mut()) }
309    }
310
311    /// Add up all non-constraint forces, compute qacc_smooth.
312    pub fn fwd_acceleration(&mut self) {
313        unsafe { mj_fwdAcceleration(self.model.ffi(), self.ffi_mut()) }
314    }
315
316    /// Run selected constraint solver.
317    pub fn fwd_constraint(&mut self) {
318        unsafe { mj_fwdConstraint(self.model.ffi(), self.ffi_mut()) }
319    }
320
321    /// Euler integrator, semi-implicit in velocity.
322    pub fn euler(&mut self) {
323        unsafe { mj_Euler(self.model.ffi(), self.ffi_mut()) }
324    }
325
326    /// Runge-Kutta explicit order-N integrator.
327    pub fn runge_kutta(&mut self, n: i32) {
328        unsafe { mj_RungeKutta(self.model.ffi(), self.ffi_mut(), n) }
329    }
330
331    /// Implicit-in-velocity integrators.
332    pub fn implicit(&mut self) {
333        unsafe { mj_implicit(self.model.ffi(), self.ffi_mut()) }
334    }
335
336    /// Run position-dependent computations in inverse dynamics.
337    pub fn inv_position(&mut self) {
338        unsafe { mj_invPosition(self.model.ffi(), self.ffi_mut()) }
339    }
340
341    /// Run velocity-dependent computations in inverse dynamics.
342    pub fn inv_velocity(&mut self) {
343        unsafe { mj_invVelocity(self.model.ffi(), self.ffi_mut()) }
344    }
345
346    /// Apply the analytical formula for inverse constraint dynamics.
347    pub fn inv_constraint(&mut self) {
348        unsafe { mj_invConstraint(self.model.ffi(), self.ffi_mut()) }
349    }
350
351    /// Compare forward and inverse dynamics, save results in fwdinv.
352    pub fn compare_fwd_inv(&mut self) {
353        unsafe { mj_compareFwdInv(self.model.ffi(), self.ffi_mut()) }
354    }
355
356    /// Evaluate position-dependent sensors.
357    pub fn sensor_pos(&mut self) {
358        unsafe { mj_sensorPos(self.model.ffi(), self.ffi_mut()) }
359    }
360
361    /// Evaluate velocity-dependent sensors.
362    pub fn sensor_vel(&mut self) {
363        unsafe { mj_sensorVel(self.model.ffi(), self.ffi_mut()) }
364    }
365
366    /// Evaluate acceleration and force-dependent sensors.
367    pub fn sensor_acc(&mut self) {
368        unsafe { mj_sensorAcc(self.model.ffi(), self.ffi_mut()) }
369    }
370
371    /// Evaluate position-dependent energy (potential).
372    pub fn energy_pos(&mut self) {
373        unsafe { mj_energyPos(self.model.ffi(), self.ffi_mut()) }
374    }
375
376    /// Evaluate velocity-dependent energy (kinetic).
377    pub fn energy_vel(&mut self) {
378        unsafe { mj_energyVel(self.model.ffi(), self.ffi_mut()) }
379    }
380
381    /// Check qpos, reset if any element is too big or nan.
382    pub fn check_pos(&mut self) {
383        unsafe { mj_checkPos(self.model.ffi(), self.ffi_mut()) }
384    }
385
386    /// Check qvel, reset if any element is too big or nan.
387    pub fn check_vel(&mut self) {
388        unsafe { mj_checkVel(self.model.ffi(), self.ffi_mut()) }
389    }
390
391    /// Check qacc, reset if any element is too big or nan.
392    pub fn check_acc(&mut self) {
393        unsafe { mj_checkAcc(self.model.ffi(), self.ffi_mut()) }
394    }
395
396    /// Run forward kinematics.
397    pub fn kinematics(&mut self) {
398        unsafe { mj_kinematics(self.model.ffi(), self.ffi_mut()) }
399    }
400
401    /// Map inertias and motion dofs to global frame centered at CoM.
402    pub fn com_pos(&mut self) {
403        unsafe { mj_comPos(self.model.ffi(), self.ffi_mut()) }
404    }
405
406    /// Compute camera and light positions and orientations.
407    pub fn camlight(&mut self) {
408        unsafe { mj_camlight(self.model.ffi(), self.ffi_mut()) }
409    }
410
411    /// Compute flex-related quantities.
412    pub fn flex_comp(&mut self) {
413        unsafe { mj_flex(self.model.ffi(), self.ffi_mut()) }
414    }
415
416    /// Compute tendon lengths, velocities and moment arms.
417    pub fn tendon_comp(&mut self) {
418        unsafe { mj_tendon(self.model.ffi(), self.ffi_mut()) }
419    }
420
421    /// Compute actuator transmission lengths and moments.
422    pub fn transmission(&mut self) {
423        unsafe { mj_transmission(self.model.ffi(), self.ffi_mut()) }
424    }
425
426    /// Run composite rigid body inertia algorithm (CRB).
427    pub fn crb(&mut self) {
428        unsafe { mj_crb(self.model.ffi(), self.ffi_mut()) }
429    }
430
431    /// Make inertia matrix.
432    pub fn make_m(&mut self) {
433        unsafe { mj_makeM(self.model.ffi(), self.ffi_mut()) }
434    }
435
436    /// Compute sparse L'*D*L factorizaton of inertia matrix.
437    pub fn factor_m(&mut self) {
438        unsafe { mj_factorM(self.model.ffi(), self.ffi_mut()) }
439    }
440
441    /// Compute cvel, cdof_dot.
442    pub fn com_vel(&mut self) {
443        unsafe { mj_comVel(self.model.ffi(), self.ffi_mut()) }
444    }
445
446    /// Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces.
447    pub fn passive(&mut self) {
448        unsafe { mj_passive(self.model.ffi(), self.ffi_mut()) }
449    }
450
451    /// Sub-tree linear velocity and angular momentum: compute subtree_linvel, subtree_angmom.
452    pub fn subtree_vel(&mut self) {
453        unsafe { mj_subtreeVel(self.model.ffi(), self.ffi_mut()) }
454    }
455
456    /// RNE: compute M(qpos)*qacc + C(qpos,qvel); flg_acc=false removes inertial term.
457    pub fn rne(&mut self, flg_acc: bool) -> Vec<MjtNum> {
458        let mut out = vec![0.0; self.model.ffi().nv as usize];
459        unsafe { mj_rne(self.model.ffi(), self.ffi_mut(), flg_acc as i32, out.as_mut_ptr()) };
460        out
461    }
462
463    /// RNE with complete data: compute cacc, cfrc_ext, cfrc_int.
464    pub fn rne_post_constraint(&mut self) {
465        unsafe { mj_rnePostConstraint(self.model.ffi(), self.ffi_mut()) }
466    }
467
468    /// Run collision detection.
469    pub fn collision(&mut self) {
470        unsafe { mj_collision(self.model.ffi(), self.ffi_mut()) }
471    }
472
473    /// Construct constraints.
474    pub fn make_constraint(&mut self) {
475        unsafe { mj_makeConstraint(self.model.ffi(), self.ffi_mut()) }
476    }
477
478    /// Find constraint islands.
479    pub fn island(&mut self) {
480        unsafe { mj_island(self.model.ffi(), self.ffi_mut()) }
481    }
482
483    /// Compute inverse constraint inertia efc_AR.
484    pub fn project_constraint(&mut self) {
485        unsafe { mj_projectConstraint(self.model.ffi(), self.ffi_mut()) }
486    }
487
488    /// Compute efc_vel, efc_aref.
489    pub fn reference_constraint(&mut self) {
490        unsafe { mj_referenceConstraint(self.model.ffi(), self.ffi_mut()) }
491    }
492
493    /// Compute efc_state, efc_force, qfrc_constraint, and (optionally) cone Hessians.
494    /// If cost is not NULL, set *cost = s(jar) where jar = Jac*qacc-aref.
495    /// Nullable: cost
496    pub fn constraint_update(&mut self, jar: &[MjtNum], cost: Option<&mut MjtNum>, flg_cone_hessian: bool) {
497        unsafe { mj_constraintUpdate(
498            self.model.ffi(), self.ffi_mut(),
499            jar.as_ptr(), cost.map_or(ptr::null_mut(), |x| x as *mut MjtNum),
500            flg_cone_hessian as i32
501        ) }
502    }
503
504    /// Add contact to d->contact list; return 0 if success; 1 if buffer full.
505    pub fn add_contact(&mut self, con: &MjContact) -> io::Result<()> {
506        match unsafe { mj_addContact(self.model.ffi(), self.ffi_mut(), con) } {
507            0 => Ok(()),
508            1 => Err(Error::new(ErrorKind::StorageFull, "buffer full")),
509            _ => Err(Error::new(ErrorKind::Other, "unknown error"))
510        }
511    }
512
513    /// Compute 3/6-by-nv end-effector Jacobian of a global point attached to the given body.
514    /// Set `jacp` to `true` to calculate the translational Jacobian and `jacr` to `true` for
515    /// the rotational Jacobian. Returns a `(Vec, Vec)` for translation and rotation. Empty `Vec`s
516    /// indicate that the corresponding Jacobian was not computed.
517    pub fn jac(&self, jacp: bool, jacr: bool, point: &[MjtNum; 3], body_id: i32) -> (Vec<MjtNum>, Vec<MjtNum>) {
518        let required_len = 3 * self.model.ffi().nv as usize;
519        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
520        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
521
522        unsafe {
523            mj_jac(
524                self.model.ffi(),
525                self.ffi(),
526                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
527                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
528                point.as_ptr(),
529                body_id,
530            )
531        };
532
533        (jacp_vec, jacr_vec)
534    }
535
536    /// Compute body frame end-effector Jacobian.
537    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
538    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
539    pub fn jac_body(&self, jacp: bool, jacr: bool, body_id: i32) -> (Vec<MjtNum>, Vec<MjtNum>) {
540        let required_len = 3 * self.model.ffi().nv as usize;
541        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
542        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
543
544        unsafe {
545            mj_jacBody(
546                self.model.ffi(),
547                self.ffi(),
548                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
549                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
550                body_id,
551            )
552        };
553
554        (jacp_vec, jacr_vec)
555    }
556
557    /// Compute body center-of-mass end-effector Jacobian.
558    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
559    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
560    pub fn jac_body_com(&self, jacp: bool, jacr: bool, body_id: i32) -> (Vec<MjtNum>, Vec<MjtNum>) {
561        let required_len = 3 * self.model.ffi().nv as usize;
562        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
563        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
564
565        unsafe {
566            mj_jacBodyCom(
567                self.model.ffi(),
568                self.ffi(),
569                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
570                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
571                body_id,
572            )
573        };
574
575        (jacp_vec, jacr_vec)
576    }
577
578    /// Compute subtree center-of-mass end-effector Jacobian (translational only).
579    /// Set `jacp` to `true` to calculate the translational component. Returns a `Vec`.
580    /// Empty `Vec` indicates that the Jacobian was not computed.
581    pub fn jac_subtree_com(&mut self, jacp: bool, body_id: i32) -> Vec<MjtNum> {
582        let required_len = 3 * self.model.ffi().nv as usize;
583        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
584
585        unsafe {
586            mj_jacSubtreeCom(
587                self.model.ffi(),
588                self.ffi_mut(),
589                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
590                body_id,
591            )
592        };
593
594        jacp_vec
595    }
596
597    /// Compute geom end-effector Jacobian.
598    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
599    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
600    pub fn jac_geom(&self, jacp: bool, jacr: bool, geom_id: i32) -> (Vec<MjtNum>, Vec<MjtNum>) {
601        let required_len = 3 * self.model.ffi().nv as usize;
602        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
603        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
604
605        unsafe {
606            mj_jacGeom(
607                self.model.ffi(),
608                self.ffi(),
609                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
610                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
611                geom_id,
612            )
613        };
614
615        (jacp_vec, jacr_vec)
616    }
617
618    /// Compute site end-effector Jacobian.
619    /// Set `jacp`/`jacr` to `true` to calculate translational/rotational components.
620    /// Returns `(Vec, Vec)` for translation and rotation. Empty `Vec`s indicate not computed.
621    pub fn jac_site(&self, jacp: bool, jacr: bool, site_id: i32) -> (Vec<MjtNum>, Vec<MjtNum>) {
622        let required_len = 3 * self.model.ffi().nv as usize;
623        let mut jacp_vec = if jacp { vec![0 as MjtNum; required_len] } else { vec![] };
624        let mut jacr_vec = if jacr { vec![0 as MjtNum; required_len] } else { vec![] };
625
626        unsafe {
627            mj_jacSite(
628                self.model.ffi(),
629                self.ffi(),
630                if jacp { jacp_vec.as_mut_ptr() } else { ptr::null_mut() },
631                if jacr { jacr_vec.as_mut_ptr() } else { ptr::null_mut() },
632                site_id,
633            )
634        };
635
636        (jacp_vec, jacr_vec)
637    }
638
639    /// Compute subtree angular momentum matrix.
640    pub fn angmom_mat(&mut self, body_id: i32) -> Vec<MjtNum> {
641        let mut mat = vec![0.0; 3 * self.model.ffi().nv as usize];
642        unsafe { mj_angmomMat(self.model.ffi(), self.ffi_mut(), mat.as_mut_ptr(), body_id) };
643        mat
644    }
645
646    /// Compute object 6D velocity (rot:lin) in object-centered frame, world/local orientation.
647    pub fn object_velocity(&self, obj_type: MjtObj, obj_id: i32, flg_local: bool) -> [MjtNum; 6] {
648        let mut result: [MjtNum; 6] = [0.0; 6];
649        unsafe { mj_objectVelocity(
650            self.model.ffi(), self.ffi(),
651            obj_type as i32, obj_id,
652            result.as_mut_ptr(), flg_local as i32
653        ) };
654        result
655    }
656
657    /// Compute object 6D acceleration (rot:lin) in object-centered frame, world/local orientation.
658    pub fn object_acceleration(&self, obj_type: MjtObj, obj_id: i32, flg_local: bool) -> [MjtNum; 6] {
659        let mut result: [MjtNum; 6] = [0.0; 6];
660        unsafe { mj_objectAcceleration(
661            self.model.ffi(), self.ffi(),
662            obj_type as i32, obj_id,
663            result.as_mut_ptr(), flg_local as i32
664        ) };
665        result
666    }
667
668    /// Returns smallest signed distance between two geoms and optionally segment from geom1 to geom2.
669    pub fn geom_distance(&self, geom1_id: i32, geom2_id: i32, dist_max: MjtNum, fromto: Option<&mut [MjtNum; 6]>) -> MjtNum {
670        unsafe { mj_geomDistance(
671            self.model.ffi(), self.ffi(),
672            geom1_id, geom2_id, dist_max,
673            fromto.map_or(ptr::null_mut(), |x| x.as_mut_ptr())
674        ) }
675    }
676
677    /// Map from body local to global Cartesian coordinates, sameframe takes values from [`MjtSameFrame`].
678    /// Returns (global position, global orientation matrix).
679    /// Wraps ``mj_local2Global``.
680    pub fn local_to_global(&mut self, pos: &[MjtNum; 3], quat: &[MjtNum; 4], body_id: i32, sameframe: MjtSameFrame) -> ([MjtNum; 3], [MjtNum; 9]) {
681        /* Create uninitialized because this gets filled by the function. */
682        let mut xpos: [MjtNum; 3] =  [0.0; 3];
683        let mut xmat: [MjtNum; 9] = [0.0; 9];
684        unsafe { mj_local2Global(self.ffi_mut(), xpos.as_mut_ptr(), xmat.as_mut_ptr(), pos.as_ptr(), quat.as_ptr(), body_id, sameframe as MjtByte) };
685        (xpos, xmat)
686    }
687
688    /// Intersect multiple rays emanating from a single point.
689    /// Similar semantics to mj_ray, but vec is an array of (nray x 3) directions.
690    /// Returns (geomids, distances).
691    pub fn multi_ray(
692        &mut self, pnt: &[MjtNum; 3], vec: &[[MjtNum; 3]], geomgroup: Option<&[MjtByte; mjNGROUP as usize]>,
693        flg_static: bool, bodyexclude: i32, cutoff: MjtNum
694    ) -> (Vec<i32>, Vec<MjtNum>) {
695        let nray = vec.len();
696        let mut geom_id = vec![0; nray];
697        let mut distance = vec![0.0; nray];
698
699        unsafe { mj_multiRay(
700            self.model.ffi(), self.ffi_mut(), pnt.as_ptr(),
701            vec.as_ptr() as *const MjtNum, geomgroup.map_or(ptr::null(), |x| x.as_ptr()),
702            flg_static as u8, bodyexclude, geom_id.as_mut_ptr(),
703            distance.as_mut_ptr(), nray as i32, cutoff
704        ) };
705
706        (geom_id, distance)
707    }
708
709    /// Intersect ray (pnt+x*vec, x>=0) with visible geoms, except geoms in bodyexclude.
710    /// Return distance (x) to nearest surface, or -1 if no intersection and output geomid.
711    /// geomgroup, flg_static are as in mjvOption; geomgroup==NULL skips group exclusion.
712    pub fn ray(
713        &self, pnt: &[MjtNum; 3], vec: &[MjtNum; 3],
714        geomgroup: Option<&[MjtByte; mjNGROUP as usize]>, flg_static: bool, bodyexclude: i32
715    ) -> (i32, MjtNum) {
716        let mut geom_id = -1;
717        let dist = unsafe { mj_ray(
718            self.model.ffi(), self.ffi(),
719            pnt.as_ptr(), vec.as_ptr(),
720            geomgroup.map_or(ptr::null(), |x| x.as_ptr()),
721            flg_static as MjtByte, bodyexclude, &mut geom_id
722        ) };
723        (geom_id, dist)
724    }
725
726    /// Returns a direct pointer to the underlying model.
727    /// THIS IS NOT TO BE USED.
728    /// It is only meant for the viewer code, which currently still depends
729    /// on mutable pointers to model and data. This will be removed in the future.
730    pub(crate) unsafe fn __raw(&self) -> *mut mjData {
731        self.data
732    }
733
734}
735
736
737/// Some public attribute methods.
738impl MjData<'_> {
739    /// Maximum stack allocation in bytes.
740    pub fn maxuse_stack(&self) -> MjtSize {
741        self.ffi().maxuse_stack
742    }
743
744    /// Maximum stack allocation per thread in bytes.
745    pub fn maxuse_threadstack(&self) -> &[MjtSize] {
746        &self.ffi().maxuse_threadstack
747    }
748
749    /// Warning statistics.
750    pub fn warning_stats(&self) -> &[MjWarningStat] {
751        &self.ffi().warning
752    }
753
754    /// Timer statistics.
755    pub fn timer_stats(&self) -> &[MjTimerStat] {
756        &self.ffi().timer
757    }
758
759    /// Simulation time
760    pub fn time(&self) -> MjtNum {
761        self.ffi().time
762    }
763
764    /// Potential, kinetic energy.
765    pub fn energy(&self) -> &[MjtNum] {
766        &self.ffi().energy
767    }
768}
769
770impl Drop for MjData<'_> {
771    fn drop(&mut self) {
772        unsafe {
773            mj_deleteData(self.data);
774        }
775    }
776}
777
778
779/**************************************************************************************************/
780// Joint view
781/**************************************************************************************************/
782info_with_view!(
783    Data,
784    joint,
785    [
786        qpos: MjtNum, qvel: MjtNum, qacc_warmstart: MjtNum, qfrc_applied: MjtNum, qacc: MjtNum, xanchor: MjtNum, xaxis: MjtNum, qLDiagInv: MjtNum,
787        qfrc_bias: MjtNum, qfrc_spring: MjtNum, qfrc_damper: MjtNum, qfrc_gravcomp: MjtNum, qfrc_fluid: MjtNum, qfrc_passive: MjtNum,
788        qfrc_actuator: MjtNum, qfrc_smooth: MjtNum, qacc_smooth: MjtNum, qfrc_constraint: MjtNum, qfrc_inverse: MjtNum
789    ],
790    []
791);
792
793/// Deprecated name for [`MjJointDataInfo`].
794#[deprecated]
795pub type MjJointInfo = MjJointDataInfo;
796
797
798/* Backward compatibility */
799impl MjJointDataViewMut<'_> {
800    /// Deprecated. Use [`MjJointDataViewMut::zero`] instead.
801    #[deprecated]
802    pub fn reset(&mut self) {
803        self.zero();
804    }
805}
806
807/// Deprecated name for [`MjJointDataView`].
808#[deprecated]
809pub type MjJointView<'d> = MjJointDataView<'d>;
810
811/// Deprecated name for [`MjJointDataViewMut`].
812#[deprecated]
813pub type MjJointViewMut<'d> = MjJointDataViewMut<'d>;
814
815/**************************************************************************************************/
816// Sensor view
817/**************************************************************************************************/
818info_with_view!(Data, sensor, sensor, [data: MjtNum], []);
819
820/**************************************************************************************************/
821// Geom view
822/**************************************************************************************************/
823info_with_view!(Data, geom, geom_, [xpos: MjtNum, xmat: MjtNum], []);
824
825/// Deprecated name for [`MjGeomDataInfo`].
826#[deprecated]
827pub type MjGeomInfo = MjGeomDataInfo;
828
829/// Deprecated name for [`MjGeomDataView`].
830#[deprecated]
831pub type MjGeomView<'d> = MjGeomDataView<'d>;
832
833/// Deprecated name for [`MjGeomDataViewMut`].
834#[deprecated]
835pub type MjGeomViewMut<'d> = MjGeomDataViewMut<'d>;
836
837/**************************************************************************************************/
838// Actuator view
839/**************************************************************************************************/
840info_with_view!(Data, actuator, [ctrl: MjtNum], [act: MjtNum]);
841
842/// Deprecated name for [`MjActuatorDataInfo`].
843#[deprecated]
844pub type MjActuatorInfo = MjActuatorDataInfo;
845
846/// Deprecated name for [`MjActuatorDataView`].
847#[deprecated]
848pub type MjActuatorView<'d> = MjActuatorDataView<'d>;
849
850/// Deprecated name for [`MjActuatorDataViewMut`].
851#[deprecated]
852pub type MjActuatorViewMut<'d> = MjActuatorDataViewMut<'d>;
853
854/**************************************************************************************************/
855// Body view
856/**************************************************************************************************/
857info_with_view!(
858    Data, body, [
859        xfrc_applied: MjtNum, xpos: MjtNum, xquat: MjtNum, xmat: MjtNum, xipos: MjtNum, ximat: MjtNum,
860        subtree_com: MjtNum, cinert: MjtNum, crb: MjtNum, cvel: MjtNum, subtree_linvel: MjtNum,
861        subtree_angmom: MjtNum, cacc: MjtNum, cfrc_int: MjtNum, cfrc_ext: MjtNum
862    ], []
863);
864
865/**************************************************************************************************/
866// Camera view
867/**************************************************************************************************/
868info_with_view!(Data, camera, cam_, [xpos: MjtNum, xmat: MjtNum], []);
869
870/**************************************************************************************************/
871// Site view
872/**************************************************************************************************/
873info_with_view!(Data, site, site_, [xpos: MjtNum, xmat: MjtNum], []);
874
875/**************************************************************************************************/
876// Tendon view
877/**************************************************************************************************/
878info_with_view!(Data, tendon, ten_, [wrapadr: i32, wrapnum: i32, J_rownnz: i32, J_rowadr: i32, J_colind: i32, length: MjtNum, J: MjtNum, velocity: MjtNum], []);
879
880/**************************************************************************************************/
881// Light view
882/**************************************************************************************************/
883info_with_view!(Data, light, light_, [xpos: MjtNum, xdir: MjtNum], []);
884
885/**************************************************************************************************/
886// Unit tests
887/**************************************************************************************************/
888
889#[cfg(test)]
890mod test {
891    use crate::assert_relative_eq;
892    use crate::prelude::*;
893    use super::*;
894
895    const MODEL: &str = "
896<mujoco>
897  <worldbody>
898    <light ambient=\"0.2 0.2 0.2\"/>
899    <body name=\"ball\" pos=\".2 .2 .1\">
900        <geom name=\"green_sphere\" size=\".1\" rgba=\"0 1 0 1\" solref=\"0.004 1.0\"/>
901        <joint name=\"ball\" type=\"free\"/>
902    </body>
903
904    <body name=\"ball2\" pos=\".7 .2 .1\">
905        <geom name=\"green_sphere2\" size=\".1\" rgba=\"0 1 0 1\" solref=\"0.004 1.0\"/>
906        <joint name=\"ball2\" type=\"free\"/>
907    </body>
908
909    <geom name=\"floor1\" type=\"plane\" size=\"10 10 1\" solref=\"0.004 1.0\"/>
910  </worldbody>
911</mujoco>";
912
913
914    #[test]
915    fn test_joint_view() {
916        let model = MjModel::from_xml_string(MODEL).unwrap();
917        let mut data = model.make_data();
918        let joint_info = data.joint("ball").unwrap();
919        let body_info = data.body("ball").unwrap();
920
921        for _ in 0..10 {
922            data.step();
923        }
924
925        /* The ball should start in a still position */
926        let mut joint_view = joint_info.view(&data);
927        assert_relative_eq!(joint_view.qvel[0], 0.0, epsilon=1e-9);  // vx
928        assert_relative_eq!(joint_view.qvel[1], 0.0, epsilon=1e-9);  // vy
929        // assert_relative_eq!(view.qvel[2], 0.0);  // vz Ignore due to slight instability of the model.
930        assert_relative_eq!(joint_view.qvel[3], 0.0, epsilon=1e-9);  // wx
931        assert_relative_eq!(joint_view.qvel[4], 0.0, epsilon=1e-9);  // wy
932        assert_relative_eq!(joint_view.qvel[5], 0.0, epsilon=1e-9);  // wz
933
934        /* Give the ball some velocity */
935        let mut joint_view_mut = joint_info.view_mut(&mut data);
936        joint_view_mut.qvel[0] = 0.5;  // vx = 0.5 m/s
937        joint_view_mut.qvel[4] = 0.5 / 0.1;  // wy = 0.5 m/s / 0.1 m
938
939        let initial_qpos: [MjtNum; 3] = joint_view_mut.qpos[..3].try_into().unwrap();  // initial x, y and z.
940        data.step();
941
942        /* Test if the ball is moving in the x direction and rotating around y. */
943        joint_view = joint_info.view(&data);
944        assert_relative_eq!(joint_view.qvel[0], 0.5, epsilon=1e-3);  // vx
945        assert_relative_eq!(joint_view.qvel[4], 0.5 / 0.1, epsilon=1e-3);  // wy
946
947        /* Test correct placement */
948        let timestep = model.opt().timestep;
949        assert_relative_eq!(joint_view.qpos[0], initial_qpos[0] + timestep * joint_view.qvel[0], epsilon=1e-9);  // p = p + dp/dt * dt
950        assert_relative_eq!(joint_view.qpos[1], initial_qpos[1] + timestep * joint_view.qvel[1], epsilon=1e-9);
951        assert_relative_eq!(joint_view.qpos[2], initial_qpos[2] + timestep * joint_view.qvel[2], epsilon=1e-9);
952
953        /* Test consistency with the body */
954        data.step1();  // update derived variables.
955
956        
957        joint_view = joint_info.view(&data);
958        let body_view = body_info.view(&data);
959        /* Consistency in position */
960        assert_relative_eq!(joint_view.qpos[0], body_view.xpos[0], epsilon=1e-9);  // same position.
961        assert_relative_eq!(joint_view.qpos[1], body_view.xpos[1], epsilon=1e-9);
962        assert_relative_eq!(joint_view.qpos[2], body_view.xpos[2], epsilon=1e-9);
963
964        assert_relative_eq!(joint_view.qpos[3], body_view.xquat[0], epsilon=1e-9);  // same orientation.
965        assert_relative_eq!(joint_view.qpos[4], body_view.xquat[1], epsilon=1e-9);
966        assert_relative_eq!(joint_view.qpos[5], body_view.xquat[2], epsilon=1e-9);
967        assert_relative_eq!(joint_view.qpos[6], body_view.xquat[3], epsilon=1e-9);
968
969        /* Consistency in velocity */
970        assert_relative_eq!(joint_view.qvel[0], body_view.cvel[3], epsilon=1e-9);  // same position velocity.
971        assert_relative_eq!(joint_view.qvel[1], body_view.cvel[4], epsilon=1e-9);
972        assert_relative_eq!(joint_view.qvel[2], body_view.cvel[5], epsilon=1e-9);
973
974        assert_relative_eq!(joint_view.qvel[3], body_view.cvel[0], epsilon=1e-9);  // same rotational velocity.
975        assert_relative_eq!(joint_view.qvel[4], body_view.cvel[1], epsilon=1e-9);
976        assert_relative_eq!(joint_view.qvel[5], body_view.cvel[2], epsilon=1e-9);
977    }
978
979    #[test]
980    fn test_body_view() {
981        let model = MjModel::from_xml_string(MODEL).unwrap();
982        let mut data = model.make_data();
983        let body_info = data.body("ball2").unwrap();
984        let mut cvel;
985
986        data.step1();
987
988        for _ in 0..10 {
989            data.step2();
990            data.step1();  // step() and step2() update before integration, thus we need to manually update non-state variables.
991        }
992
993        // The ball should start in a still position
994        cvel = body_info.view(&data).cvel;
995        assert_relative_eq!(cvel[0], 0.0, epsilon=1e-9);
996        assert_relative_eq!(cvel[1], 0.0, epsilon=1e-9);
997        assert_relative_eq!(cvel[2], 0.0, epsilon=1e-9);
998        assert_relative_eq!(cvel[3], 0.0, epsilon=1e-9);
999        assert_relative_eq!(cvel[4], 0.0, epsilon=1e-9);
1000        // assert_relative_eq!(cvel[5], 0.0);  // Ignore due to slight instability of the model.
1001
1002        // Give the ball some velocity
1003        body_info.view_mut(&mut data).xfrc_applied[0] = 5.0;
1004        data.step2();
1005        data.step1();
1006
1007        let view = body_info.view(&data);
1008        cvel = view.cvel;
1009        println!("{:?}", cvel);
1010        assert_relative_eq!(cvel[0], 0.0, epsilon=1e-9);
1011        assert!(cvel[1] > 0.0);  // wy should be positive when rolling with positive vx.
1012        assert_relative_eq!(cvel[2], 0.0, epsilon=1e-9);
1013        assert!(cvel[3] > 0.0);  // vx should point in the direction of the applied force.
1014        assert_relative_eq!(cvel[4], 0.0, epsilon=1e-9);  // vy should be 0.
1015        // assert_relative_eq!(cvel[5], 0.0);  // vz should be 0, but we don't test it due to jumpiness (instability) of the ball.
1016
1017        assert_relative_eq!(view.xfrc_applied[0], 5.0, epsilon=1e-9); // the original force should stay applied.
1018
1019        data.step2();
1020        data.step1();
1021    }
1022
1023    #[test]
1024    fn test_copy_reset_variants() {
1025        let model = MjModel::from_xml_string(MODEL).unwrap();
1026        let mut data = model.make_data();
1027
1028        // Test reset variants
1029        data.reset();
1030        data.reset_debug(7);
1031        data.reset_keyframe(0);
1032    }
1033
1034    #[test]
1035    fn test_dynamics_and_sensors() {
1036        let model = MjModel::from_xml_string(MODEL).unwrap();
1037        let mut data = model.make_data();
1038
1039        // Simulation pipeline components
1040        data.fwd_position();
1041        data.fwd_velocity();
1042        data.fwd_actuation();
1043        data.fwd_acceleration();
1044        data.fwd_constraint();
1045
1046        data.euler();
1047        data.runge_kutta(4);
1048        // data.implicit();  // integrator isn't implicit in the model => skip this check
1049
1050        data.inv_position();
1051        data.inv_velocity();
1052        data.inv_constraint();
1053        data.compare_fwd_inv();
1054
1055        // Sensors
1056        data.sensor_pos();
1057        data.sensor_vel();
1058        data.sensor_acc();
1059
1060        data.energy_pos();
1061        data.energy_vel();
1062
1063        data.check_pos();
1064        data.check_vel();
1065        data.check_acc();
1066
1067        data.kinematics();
1068        data.com_pos();
1069        data.camlight();
1070        data.flex_comp();
1071        data.tendon_comp();
1072        data.transmission();
1073        data.crb();
1074        data.make_m();
1075        data.factor_m();
1076        data.com_vel();
1077        data.passive();
1078        data.subtree_vel();
1079    }
1080
1081
1082    #[test]
1083    fn test_rne_and_collision_pipeline() {
1084        let model = MjModel::from_xml_string(MODEL).unwrap();
1085        let mut data = model.make_data();
1086        data.step();
1087
1088        // mj_rne returns a scalar as result
1089        data.rne(true);
1090
1091        data.rne_post_constraint();
1092
1093        // // Collision and constraint pipeline
1094        data.collision();
1095        data.make_constraint();
1096        data.island();
1097        data.project_constraint();
1098        data.reference_constraint();
1099
1100        let jar = vec![0.0; (data.model.ffi().nv) as usize];
1101        let mut cost = 0.0;
1102        data.constraint_update(&jar, None, false);
1103        data.constraint_update(&jar, Some(&mut cost), true);
1104    }
1105
1106    #[test]
1107    fn test_add_contact() {
1108        let model = MjModel::from_xml_string(MODEL).unwrap();
1109        let mut data = model.make_data();
1110
1111        // Add a dummy contact
1112        let dummy_contact = unsafe { std::mem::zeroed() };
1113        data.add_contact(&dummy_contact).unwrap();
1114    }
1115
1116    #[test]
1117    fn test_jacobian() {
1118        let model = MjModel::from_xml_string(MODEL).unwrap();
1119        let mut data = model.make_data();
1120
1121        let nv = data.model.ffi().nv as usize;
1122        let expected_len = 3 * nv;
1123
1124        // Use a small offset point relative to the joint origin
1125        let point = [0.1, 0.0, 0.0];
1126
1127        let ball_body_id = model.body("ball").unwrap().id as i32;
1128
1129        // Test global point Jacobian
1130        let (jacp, jacr) = data.jac(true, true, &point, ball_body_id);
1131        assert_eq!(jacp.len(), expected_len);
1132        assert_eq!(jacr.len(), expected_len);
1133
1134        // Test body frame Jacobian
1135        let (jacp_body, jacr_body) = data.jac_body(true, true, ball_body_id);
1136        assert_eq!(jacp_body.len(), expected_len);
1137        assert_eq!(jacr_body.len(), expected_len);
1138
1139        // Test body COM Jacobian
1140        let (jacp_com, jacr_com) = data.jac_body_com(true, true, ball_body_id);
1141        assert_eq!(jacp_com.len(), expected_len);
1142        assert_eq!(jacr_com.len(), expected_len);
1143
1144        // Test subtree COM Jacobian (translational only)
1145        let jac_subtree = data.jac_subtree_com(true, 0);
1146        assert_eq!(jac_subtree.len(), expected_len);
1147
1148        // Test geom Jacobian
1149        let (jacp_geom, jacr_geom) = data.jac_geom(true, true, ball_body_id);
1150        assert_eq!(jacp_geom.len(), expected_len);
1151        assert_eq!(jacr_geom.len(), expected_len);
1152
1153        // Test site Jacobian
1154        let (jacp_site, jacr_site) = data.jac_site(true, true, ball_body_id);
1155        assert_eq!(jacp_site.len(), expected_len);
1156        assert_eq!(jacr_site.len(), expected_len);
1157
1158        // Test flags set to false produce empty Vec
1159        let (jacp_none, jacr_none) = data.jac(false, false, &[0.0; 3], ball_body_id);
1160        assert!(jacp_none.is_empty());
1161        assert!(jacr_none.is_empty());
1162    }
1163
1164    #[test]
1165    fn test_angmom_and_object_dynamics() {
1166        let model = MjModel::from_xml_string(MODEL).unwrap();
1167        let mut data = model.make_data();
1168
1169        let mat = data.angmom_mat(0);
1170        assert_eq!(mat.len(), (3 * data.model.ffi().nv as usize));
1171
1172        let vel = data.object_velocity(MjtObj::mjOBJ_BODY, 0, true);
1173        assert_eq!(vel, vel); // just ensure it returns 6-length
1174
1175        let acc = data.object_acceleration(MjtObj::mjOBJ_BODY, 0, false);
1176        assert_eq!(acc, acc);
1177    }
1178
1179    #[test]
1180    fn test_geom_distance_and_transforms() {
1181        let model = MjModel::from_xml_string(MODEL).unwrap();
1182        let mut data = model.make_data();
1183        data.step();
1184
1185        let mut ft = [0.0; 6];
1186        let dist = data.geom_distance(0, 0, 1.0, Some(&mut ft));
1187        assert_eq!(ft, [0.0; 6]);
1188        assert_eq!(dist, 1.0);
1189
1190        let pos = [0.0; 3];
1191        let quat = [1.0, 0.0, 0.0, 0.0];
1192        let (xpos, xmat) = data.local_to_global(&pos, &quat, 0, MjtSameFrame::mjSAMEFRAME_NONE);
1193        assert_eq!(xpos.len(), 3);
1194        assert_eq!(xmat.len(), 9);
1195
1196        let ray_vecs = [[1.0, 0.0, 0.0], [1.0, 0.0, 0.0], [1.0, 0.0, 0.0]];
1197        let rays = data.multi_ray(&pos, &ray_vecs, None, false, -1, 10.0);
1198        assert_eq!(rays.0.len(), 3);
1199        assert_eq!(rays.1.len(), 3);
1200
1201        let (geomid, dist) = data.ray(&pos, &[1.0, 0.0, 0.0], None, true, -1);
1202        assert!(dist.is_finite());
1203        assert!(geomid >= -1);
1204    }
1205}