Skip to main content

mujoco_rs/wrappers/
mj_editing.rs

1//! Definitions related to model editing.
2use std::ffi::{c_char, c_int, CStr, CString};
3use std::marker::PhantomData;
4use std::ptr::{self, NonNull};
5use std::path::Path;
6use crate::error::MjEditError;
7
8#[macro_use]
9mod utility;
10use utility::*;
11
12mod traits;
13pub use traits::*;
14
15mod default;
16pub use default::*;
17
18use super::mj_model::{
19    MjModel, MjtObj, MjtGeom, MjtJoint, MjtCamLight,
20    MjtLightType, MjtSensor, MjtDataType, MjtGain,
21    MjtBias, MjtDyn, MjtEq, MjtTexture, MjtColorSpace,
22    MjtTrn, MjtStage, MjtFlexSelf, MjtProjection,
23    MjtSleepPolicy, MjtWrap, MjtTextureRole, MjtCubeFace
24};
25use super::mj_auxiliary::{MjVfs, MjVisual, MjStatistic, MjLROpt};
26use super::mj_option::MjOption;
27use super::mj_primitive::*;
28use crate::mujoco_c::*;
29
30use crate::getter_setter;
31
32// Re-export with lowercase 'f' to fix method generation
33use crate::mujoco_c::{mjs_addHField as mjs_addHfield, mjsHField as mjsHfield, mjs_asHField as mjs_asHfield};
34use crate::util::{assert_mujoco_version, ERROR_BUF_LEN};
35
36/* Validation helpers */
37/// Validates that an object-type value is a real object type, i.e. an [`MjtObj`] discriminant below
38/// [`MjtObj::mjNOBJECT`]. Meta variants (`mjOBJ_FRAME`, `mjOBJ_DEFAULT`, `mjOBJ_MODEL`) and
39/// `mjNOBJECT` itself are rejected because the model compiler uses such values as an unchecked
40/// index into a `mjNOBJECT`-sized array (via `mjCModel::FindObject`), which would read out of
41/// bounds. Used for any safe setter whose value reaches `FindObject` during `compile()`.
42fn check_objtype(t: MjtObj) -> Result<(), MjEditError> {
43    if (t as i32) < (MjtObj::mjNOBJECT as i32) {
44        Ok(())
45    } else {
46        Err(MjEditError::InvalidParameter(format!(
47            "object type must be a real MjtObj below MjtObj::mjNOBJECT, got {t:?}"
48        )))
49    }
50}
51
52/// Validates that a custom-numeric array size is non-negative.
53///
54/// A negative `size` slips through every guard in the model compiler's `mjCNumeric::Compile`
55/// (the `size < data_.size()` check is gated on a non-empty init array, and the zero checks treat
56/// negatives as non-zero), so it undersizes the shared `numeric_data` allocation while another
57/// numeric's zero-fill loop still runs up to its own positive size, writing out of bounds.
58fn check_numeric_size(size: i32) -> Result<(), MjEditError> {
59    if size < 0 {
60        Err(MjEditError::InvalidParameter(format!(
61            "numeric size must be non-negative, got {size}"
62        )))
63    } else {
64        Ok(())
65    }
66}
67
68/* Types */
69/// Type of inertia inference.
70pub type MjtGeomInertia = mjtGeomInertia;
71
72/// Type of mesh inertia.
73pub type MjtMeshInertia = mjtMeshInertia;
74
75/// Type of built-in procedural texture.
76pub type MjtBuiltin = mjtBuiltin;
77
78/// Type of built-in procedural mesh.
79pub type MjtMeshBuiltin = mjtMeshBuiltin;
80
81/// Mark type for procedural textures.
82pub type MjtMark = mjtMark;
83
84/// Type of limit specification.
85pub type MjtLimited = mjtLimited;
86
87/// Whether to align free joints with the inertial frame.
88pub type MjtAlignFree = mjtAlignFree;
89
90/// Whether to infer body inertias from child geoms.
91pub type MjtInertiaFromGeom = mjtInertiaFromGeom;
92
93/// Type of orientation specifier.
94pub type MjtOrientation = mjtOrientation;
95
96/// Compiler timing categories, used in `mjs_getTimer`.
97pub type MjtCTimer = mjtCTimer;
98/*******************************************************/
99
100/******************************
101** Type aliases
102******************************/
103/// Alternative orientation specifiers.
104pub type MjsOrientation = mjsOrientation;
105impl MjsOrientation {
106    /// Sets orientation in Euler space.
107    pub fn set_euler(&mut self, angle: &[f64; 3]) {
108        self.type_ = MjtOrientation::mjORIENTATION_EULER;
109        self.euler = *angle;
110    }
111
112    /// Sets orientation in axis angle space.
113    pub fn set_axis_angle(&mut self, angle: &[f64; 4]) {
114        self.type_ = MjtOrientation::mjORIENTATION_AXISANGLE;
115        self.axisangle = *angle;
116    }
117
118    /// Sets orientation in XY axes space.
119    pub fn set_xy_axis(&mut self, angle: &[f64; 6]) {
120        self.type_ = MjtOrientation::mjORIENTATION_XYAXES;
121        self.xyaxes = *angle;
122    }
123
124    /// Sets orientation in Z axis space.
125    pub fn set_z_axis(&mut self, angle: &[f64; 3]) {
126        self.type_ = MjtOrientation::mjORIENTATION_ZAXIS;
127        self.zaxis = *angle;
128    }
129
130    /// Changes the orientation mode to quaternions. The orientation must
131    /// be specified via the main angle attribute, not through [`MjsOrientation`].
132    pub fn switch_quat(&mut self) {
133        self.type_ = MjtOrientation::mjORIENTATION_QUAT;
134    }
135}
136
137/// Compiler options.
138pub type MjsCompiler = mjsCompiler;
139impl MjsCompiler {
140    getter_setter! {[&] with, get, set, [
141        autolimits: bool;              "infer \"limited\" attribute based on range.";
142        balanceinertia: bool;          "automatically impose A + B >= C rule.";
143        fitaabb: bool;                 "meshfit to aabb instead of inertia box.";
144        degree: bool;                  "angles in radians or degrees.";
145        discardvisual: bool;           "discard visual geoms in parser.";
146        usethread: bool;               "use multiple threads to speed up compiler.";
147        fusestatic: bool;              "fuse static bodies with parent.";
148        saveinertial: bool;            "save explicit inertial clause for all bodies to XML.";
149        alignfree: bool;               "align free joints with inertial frame.";
150    ]}
151
152    getter_setter! {[&] with, get, set, [
153        boundmass: f64;                "enforce minimum body mass.";
154        boundinertia: f64;             "enforce minimum body diagonal inertia.";
155        settotalmass: f64;             "rescale masses and inertias; <=0: ignore.";
156    ]}
157
158    getter_setter! {[&] with, get, set, [
159        inertiafromgeom: MjtInertiaFromGeom [force];  "use geom inertias.";
160    ]}
161
162    getter_setter! {[&] with, get, [
163        inertiagrouprange: &[i32; 2];       "range of geom groups used to compute inertia.";
164        eulerseq: &[c_char; 3];             "sequence for euler rotations.";
165        LRopt: &MjLROpt;                    "options for lengthrange computation.";
166    ]}
167
168    string_set_get_with! {[&]
169        meshdir;        "mesh and hfield directory.";
170        texturedir;     "texture directory.";
171    }
172}
173
174/***************************
175** Model Specification
176***************************/
177/// Model specification. This wraps the FFI type [`mjSpec`] internally.
178#[derive(Debug)]
179pub struct MjSpec(NonNull<mjSpec>);
180
181// SAFETY: `MjSpec` owns its `mjSpec` exclusively, so moving it between threads transfers
182// sole ownership and cannot race.
183//
184// It is intentionally NOT `Sync`. `clone`/`try_clone` produce a faithful, independent copy, but
185// the C++ copy constructor behind `mj_copySpec` is not strictly `const` on the source: for every
186// actuator it calls `ForgetKeyframes`, which clears two `std::map` keyframe-resolution caches
187// (`act_`/`ctrl_`). Those maps are empty for a normally-built spec, yet `std::map::clear` rewrites
188// the tree header unconditionally, so two threads sharing a `&MjSpec` and cloning concurrently
189// would race on those writes (a data race, though no spec data is lost). Hence the type stays `!Sync`.
190unsafe impl Send for MjSpec {}
191
192impl MjSpec {
193    /// Creates an empty [`MjSpec`].
194    ///
195    /// # Panics
196    /// - When the linked MuJoCo version does not match the expected from MuJoCo-rs.
197    /// - When MuJoCo fails to allocate the specification.
198    ///   Use [`MjSpec::try_new`] for a fallible alternative.
199    pub fn new() -> Self {
200        Self::try_new().expect("MuJoCo failed to allocate MjSpec")
201    }
202
203    /// Fallible version of [`MjSpec::new`].
204    ///
205    /// # Errors
206    /// Returns [`MjEditError::AllocationFailed`] if MuJoCo fails to allocate
207    /// the specification.
208    ///
209    /// # Panics
210    /// When the linked MuJoCo version does not match the expected from MuJoCo-rs.
211    pub fn try_new() -> Result<Self, MjEditError> {
212        assert_mujoco_version();
213        // SAFETY: mj_makeSpec allocates a new MjSpec; returns null on allocation
214        // failure, handled by ok_or below.
215        let ptr = unsafe { mj_makeSpec() };
216        Ok(MjSpec(NonNull::new(ptr).ok_or(MjEditError::AllocationFailed)?))
217    }
218
219    /// Creates a deep copy of this [`MjSpec`].
220    ///
221    /// Internally calls `mj_copySpec`, which invokes the C++ copy constructor
222    /// on the underlying model.  This is a proper deep copy: the returned spec
223    /// is fully independent from the original.
224    ///
225    /// # Errors
226    /// Returns [`MjEditError::AllocationFailed`] if MuJoCo fails to allocate
227    /// the copy (e.g. out of memory or an internal C++ exception).
228    pub fn try_clone(&self) -> Result<Self, MjEditError> {
229        // SAFETY: self.0 is a valid non-null mjSpec pointer for the lifetime of self
230        // (struct invariant); mj_copySpec returns null on allocation failure, handled below.
231        let ptr = unsafe { mj_copySpec(self.0.as_ptr()) };
232        NonNull::new(ptr).map(MjSpec).ok_or(MjEditError::AllocationFailed)
233    }
234
235    /// Creates a [`MjSpec`] from the `path` to a file.
236    /// # Returns
237    /// On success, returns [`Ok`] variant containing the loaded [`MjSpec`].
238    /// # Errors
239    /// - [`MjEditError::InvalidUtf8Path`] if the path contains invalid UTF-8.
240    /// - [`MjEditError::ParseFailed`] if MuJoCo fails to parse the XML.
241    /// # Panics
242    /// - when the `path` contains '\0'.
243    /// - when the linked MuJoCo version does not match the expected from MuJoCo-rs.
244    pub fn from_xml<T: AsRef<Path>>(path: T) -> Result<Self, MjEditError> {
245        Self::from_xml_file(path, None)
246    }
247
248    /// Creates a [`MjSpec`] from the `path` to a file, located in a virtual file system (`vfs`).
249    /// # Returns
250    /// On success, returns [`Ok`] variant containing the loaded [`MjSpec`].
251    /// # Errors
252    /// - [`MjEditError::InvalidUtf8Path`] if the path contains invalid UTF-8.
253    /// - [`MjEditError::ParseFailed`] if MuJoCo fails to parse the XML.
254    /// # Panics
255    /// - when the `path` contains '\0'.
256    /// - when the linked MuJoCo version does not match the expected from MuJoCo-rs.
257    pub fn from_xml_vfs<T: AsRef<Path>>(path: T, vfs: &MjVfs) -> Result<Self, MjEditError> {
258        Self::from_xml_file(path, Some(vfs))
259    }
260
261    fn from_xml_file<T: AsRef<Path>>(path: T, vfs: Option<&MjVfs>) -> Result<Self, MjEditError> {
262        assert_mujoco_version();
263
264        let mut error_buffer = [0; ERROR_BUF_LEN];
265        unsafe {
266            let path_str = path.as_ref().to_str()
267                .ok_or(MjEditError::InvalidUtf8Path)?;
268            let path = CString::new(path_str).unwrap();
269            let raw_ptr = mj_parseXML(
270                path.as_ptr(), vfs.map_or(ptr::null(), |v| v.ffi()),
271                error_buffer.as_mut_ptr(), error_buffer.len() as c_int
272            );
273
274            Self::check_spec(raw_ptr, &error_buffer)
275        }
276    }
277
278    /// Creates a [`MjSpec`] from an `xml` string.
279    /// # Returns
280    /// On success, returns [`Ok`] variant containing the loaded [`MjSpec`].
281    /// # Errors
282    /// Returns [`MjEditError::ParseFailed`] if MuJoCo encounters an error parsing the string.
283    /// # Panics
284    /// - when the `xml` contains '\0'.
285    /// - when the linked MuJoCo version does not match the expected from MuJoCo-rs.
286    pub fn from_xml_string(xml: &str) -> Result<Self, MjEditError> {
287        assert_mujoco_version();
288
289        let c_xml = CString::new(xml).unwrap();
290        let mut error_buffer = [0; ERROR_BUF_LEN];
291        unsafe {
292            let spec_ptr = mj_parseXMLString(
293                c_xml.as_ptr(), ptr::null(),
294                error_buffer.as_mut_ptr(), error_buffer.len() as c_int
295            );
296            Self::check_spec(spec_ptr, &error_buffer)
297        }
298    }
299
300    /// Parse and create a [`MjSpec`] from `filename`.
301    /// The `content_type` controls the decoder to use.
302    /// This is a wrapper around low-level method [`mj_parse`].
303    /// # Returns
304    /// On success, returns [`Ok`] variant containing the loaded [`MjSpec`].
305    /// # Errors
306    /// - [`MjEditError::InvalidUtf8Path`] if the path contains invalid UTF-8.
307    /// - [`MjEditError::ParseFailed`] if MuJoCo fails to parse the file.
308    /// # Panics
309    /// - When `content_type` or the path contain interior `\0` characters.
310    /// - When the linked MuJoCo version does not match the expected from MuJoCo-rs.
311    pub fn from_parse<T: AsRef<Path>>(filename: T, content_type: &str) -> Result<Self, MjEditError> {
312        Self::from_parse_file(filename, content_type, None)
313    }
314
315    /// Same as [`MjSpec::from_parse`], except `filename` is taken from `vfs`.
316    /// # Returns
317    /// On success, returns [`Ok`] variant containing the loaded [`MjSpec`].
318    /// # Errors
319    /// - [`MjEditError::InvalidUtf8Path`] if the path contains invalid UTF-8.
320    /// - [`MjEditError::ParseFailed`] if MuJoCo fails to parse the file.
321    /// # Panics
322    /// - When `content_type` or the path contain interior `\0` characters.
323    /// - When the linked MuJoCo version does not match the expected from MuJoCo-rs.
324    pub fn from_parse_vfs<T: AsRef<Path>>(filename: T, content_type: &str, vfs: &MjVfs) -> Result<Self, MjEditError> {
325        Self::from_parse_file(filename, content_type, Some(vfs))
326    }
327
328    /// Parse and create a [`MjSpec`] from `filename`.
329    /// The `content_type` controls the decoder to use.
330    /// This is a wrapper around low-level method [`mj_parse`].
331    /// # Panics
332    /// - When `content_type` or the path contain interior `\0` characters.
333    /// - When the linked MuJoCo version does not match the version MuJoCo-rs was compiled against.
334    fn from_parse_file<T: AsRef<Path>>(filename: T, content_type: &str, vfs: Option<&MjVfs>) -> Result<Self, MjEditError> {
335        assert_mujoco_version();
336        let mut error_buffer = [0; ERROR_BUF_LEN];
337        unsafe {
338            let c_filename = CString::new(
339                filename.as_ref().to_str()
340                .ok_or(MjEditError::InvalidUtf8Path)?
341            ).unwrap();
342            let c_content_type = CString::new(content_type).unwrap();
343            let ptr = mj_parse(
344                c_filename.as_ptr(), c_content_type.as_ptr(),
345                vfs.map_or(ptr::null(), |v| v.ffi()),
346                error_buffer.as_mut_ptr(), error_buffer.len() as i32
347            );
348            Self::check_spec(ptr, &error_buffer)
349        }
350    }
351
352    /// Handles spec pointer input.
353    fn check_spec(spec_ptr: *mut mjSpec, error_buffer: &[c_char]) -> Result<Self, MjEditError> {
354        if spec_ptr.is_null() {
355            // SAFETY: error_buffer is zero-initialised and MuJoCo always
356            // NUL-terminates the message it writes into it.
357            let message = unsafe { CStr::from_ptr(error_buffer.as_ptr()) }
358                .to_string_lossy()
359                .into_owned();
360            Err(MjEditError::ParseFailed(message))
361        }
362        else {
363            // SAFETY: spec_ptr is confirmed non-null by the guard above.
364            Ok(MjSpec(unsafe { NonNull::new_unchecked(spec_ptr) }))
365        }
366    }
367
368    /// An immutable reference to the internal FFI struct.
369    pub fn ffi(&self) -> &mjSpec {
370        // SAFETY: self.0 is a valid non-null mjSpec pointer for the lifetime of
371        // self (struct invariant).
372        unsafe { self.0.as_ref() }
373    }
374
375    /// A mutable reference to the internal FFI struct.
376    ///
377    /// # Safety
378    /// Callers must ensure that any mutations performed through the returned reference
379    /// preserve the invariants that MuJoCo expects for `mjSpec`.
380    pub unsafe fn ffi_mut(&mut self) -> &mut mjSpec {
381        unsafe { self.0.as_mut() }
382    }
383
384    /// Delete an element from this specification.
385    ///
386    /// # Errors
387    /// Returns [`MjEditError::DeleteFailed`] if MuJoCo cannot delete the element.
388    ///
389    /// # Safety
390    /// The caller must ensure:
391    /// - `element` is a valid pointer to an mjsElement
392    /// - `element` is owned by this spec
393    /// - `element` has not been previously deleted
394    /// - no Rust references derived from `element` exist
395    pub unsafe fn delete_element(&mut self, element: *mut mjsElement) -> Result<(), MjEditError> {
396        if element.is_null() {
397            return Err(MjEditError::DeleteFailed("null element pointer".to_owned()));
398        }
399
400        let spec = unsafe { self.ffi_mut() };
401        let owner = unsafe { mjs_getSpec(element) };
402        if owner != spec {
403            return Err(MjEditError::DeleteFailed("element does not belong to this spec".to_owned()));
404        }
405
406        if unsafe { (*element).elemtype } == MjtObj::mjOBJ_DEFAULT {
407            return Err(MjEditError::UnsupportedOperation);
408        }
409        if unsafe { (*element).elemtype } == MjtObj::mjOBJ_BODY {
410            let name = unsafe { read_mjs_string(mjs_getName(element)) };
411            if name == "world" {
412                return Err(MjEditError::UnsupportedOperation);
413            }
414        }
415
416        let result = unsafe { mjs_delete(spec, element) };
417        match result {
418            0 => Ok(()),
419            _ => {
420                let error_msg = unsafe {
421                    let ptr = mjs_getError(spec);
422                    if ptr.is_null() {
423                        "Unknown error".to_owned()
424                    } else {
425                        CStr::from_ptr(ptr).to_string_lossy().into_owned()
426                    }
427                };
428                Err(MjEditError::DeleteFailed(error_msg))
429            }
430        }
431    }
432
433    /// Compile [`MjSpec`] to [`MjModel`].
434    /// A spec can be edited and compiled multiple times,
435    /// returning a new mjModel instance that takes the edits into account.
436    /// # Returns
437    /// On success, returns [`Ok`] variant containing the loaded [`MjModel`].
438    /// # Errors
439    /// Returns [`MjEditError::CompileFailed`] if the model fails to compile, including when a
440    /// texture has a builtin pattern set while its `nchannel` is less than 3.
441    pub fn compile(&mut self) -> Result<MjModel, MjEditError> {
442        // The builtin-texture generators (`Builtin2D`/`BuiltinCube`) write a hard-coded 3 bytes per
443        // pixel, but MuJoCo only allocates `nchannel*width*height` bytes and (unlike the file/data
444        // paths) does not check `nchannel >= 3` for the builtin path, so `nchannel < 3` heap-overflows
445        // during compilation. Both setters (`set_nchannel`, `set_builtin`) are safe and independent,
446        // so this cross-field invariant can only be enforced at the compile choke point.
447        for texture in self.texture_iter() {
448            if texture.builtin() != MjtBuiltin::mjBUILTIN_NONE && texture.nchannel() < 3 {
449                return Err(MjEditError::CompileFailed(
450                    "texture with a builtin pattern requires nchannel >= 3".to_owned(),
451                ));
452            }
453        }
454
455        let result = unsafe { MjModel::from_raw( mj_compile(self.0.as_ptr(), ptr::null()) ) };
456        result.map_err(|_| {
457            // SAFETY: The spec is still valid after failed compilation.
458            // The error pointer is valid until the next MuJoCo call on this spec.
459            let error_msg: String = unsafe {
460                let ptr = mjs_getError(self.ffi_mut());
461                if ptr.is_null() {
462                    "Compilation failed (unknown error)".to_owned()
463                } else {
464                    CStr::from_ptr(ptr).to_string_lossy().into_owned()
465                }
466            };
467            MjEditError::CompileFailed(error_msg)
468        })
469    }
470
471    /// Return compiler timers (`mjtCTimer` order).
472    pub fn timer(&self) -> &[f64; MjtCTimer::mjNCTIMER as usize] {
473        unsafe { &*mjs_getTimer(self.0.as_ptr()).cast() }
474    }
475
476    /// Saves the spec to an XML file.
477    /// # Returns
478    /// `Ok(())` on success.
479    /// # Errors
480    /// - [`MjEditError::InvalidUtf8Path`] if the path contains invalid UTF-8.
481    /// - [`MjEditError::SaveFailed`] with MuJoCo's error message if saving fails.
482    /// # Panics
483    /// When `filename` contains interior `\0` characters.
484    pub fn save_xml<T: AsRef<Path>>(&self, filename: T) -> Result<(), MjEditError> {
485        let mut error_buff = [0; ERROR_BUF_LEN];
486        let cname = CString::new(
487            filename.as_ref().to_str()
488            .ok_or(MjEditError::InvalidUtf8Path)?
489        ).unwrap();  // filename is always UTF-8
490        let result = unsafe { mj_saveXML(
491            self.ffi(), cname.as_ptr(),
492            error_buff.as_mut_ptr(), error_buff.len() as i32
493        ) };
494        match result {
495            0 => Ok(()),
496            _ => {
497                // SAFETY: error_buff is zero-initialised and MuJoCo always
498                // NUL-terminates the message it writes into it.
499                let message = unsafe { CStr::from_ptr(error_buff.as_ptr()) }
500                    .to_string_lossy()
501                    .into_owned();
502                Err(MjEditError::SaveFailed(message))
503            }
504        }
505    }
506
507    /// Saves the spec to an XML string.
508    /// `buffer_size` controls how many bytes are allocated for the output.
509    /// # Returns
510    /// On success, returns the generated XML string.
511    /// # Errors
512    /// - [`MjEditError::XmlBufferTooSmall`] when `buffer_size` is too small.
513    ///   The `required_size` field uses `snprintf`-style semantics (bytes to write, excluding NUL),
514    ///   so retry with `required_size as usize + 1` bytes.
515    /// - [`MjEditError::SaveFailed`] with MuJoCo's error message on any other failure.
516    /// # Panics
517    /// Panics if MuJoCo reports success but returns XML that is not NUL-terminated
518    /// within the allocated output buffer.
519    pub fn save_xml_string(&self, buffer_size: usize) -> Result<String, MjEditError> {
520        let mut error_buff = [0; ERROR_BUF_LEN];
521        let mut result_buff = vec![0u8; buffer_size];
522        let result = unsafe { mj_saveXMLString(
523            self.ffi(), result_buff.as_mut_ptr().cast(), result_buff.len() as i32,
524            error_buff.as_mut_ptr(), error_buff.len() as i32
525        ) };
526        match result {
527            0 => Ok(CStr::from_bytes_until_nul(&result_buff).unwrap().to_string_lossy().into_owned()),
528            r if r > 0 => Err(MjEditError::XmlBufferTooSmall { required_size: r as usize }),
529            _ => {
530                // SAFETY: error_buff is zero-initialised and MuJoCo always
531                // NUL-terminates the message it writes into it.
532                let message = unsafe { CStr::from_ptr(error_buff.as_ptr()) }
533                    .to_string_lossy()
534                    .into_owned();
535                Err(MjEditError::SaveFailed(message))
536            }
537        }
538    }
539}
540
541/// Children accessor methods.
542impl MjSpec {
543    find_x_method! {
544        body, geom, joint, site, camera, light, frame, actuator, sensor, flex, pair, equality, exclude, tendon,
545        numeric, text, tuple, key, mesh, hfield, skin, texture, material, plugin
546    }
547
548    find_x_method_direct! { default }
549
550    /// Returns an immutable reference to the world body.
551    /// # Panics
552    /// Panics if the "world" body is not found.
553    pub fn world_body(&self) -> &MjsBody {
554        self.body("world").unwrap()
555    }
556
557    /// Returns a mutable reference to the world body.
558    /// # Panics
559    /// Panics if the "world" body is not found.
560    pub fn world_body_mut(&mut self) -> &mut MjsBody {
561        self.body_mut("world").unwrap()
562    }
563}
564
565/// Public attributes.
566impl MjSpec {
567    string_set_get_with! {
568        [ffi, ffi_mut] modelname; "model name.";
569        [ffi, ffi_mut] comment; "comment at top of XML.";
570        [ffi, ffi_mut] modelfiledir; "path to model file.";
571    }
572
573    getter_setter! {
574        with, get, [
575            [ffi, ffi_mut] compiler: &MjsCompiler; "compiler options.";
576            [ffi, ffi_mut] stat: &MjStatistic; "statistic overrides.";
577            [ffi, ffi_mut] visual: &MjVisual; "visualization options.";
578            [ffi, ffi_mut] option: &MjOption; "simulation options.";
579        ]
580    }
581
582    getter_setter! {
583        with, get, set, [
584            [ffi, ffi_mut] strippath: bool; "whether to strip paths from mesh files.";
585            [ffi, ffi_mut] hasImplicitPluginElem: bool; "already encountered an implicit plugin sensor/actuator.";
586        ]
587    }
588
589    getter_setter! {
590        get, [
591            [ffi] memory: MjtSize;     "number of bytes in arena+stack memory.";
592            [ffi] nemax: i32;             "max number of equality constraints.";
593            [ffi] nuserdata: i32;              "number of mjtNums in userdata.";
594            [ffi] nuser_body: i32;            "number of mjtNums in body_user.";
595            [ffi] nuser_jnt: i32;              "number of mjtNums in jnt_user.";
596            [ffi] nuser_geom: i32;            "number of mjtNums in geom_user.";
597            [ffi] nuser_site: i32;            "number of mjtNums in site_user.";
598            [ffi] nuser_cam: i32;              "number of mjtNums in cam_user.";
599            [ffi] nuser_tendon: i32;        "number of mjtNums in tendon_user.";
600            [ffi] nuser_actuator: i32;    "number of mjtNums in actuator_user.";
601            [ffi] nuser_sensor: i32;        "number of mjtNums in sensor_user.";
602            [ffi] nkey: i32;                             "number of keyframes.";
603        ]
604    }
605}
606
607/// Methods for adding non-tree elements.
608impl MjSpec {
609    add_x_method! { actuator, pair, equality, tendon, mesh, material }
610    add_x_method_no_default! {
611        sensor, flex, exclude, numeric, text, tuple, key, plugin,
612        hfield, skin, texture
613        // Wrap
614    }
615
616    /// Adds a new `<default>` element.
617    ///
618    /// # Panics
619    /// Panics when `class_name` already exists or `parent_class_name` doesn't exist.
620    /// Also panics when the `class_name` or `parent_class_name` contain '\0' characters.
621    ///
622    /// Use [`MjSpec::try_add_default`] for a fallible alternative.
623    pub fn add_default(&mut self, class_name: &str, parent_class_name: Option<&str>) -> &mut MjsDefault {
624        self.try_add_default(class_name, parent_class_name).unwrap()
625    }
626
627    /// Fallible version of [`MjSpec::add_default`].
628    /// # Returns
629    /// On success, returns a mutable reference to the newly created [`MjsDefault`].
630    /// # Errors
631    /// Returns [`MjEditError::AlreadyExists`] when `class_name` already exists.
632    /// Returns [`MjEditError::NotFound`] when `parent_class_name` doesn't exist.
633    /// # Panics
634    /// When the `class_name` or `parent_class_name` contain '\0' characters, a panic occurs.
635    pub fn try_add_default(&mut self, class_name: &str, parent_class_name: Option<&str>) -> Result<&mut MjsDefault, MjEditError> {
636        let c_class_name = CString::new(class_name).unwrap();
637
638        let parent_ptr = if let Some(name) = parent_class_name {
639                self.default(name).ok_or(MjEditError::NotFound)?
640        } else {
641            ptr::null()
642        };
643
644        unsafe {
645            let ptr_default = mjs_addDefault(
646                self.ffi_mut(),
647                c_class_name.as_ptr(),
648                parent_ptr
649            );
650            if ptr_default.is_null() {
651                Err(MjEditError::AlreadyExists)
652            }
653            else {
654                Ok(&mut *ptr_default)
655            }
656        }
657    }
658}
659
660/// Mutable iterator over items in [`MjSpec`].
661#[derive(Debug)]
662pub struct MjsSpecItemIterMut<'a, T> {
663    /// Pointer to the wrapped mjSpec pointer.
664    /// This is the FFI type wrapped inside [`MjSpec`].
665    ffi_ptr: *mut mjSpec,
666    /// Last obtained element in the iterator.
667    /// This CAN be null, and this iterator it uses the null to detect
668    /// end of iteration. 
669    last: *mut mjsElement,
670    /// Used for generic implementation of iterator's methods.
671    item_type: PhantomData<&'a mut T>
672}
673
674/// Immutable iterator over items in [`MjSpec`].
675#[derive(Debug, Clone)]
676pub struct MjsSpecItemIter<'a, T> {
677    /// Pointer to the wrapped mjSpec pointer.
678    /// This is the FFI type wrapped inside [`MjSpec`].
679    ffi_ptr: *const mjSpec,
680    /// Last obtained element in the iterator.
681    /// This CAN be null, and this iterator it uses the null to detect
682    /// end of iteration. 
683    last: *mut mjsElement,
684    /// Used for generic implementation of iterator's methods.
685    item_type: PhantomData<&'a T>
686}
687
688impl<'a, T: SpecObject> MjsSpecItemIterMut<'a, T> {
689    fn new(root: &'a mut MjSpec) -> Self {
690        let last = unsafe { mjs_firstElement(root.0.as_ptr(), T::OBJ_TYPE) };
691        Self { ffi_ptr: root.0.as_ptr(), last, item_type: PhantomData }
692    }
693}
694
695impl<'a, T: SpecObject> MjsSpecItemIter<'a, T> {
696    fn new(root: &'a MjSpec) -> Self {
697        // SAFETY: mjs_firstElement does not mutate mjsSpec, thus as_ptr is valid to be case to *mut
698        // from the const reference to its wrapper.
699        let last = unsafe { mjs_firstElement(root.0.as_ptr(), T::OBJ_TYPE) };
700        Self { ffi_ptr: root.0.as_ptr(), last, item_type: PhantomData }
701    }
702}
703
704impl<'a, T: SpecObject + 'a> Iterator for MjsSpecItemIterMut<'a, T> {
705    type Item = &'a mut T;
706
707    fn next(&mut self) -> Option<Self::Item> {
708        if self.last.is_null() {
709            return None;
710        }
711        unsafe {
712            let out = T::from_element_as_ptr_mut(self.last).as_mut();
713            // Use as_ptr() instead of ffi_mut() to avoid creating &mut mjSpec,
714            // which would alias with previously yielded &mut items.
715            self.last = mjs_nextElement(self.ffi_ptr, self.last);
716            out
717        }
718    }
719}
720
721impl<'a, T: SpecObject + 'a> Iterator for MjsSpecItemIter<'a, T> {
722    type Item = &'a T;
723
724    fn next(&mut self) -> Option<Self::Item> {
725        if self.last.is_null() {
726            return None;
727        }
728        unsafe {
729            let out = T::from_element_as_ptr_mut(self.last).as_ref();
730            // SAFETY: mjs_nextElement does not mutate mjsSpec, thus as_ptr is valid to be case to *mut
731            // from the const reference to its wrapper.
732            self.last = mjs_nextElement(self.ffi_ptr, self.last);
733            out
734        }
735    }
736}
737
738// Once self.last is null, next() always returns None.
739impl<'a, T: SpecObject + 'a> std::iter::FusedIterator for MjsSpecItemIterMut<'a, T> {}
740impl<'a, T: SpecObject + 'a> std::iter::FusedIterator for MjsSpecItemIter<'a, T> {}
741
742/// Iterator methods.
743impl MjSpec {
744    spec_get_iter! {
745        body, geom, joint, site, camera, light, frame, actuator, sensor, flex, pair, equality,
746        exclude, tendon, numeric, text, tuple, key, mesh, hfield, skin, texture, material, plugin
747    }
748}
749
750impl Default for MjSpec {
751    fn default() -> Self {
752        Self::new()
753    }
754}
755
756impl Drop for MjSpec {
757    fn drop(&mut self) {
758        // SAFETY: self.0 is a valid non-null mjSpec pointer; called exactly once
759        // in Drop.
760        unsafe { mj_deleteSpec(self.0.as_ptr()); }
761    }
762}
763
764impl Clone for MjSpec {
765    /// Creates a deep copy of this [`MjSpec`].
766    ///
767    /// # Panics
768    /// Panics if MuJoCo fails to allocate the cloned spec.
769    /// Use [`MjSpec::try_clone`] for a fallible alternative.
770    fn clone(&self) -> Self {
771        self.try_clone().expect("MuJoCo failed to clone MjSpec")
772    }
773}
774
775/***************************
776** Site specification
777***************************/
778mjs_struct!(Site [SpecObject]);
779impl MjsSite {
780    getter_setter! {
781        [&] with, get, [
782            // frame, size
783            pos:  &[f64; 3];              "position.";
784            quat: &[f64; 4];              "orientation.";
785            alt:  &MjsOrientation;        "alternative orientation.";
786            fromto: &[f64; 6];            "alternative for capsule, cylinder, box, ellipsoid.";
787            size: &[f64; 3];              "geom size.";
788
789            // visual
790            rgba: &[f32; 4];              "rgba when material is omitted.";
791    ]}
792
793    getter_setter!([&] with, get, set, [
794        type_ + _: MjtGeom;               "geom type.";
795        group: i32;                       "group.";
796    ]);
797
798    userdata_method!(f64);
799
800    string_set_get_with! {[&]
801        material; "name of material.";
802    }
803}
804
805/***************************
806** Joint specification
807***************************/
808mjs_struct!(Joint [SpecObject]);
809impl MjsJoint {
810    getter_setter! {
811        [&] with, get, [
812            // kinematics
813            pos:     &[f64; 3];         "anchor position.";
814            axis:    &[f64; 3];         "joint axis.";
815            ref_ + _:    &f64;          "value at reference configuration: qpos0.";
816            springdamper: &[f64; 2];    "timeconst, dampratio.";
817
818            // stiffness
819            stiffness: &[f64; mjNPOLY as usize + 1];            "stiffness coefficient.";
820
821            // limits
822            range:   &[f64; 2];         "joint limits.";
823            solref_limit: &[MjtNum; mjNREF as usize];  "solver reference: joint limits.";
824            solimp_limit: &[MjtNum; mjNIMP as usize];  "solver impedance: joint limits.";
825            actfrcrange: &[f64; 2];     "actuator force limits.";
826
827            // dof properties
828            damping: &[f64; mjNPOLY as usize + 1];                 "damping coefficient.";
829            solref_friction: &[MjtNum; mjNREF as usize]; "solver reference: dof friction.";
830            solimp_friction: &[MjtNum; mjNIMP as usize]; "solver impedance: dof friction.";
831        ]
832    }
833
834    getter_setter!([&] with, get, set, [
835        type_ + _: MjtJoint;           "joint type.";
836        group: i32;                    "joint group.";
837        springref: f64;               "spring reference value: qpos_spring.";
838        margin: f64;                  "margin value for joint limit detection.";
839        armature: f64;                "armature inertia (mass for slider).";
840        frictionloss: f64;            "friction loss.";
841    ]);
842
843    getter_setter! {
844        [&] with, get, set, [
845            align: MjtAlignFree [force];       "align free joint with body com (mjtAlignFree).";
846            limited: MjtLimited [force];       "does joint have limits (mjtLimited).";
847            actfrclimited: MjtLimited [force]; "are actuator forces on joint limited (mjtLimited).";
848        ]
849    }
850
851    getter_setter! {
852        [&] with, get, set, [
853            actgravcomp: bool;         "is gravcomp force applied via actuators.";
854        ]
855    }
856
857    userdata_method!(f64);
858}
859
860/***************************
861** Geom specification
862***************************/
863mjs_struct!(Geom [SpecObject]);
864impl MjsGeom {
865    getter_setter! {
866        [&] with, get, [
867            pos: &[f64; 3];                         "geom position.";
868            quat: &[f64; 4];                        "geom orientation.";
869            alt: &MjsOrientation;                   "alternative orientation.";
870            fromto: &[f64; 6];                      "alternative for capsule, cylinder, box, ellipsoid.";
871            size: &[f64; 3];                        "geom size.";
872            rgba: &[f32; 4];                        "rgba when material is omitted.";
873            friction: &[f64; 3];                    "one-sided friction coefficients: slide, roll, spin.";
874            solref: &[MjtNum; mjNREF as usize];     "solver reference.";
875            solimp: &[MjtNum; mjNIMP as usize];     "solver impedance.";
876            fluid_coefs: &[MjtNum; 5];              "ellipsoid-fluid interaction coefs."
877        ]
878    }
879
880    getter_setter! {
881        get, [
882            plugin: &MjsPlugin;                     "sdf plugin.";
883        ]
884    }
885
886    getter_setter!([&] with, get, set, [
887        type_ + _: MjtGeom;            "geom type.";
888        group: i32;                    "group.";
889        contype: i32;                  "contact type.";
890        conaffinity: i32;              "contact affinity.";
891        condim: i32;                   "contact dimensionality.";
892        priority: i32;                 "contact priority.";
893        solmix: f64;                   "solver mixing for contact pairs.";
894        margin: f64;                   "margin for contact detection.";
895        gap: f64;                      "additional contact detection buffer.";
896        mass: f64;                     "used to compute density.";
897        density: f64;                  "used to compute mass and inertia from volume or surface.";
898        typeinertia: MjtGeomInertia;   "selects between surface and volume inertia.";
899        fluid_ellipsoid: MjtNum;       "whether ellipsoid-fluid model is active.";
900        fitscale: f64;                 "scale mesh uniformly.";
901    ]);
902
903    userdata_method!(f64);
904
905    string_set_get_with! {[&]
906        meshname;   "mesh attached to geom.";
907        material;   "name of material.";
908        hfieldname; "heightfield attached to geom.";
909    }
910}
911
912/***************************
913** Camera specification
914***************************/
915mjs_struct!(Camera [SpecObject]);
916impl MjsCamera {
917    getter_setter! {
918        [&] with, get, [
919            pos: &[f64; 3];               "camera position.";
920            quat: &[f64; 4];              "camera orientation.";
921            alt: &MjsOrientation;         "alternative orientation.";
922            intrinsic: &[f32; 4];         "intrinsic parameters.";
923            sensor_size: &[f32; 2];       "sensor size.";
924            resolution: &[i32; 2];        "resolution.";
925            focal_length: &[f32; 2];      "focal length (length).";
926            focal_pixel: &[f32; 2];       "focal length (pixel).";
927            principal_length: &[f32; 2];  "principal point (length).";
928            principal_pixel: &[f32; 2];   "principal point (pixel).";
929        ]
930    }
931
932    getter_setter!([&] with, get, set, [
933        mode: MjtCamLight;              "camera mode.";
934        fovy: f64;                      "field of view in y direction.";
935        ipd: f64;                       "inter-pupillary distance for stereo.";
936        proj: MjtProjection;            "camera projection type.";
937        output: i32;                    "bit flags for output type.";
938    ]);
939
940    userdata_method!(f64);
941
942    string_set_get_with! {[&]
943        targetbody; "target body for tracking/targeting.";
944    }
945}
946
947/***************************
948** Light specification
949***************************/
950mjs_struct!(Light [SpecObject]);
951impl MjsLight {
952    getter_setter! {
953        [&] with, get, [
954            pos: &[f64; 3];               "light position.";
955            dir: &[f64; 3];               "light direction.";
956            ambient: &[f32; 3];           "ambient color.";
957            diffuse: &[f32; 3];           "diffuse color.";
958            specular: &[f32; 3];          "specular color.";
959            attenuation: &[f32; 3];       "OpenGL attenuation (quadratic model).";
960        ]
961    }
962
963    getter_setter!([&] with, get, set, [
964        mode: MjtCamLight;             "light mode.";
965        type_ + _: MjtLightType;       "light type.";
966        bulbradius: f32;               "bulb radius, for soft shadows.";
967        intensity: f32;                "intensity, in candelas.";
968        range: f32;                    "range of effectiveness.";
969        cutoff: f32;                   "OpenGL cutoff.";
970        exponent: f32;                 "OpenGL exponent.";
971    ]);
972
973    getter_setter! {
974        [&] with, get, set, [
975            active: bool;       "active flag.";
976            castshadow: bool;   "whether light cast shadows."
977        ]
978    }
979
980    string_set_get_with! {[&]
981        texture; "texture name for image lights.";
982        targetbody; "target body for targeting.";
983    }
984}
985
986/***************************
987** Frame specification
988***************************/
989mjs_struct!(Frame [SpecObject]);
990impl MjsFrame {
991    add_x_method_by_frame! { body, site, joint, geom, camera, light }
992
993    getter_setter! {
994        [&] with, get, [
995            pos: &[f64; 3];               "frame position.";
996            quat: &[f64; 4];              "frame orientation.";
997            alt: &MjsOrientation;         "alternative orientation.";
998        ]
999    }
1000
1001    string_set_get_with! {[&]
1002        childclass; "childclass name.";
1003    }
1004
1005    /// Add and return a child frame.
1006    ///
1007    /// Delegates to [`Self::try_add_frame`] and panics if allocation fails.
1008    /// # Panics
1009    /// Panics if MuJoCo fails to allocate the frame.
1010    pub fn add_frame(&mut self) -> &mut MjsFrame {
1011        self.try_add_frame().expect("mjs_addFrame returned null; allocation failed")
1012    }
1013
1014    /// Fallible version of [`Self::add_frame`].
1015    ///
1016    /// # Errors
1017    /// Returns [`MjEditError::AllocationFailed`] when MuJoCo fails to allocate
1018    /// the frame, instead of panicking.
1019    pub fn try_add_frame(&mut self) -> Result<&mut MjsFrame, MjEditError> {
1020        // SAFETY: element_mut_pointer() reads `self.element`, valid for any live MjsFrame.
1021        // mjs_getParent returns non-null because every Rust-API MjsFrame was created via
1022        // mjs_addFrame, which always calls SetParent(body).
1023        let parent_body = unsafe { mjs_getParent(self.element_mut_pointer()) };
1024        debug_assert!(!parent_body.is_null(), "mjs_getParent returned null; frame has no parent body");
1025        let ptr = unsafe { mjs_addFrame(parent_body, self) };
1026        // SAFETY: ptr.as_mut() returns None for null, handled by ok_or; when non-null the
1027        // pointee is properly aligned and initialized by C++ operator new, and freshly
1028        // allocated so no existing Rust reference aliases it for the returned lifetime.
1029        unsafe { ptr.as_mut() }.ok_or(MjEditError::AllocationFailed)
1030    }
1031}
1032
1033/* Non-tree elements */
1034
1035/***************************
1036** Actuator specification
1037***************************/
1038mjs_struct!(Actuator [SpecObject]);
1039impl MjsActuator {
1040    getter_setter! {
1041        [&] with, get, [
1042            gear: &[f64; 6];                            "gear parameters.";
1043            gainprm: &[f64; mjNGAIN as usize];          "gain parameters.";
1044            biasprm: &[f64; mjNBIAS as usize];          "bias parameters.";
1045            dynprm: &[f64; mjNDYN as usize];            "dynamic parameters.";
1046            lengthrange: &[f64; 2];                     "transmission length range.";
1047            damping: &[f64; mjNPOLY as usize + 1];      "damping coefficient.";
1048            ctrlrange: &[f64; 2];                       "control range.";
1049            forcerange: &[f64; 2];                      "force range.";
1050            actrange: &[f64; 2];                        "activation range.";
1051        ]
1052    }
1053
1054    getter_setter! {
1055        get, [
1056            plugin: &MjsPlugin;                     "actuator plugin.";
1057        ]
1058    }
1059
1060    getter_setter!([&] with, get, set, [
1061        gaintype: MjtGain;             "gain type.";
1062        biastype: MjtBias;             "bias type.";
1063        dyntype: MjtDyn;               "dyn type.";
1064        group: i32;                    "group.";
1065        actdim: i32;                   "number of activation variables.";
1066        trntype: MjtTrn;               "transmission type.";
1067        cranklength: f64;              "crank length, for slider-crank.";
1068        inheritrange: f64;             "automatic range setting for position and intvelocity.";
1069        armature: f64;                 "armature inertia.";
1070        nsample: i32;                  "number of samples in history buffer.";
1071        interp: i32;                   "interpolation order (0=ZOH, 1=linear, 2=cubic).";
1072        delay: f64;                    "delay time in seconds; 0: no delay.";
1073    ]);
1074
1075    getter_setter! {
1076        [&] with, get, set, [
1077            ctrllimited: MjtLimited [force];        "are control limits defined.";
1078            forcelimited: MjtLimited [force];       "are force limits defined.";
1079        ]
1080    }
1081
1082    getter_setter! {
1083        [&] with, get, set, [
1084            actlimited: MjtLimited [force];         "are activation limits defined.";
1085        ]
1086    }
1087
1088    getter_setter! {
1089        [&] with, get, set, [
1090            actearly: bool;                "apply next activations to qfrc.";
1091        ]
1092    }
1093
1094    userdata_method!(f64);
1095
1096    string_set_get_with! {[&]
1097        target;                 "name of transmission target.";
1098        refsite;                "reference site, for site transmission.";
1099        slidersite;             "site defining cylinder, for slider-crank.";
1100    }
1101}
1102
1103
1104/// Converts the error string returned by MuJoCo's `mjs_setToX` actuator
1105/// configuration functions into a [`Result`].
1106///
1107/// Those functions return an empty string on success and a non-empty,
1108/// NUL-terminated message describing the rejected parameter on failure.
1109fn actuator_set_result(c_err_msg: *const c_char) -> Result<(), MjEditError> {
1110    // SAFETY: MuJoCo's error messages are always NUL terminated.
1111    let err_msg = unsafe { CStr::from_ptr(c_err_msg) }.to_string_lossy();
1112    if err_msg.is_empty() {
1113        Ok(())
1114    }
1115    else {
1116        Err(MjEditError::InvalidParameter(err_msg.into_owned()))
1117    }
1118}
1119
1120/* Actuator configuration structs.
1121** Each `set_to_*` method taking optional (nullable in C) parameters has its own config struct.
1122** Build either with struct-update syntax or with the chainable `with_*` builder methods, e.g.
1123** `PositionConfig { kp: 10.0, kv: Some(2.0), ..Default::default() }` or
1124** `PositionConfig::default().with_kp(10.0).with_kv(2.0)`. Optional fields default to `None`,
1125** leaving the corresponding actuator parameter at its MuJoCo default; the `with_*` setters take
1126** the inner value directly and wrap it in `Some`. */
1127
1128/// Configuration for [`MjsActuator::set_to_position`].
1129#[derive(Clone, Copy, Debug, Default, PartialEq)]
1130pub struct PositionConfig {
1131    /// Proportional (position) gain.
1132    pub kp: f64,
1133    /// Automatic range-inheritance factor (0 disables it).
1134    pub inheritrange: f64,
1135    /// Velocity feedback gain. Mutually exclusive with `dampratio`.
1136    pub kv: Option<f64>,
1137    /// Damping ratio. Mutually exclusive with `kv`.
1138    pub dampratio: Option<f64>,
1139    /// First-order activation-filter time constant.
1140    pub timeconst: Option<f64>,
1141}
1142
1143impl PositionConfig {
1144    getter_setter! {
1145        with, [
1146            kp: f64;            "the proportional (position) gain.";
1147            inheritrange: f64;  "the automatic range-inheritance factor.";
1148            kv: f64;            "the velocity feedback gain (mutually exclusive with dampratio).";
1149            dampratio: f64;     "the damping ratio (mutually exclusive with kv).";
1150            timeconst: f64;     "the first-order activation-filter time constant.";
1151        ]
1152    }
1153}
1154
1155/// Configuration for [`MjsActuator::set_to_int_velocity`]. Same parameters as [`PositionConfig`].
1156#[derive(Clone, Copy, Debug, Default, PartialEq)]
1157pub struct IntVelocityConfig {
1158    /// Proportional gain.
1159    pub kp: f64,
1160    /// Automatic range-inheritance factor (0 disables it).
1161    pub inheritrange: f64,
1162    /// Velocity feedback gain. Mutually exclusive with `dampratio`.
1163    pub kv: Option<f64>,
1164    /// Damping ratio. Mutually exclusive with `kv`.
1165    pub dampratio: Option<f64>,
1166    /// First-order activation-filter time constant.
1167    pub timeconst: Option<f64>,
1168}
1169
1170impl IntVelocityConfig {
1171    getter_setter! {
1172        with, [
1173            kp: f64;            "the proportional gain.";
1174            inheritrange: f64;  "the automatic range-inheritance factor.";
1175            kv: f64;            "the velocity feedback gain (mutually exclusive with dampratio).";
1176            dampratio: f64;     "the damping ratio (mutually exclusive with kv).";
1177            timeconst: f64;     "the first-order activation-filter time constant.";
1178        ]
1179    }
1180}
1181
1182/// Configuration for [`MjsActuator::set_to_dc_motor`].
1183///
1184/// Each optional field defaults to `None`, disabling the corresponding feature.
1185#[derive(Clone, Copy, Debug, Default, PartialEq)]
1186pub struct DcMotorConfig {
1187    /// Electrical resistance.
1188    pub resistance: f64,
1189    /// Input mode selector.
1190    pub input_mode: i32,
1191    /// Torque and back-EMF constants `[Kt, Ke]`.
1192    pub motorconst: Option<[f64; 2]>,
1193    /// Nominal ratings `[voltage, stall_torque, no_load_speed]`.
1194    pub nominal: Option<[f64; 3]>,
1195    /// Saturation `[tau_max, i_max, di_dt_max]`.
1196    pub saturation: Option<[f64; 3]>,
1197    /// Inductance `[L, te]`.
1198    pub inductance: Option<[f64; 2]>,
1199    /// Cogging `[amplitude, periodicity, phase]`.
1200    pub cogging: Option<[f64; 3]>,
1201    /// Controller `[kp, ki, kd, slewmax, Imax, v_max]`.
1202    pub controller: Option<[f64; 6]>,
1203    /// Thermal `[R_th, C, tau_th, alpha, T0, T_ambient]`.
1204    pub thermal: Option<[f64; 6]>,
1205    /// LuGre friction `[stiffness, damping, coulomb, static, stribeck]`.
1206    pub lugre: Option<[f64; 5]>,
1207}
1208
1209impl DcMotorConfig {
1210    getter_setter! {
1211        with, [
1212            resistance: f64;       "the electrical resistance.";
1213            input_mode: i32;       "the input mode selector.";
1214            motorconst: [f64; 2];  "the torque and back-EMF constants [Kt, Ke].";
1215            nominal: [f64; 3];     "the nominal ratings [voltage, stall_torque, no_load_speed].";
1216            saturation: [f64; 3];  "the saturation [tau_max, i_max, di_dt_max].";
1217            inductance: [f64; 2];  "the inductance [L, te].";
1218            cogging: [f64; 3];     "the cogging [amplitude, periodicity, phase].";
1219            controller: [f64; 6];  "the controller [kp, ki, kd, slewmax, Imax, v_max].";
1220            thermal: [f64; 6];     "the thermal [R_th, C, tau_th, alpha, T0, T_ambient].";
1221            lugre: [f64; 5];       "the LuGre friction [stiffness, damping, coulomb, static, stribeck].";
1222        ]
1223    }
1224}
1225
1226impl MjsActuator {
1227    /// Configure the actuator to be a motor.
1228    pub fn set_to_motor(&mut self) {
1229        // mjs_setToMotor cannot fail; it always returns an empty string.
1230        unsafe { mjs_setToMotor(self) };
1231    }
1232
1233    /// Configure the actuator to be a positional-target motor (with a proportional regulator).
1234    /// # Errors
1235    /// Returns [`MjEditError::InvalidParameter`] when the configuration is rejected, e.g. `kv` and
1236    /// `dampratio` are both set, a value that must be non-negative is negative, or `inheritrange`
1237    /// is set together with a control range.
1238    pub fn set_to_position(&mut self, config: PositionConfig) -> Result<(), MjEditError> {
1239        let PositionConfig { kp, inheritrange, mut kv, mut dampratio, mut timeconst } = config;
1240        let c_err_msg = unsafe { mjs_setToPosition(
1241            self, kp,
1242            kv.as_mut().map_or(ptr::null_mut(), |x| x),
1243            dampratio.as_mut().map_or(ptr::null_mut(), |x| x),
1244            timeconst.as_mut().map_or(ptr::null_mut(), |x| x),
1245            inheritrange
1246        ) };
1247        actuator_set_result(c_err_msg)
1248    }
1249
1250    /// Configure the actuator to be an integrated-velocity servo. Behaves like
1251    /// [`MjsActuator::set_to_position`], but integrates the control signal into an activation
1252    /// variable.
1253    /// # Errors
1254    /// Returns [`MjEditError::InvalidParameter`] when `inheritrange` is set together with an
1255    /// activation range.
1256    pub fn set_to_int_velocity(&mut self, config: IntVelocityConfig) -> Result<(), MjEditError> {
1257        let IntVelocityConfig { kp, inheritrange, mut kv, mut dampratio, mut timeconst } = config;
1258        let c_err_msg = unsafe { mjs_setToIntVelocity(
1259            self, kp,
1260            kv.as_mut().map_or(ptr::null_mut(), |x| x),
1261            dampratio.as_mut().map_or(ptr::null_mut(), |x| x),
1262            timeconst.as_mut().map_or(ptr::null_mut(), |x| x),
1263            inheritrange
1264        ) };
1265        actuator_set_result(c_err_msg)
1266    }
1267
1268    /// Configure the actuator to be a velocity servo with velocity feedback gain `kv`.
1269    pub fn set_to_velocity(&mut self, kv: f64) {
1270        // mjs_setToVelocity cannot fail; it always returns an empty string.
1271        unsafe { mjs_setToVelocity(self, kv) };
1272    }
1273
1274    /// Configure the actuator to be a damper with damping coefficient `kv`. The applied force is
1275    /// proportional to velocity and modulated by the (non-negative) control input.
1276    /// # Errors
1277    /// Returns [`MjEditError::InvalidParameter`] when `kv` is negative or the control range is
1278    /// negative.
1279    pub fn set_to_damper(&mut self, kv: f64) -> Result<(), MjEditError> {
1280        actuator_set_result(unsafe { mjs_setToDamper(self, kv) })
1281    }
1282
1283    /// Configure the actuator to be a hydraulic or pneumatic cylinder. `timeconst` is the
1284    /// activation filter time constant, `bias` is added to the force, and the effective area is
1285    /// `area`; if `diameter` is non-negative the area is computed from it instead (pass a negative
1286    /// `diameter` to use `area` directly).
1287    pub fn set_to_cylinder(&mut self, timeconst: f64, bias: f64, area: f64, diameter: f64) {
1288        // mjs_setToCylinder cannot fail; it always returns an empty string.
1289        unsafe { mjs_setToCylinder(self, timeconst, bias, area, diameter) };
1290    }
1291
1292    /// Configure the actuator to be a muscle. `timeconst` holds the activation and deactivation
1293    /// time constants, `range` the operating-length range, and the remaining scalars the muscle
1294    /// force-length-velocity parameters. A negative value for any array entry or scalar (except
1295    /// `tausmooth`) leaves the corresponding muscle default in place.
1296    /// # Errors
1297    /// Returns [`MjEditError::InvalidParameter`] when `tausmooth` is negative.
1298    #[allow(clippy::too_many_arguments)]
1299    pub fn set_to_muscle(
1300        &mut self, mut timeconst: [f64; 2], tausmooth: f64, mut range: [f64; 2],
1301        force: f64, scale: f64, lmin: f64, lmax: f64, vmax: f64, fpmax: f64, fvmax: f64
1302    ) -> Result<(), MjEditError>
1303    {
1304        let c_err_msg = unsafe { mjs_setToMuscle(
1305            self, &mut timeconst, tausmooth, &mut range,
1306            force, scale, lmin, lmax, vmax, fpmax, fvmax
1307        ) };
1308        actuator_set_result(c_err_msg)
1309    }
1310
1311    /// Configure the actuator to be an active-adhesion actuator with the given `gain`.
1312    /// # Errors
1313    /// Returns [`MjEditError::InvalidParameter`] when `gain` is negative or the control range is
1314    /// negative.
1315    pub fn set_to_adhesion(&mut self, gain: f64) -> Result<(), MjEditError> {
1316        actuator_set_result(unsafe { mjs_setToAdhesion(self, gain) })
1317    }
1318
1319    /// Configure the actuator to be a DC motor.
1320    /// # Errors
1321    /// Returns [`MjEditError::InvalidParameter`] when MuJoCo cannot derive a positive motor
1322    /// constant or resistance, or when an inductance, thermal resistance, or thermal capacitance
1323    /// value is out of its allowed range.
1324    pub fn set_to_dc_motor(&mut self, config: DcMotorConfig) -> Result<(), MjEditError> {
1325        let DcMotorConfig {
1326            resistance, input_mode,
1327            mut motorconst, mut nominal, mut saturation, mut inductance,
1328            mut cogging, mut controller, mut thermal, mut lugre
1329        } = config;
1330        let c_err_msg = unsafe { mjs_setToDCMotor(
1331            self,
1332            motorconst.as_mut().map_or(ptr::null_mut(), |x| x),
1333            resistance,
1334            nominal.as_mut().map_or(ptr::null_mut(), |x| x),
1335            saturation.as_mut().map_or(ptr::null_mut(), |x| x),
1336            inductance.as_mut().map_or(ptr::null_mut(), |x| x),
1337            cogging.as_mut().map_or(ptr::null_mut(), |x| x),
1338            controller.as_mut().map_or(ptr::null_mut(), |x| x),
1339            thermal.as_mut().map_or(ptr::null_mut(), |x| x),
1340            lugre.as_mut().map_or(ptr::null_mut(), |x| x),
1341            input_mode
1342        ) };
1343        actuator_set_result(c_err_msg)
1344    }
1345}
1346
1347/***************************
1348** Sensor specification
1349***************************/
1350mjs_struct!(Sensor [SpecObject]);
1351impl MjsSensor {
1352    getter_setter! {
1353        [&] with, get, [
1354            intprm: &[i32; mjNSENS as usize];            "integer parameters.";
1355            interval: &[f64; 2];                         "[period, time_prev] in seconds.";
1356        ]
1357    }
1358
1359    getter_setter! {
1360        get, [
1361            plugin: &MjsPlugin;                     "sensor plugin.";
1362        ]
1363    }
1364
1365    getter_setter!([&] with, get, set, [
1366        type_ + _: MjtSensor;          "sensor type.";
1367        objtype: MjtObj { check_objtype, "[`MjEditError::InvalidParameter`] when the object type is not a real object type (i.e. not below [`MjtObj::mjNOBJECT`])" } => MjEditError;
1368                                       "object type the sensor refers to.";
1369        reftype: MjtObj { check_objtype, "[`MjEditError::InvalidParameter`] when the reference type is not a real object type (i.e. not below [`MjtObj::mjNOBJECT`])" } => MjEditError;
1370                                       "type of referenced object.";
1371        datatype: MjtDataType;         "data type.";
1372        cutoff: f64;                   "cutoff for real and positive datatypes.";
1373        noise: f64;                    "noise stdev.";
1374        needstage: MjtStage;           "compute stage needed to simulate sensor.";
1375        dim: i32;                      "number of scalar outputs.";
1376        nsample: i32;                  "number of samples in history buffer.";
1377        interp: i32;                   "interpolation order (0=ZOH, 1=linear, 2=cubic).";
1378        delay: f64;                    "delay time in seconds; 0: no delay.";
1379    ]);
1380
1381    userdata_method!(f64);
1382
1383    string_set_get_with! {[&]
1384        refname; "name of referenced object.";
1385        objname; "name of sensorized object.";
1386    }
1387}
1388
1389/***************************
1390** Flex specification
1391***************************/
1392mjs_struct!(Flex [SpecObject]);
1393impl MjsFlex {
1394    getter_setter! {
1395        [&] with, get, [
1396            rgba: &[f32; 4];                                "rgba when material is omitted.";
1397            friction: &[f64; 3];                            "contact friction vector.";
1398            solref: &[MjtNum; mjNREF as usize];             "solref for the pair.";
1399            solimp: &[MjtNum; mjNIMP as usize];             "solimp for the pair.";
1400            size: &[f64; 3];                                "vertex bounding box half sizes in qpos0.";
1401            cellcount: &[i32; 3];                           "grid cell count for finite cell method.";
1402        ]
1403    }
1404
1405    getter_setter! {
1406        [&] with, get, set, [
1407            young: f64;                    "elastic stiffness.";
1408            group: i32;                    "group.";
1409            contype: i32;                  "contact type.";
1410            conaffinity: i32;              "contact affinity.";
1411            condim: i32;                   "contact dimensionality.";
1412            priority: i32;                 "contact priority.";
1413            solmix: f64;                   "solver mixing for contact pairs.";
1414            margin: f64;                   "margin for contact detection.";
1415            gap: f64;                      "additional contact detection buffer.";
1416
1417            dim: i32;                "element dimensionality.";
1418            radius: f64;             "radius around primitive element.";
1419            activelayers: i32;       "number of active element layers in 3D.";
1420            edgestiffness: f64;      "edge stiffness.";
1421            edgedamping: f64;        "edge damping.";
1422            poisson: f64;            "Poisson's ratio.";
1423            damping: f64;            "Rayleigh's damping.";
1424            thickness: f64;          "thickness (2D only).";
1425            elastic2d: i32;          "2D passive forces; 0: none, 1: bending, 2: stretching, 3: both.";
1426            order: i32;              "interpolation order (1: trilinear, 2: quadratic).";
1427        ]
1428    }
1429
1430    getter_setter! {
1431        [&] with, get, set, [
1432            internal: bool;       "enable internal collisions.";
1433            flatskin: bool;       "render flex skin with flat shading.";
1434            passive: bool;        "mode for passive collisions.";
1435        ]        
1436    }
1437
1438    getter_setter! {
1439        [&] with, get, set, [
1440            selfcollide: MjtFlexSelf [force];        "mode for flex self collision.";
1441        ]
1442    }
1443
1444    string_set_get_with! {[&]
1445        material; "name of material used for rendering.";
1446    }
1447
1448    vec_string_set_append! {
1449        nodebody; "node body names.";
1450        vertbody; "vertex body names.";
1451    }
1452
1453    vec_set_get! {
1454        node: f64;      "node positions.";
1455        vert: f64;      "vertex positions.";
1456    }
1457
1458    vec_set! {
1459        texcoord: f32;          "vertex texture coordinates.";
1460        elem: i32;              "element vertex ids.";
1461    }
1462
1463    vec_set! {
1464        [unsafe: "The slice must have exactly `(dim + 1) * nelem` entries and every entry \
1465                  must be a valid index into the flex texture coordinates."
1466        ] elemtexcoord: i32 => i32; "element texture coordinates.";
1467    }
1468}
1469
1470/***************************
1471** Pair specification
1472***************************/
1473mjs_struct!(Pair [SpecObject]);
1474impl MjsPair {
1475    getter_setter! {
1476        [&] with, get, [
1477            friction: &[f64; 5];                            "contact friction vector.";
1478            solref: &[MjtNum; mjNREF as usize];             "solref for the pair.";
1479            solimp: &[MjtNum; mjNIMP as usize];             "solimp for the pair.";
1480            solreffriction: &[MjtNum; mjNREF as usize];     "solver reference, frictional directions.";
1481        ]
1482    }
1483
1484    getter_setter! {
1485        [&] with, get, set, [
1486            margin: f64;             "margin for contact detection.";
1487            gap: f64;         "additional contact detection buffer.";
1488            condim: i32;                   "contact dimensionality.";
1489        ]
1490    }
1491
1492    string_set_get_with! {[&]
1493        geomname1; "name of geom 1.";
1494        geomname2; "name of geom 2.";
1495    }
1496}
1497
1498/***************************
1499** Exclude specification
1500***************************/
1501mjs_struct!(Exclude [SpecObject]);
1502impl MjsExclude {
1503    string_set_get_with! {[&]
1504        bodyname1; "name of body 1.";
1505        bodyname2; "name of body 2.";
1506    }
1507}
1508
1509/***************************
1510** Equality specification
1511***************************/
1512mjs_struct!(Equality [SpecObject]);
1513impl MjsEquality {
1514    getter_setter! {
1515        [&] with, get, [
1516            data: &[f64; mjNEQDATA as usize];   "data array for equality parameters.";
1517            solref: &[f64; mjNREF as usize];    "solver reference.";         
1518            solimp: &[f64; mjNIMP as usize];    "solver impedance.";
1519        ]
1520    }
1521
1522    getter_setter! {[&] with, get, set, [
1523        active: bool;   "active flag.";
1524    ]}
1525
1526    getter_setter! {[&] with, get, set, [
1527        type_ + _: MjtEq;   "equality type.";
1528        objtype: MjtObj;    "type of both objects.";
1529    ]}
1530
1531    string_set_get_with! {[&]
1532        name1; "name of object 1";
1533        name2; "name of object 2";
1534    }
1535}
1536
1537/***************************
1538** Tendon specification
1539***************************/
1540mjs_struct!(Tendon [SpecObject]);
1541impl MjsTendon {
1542    getter_setter! {
1543        [&] with, get, [
1544            damping: &[f64; mjNPOLY as usize + 1];       "damping coefficient.";
1545            stiffness: &[f64; mjNPOLY as usize + 1];     "stiffness coefficient.";
1546            springlength: &[f64; 2];                    "spring length.";
1547            solref_friction: &[f64; mjNREF as usize];   "solver reference: tendon friction.";
1548            solimp_friction: &[f64; mjNIMP as usize];   "solver impedance: tendon friction.";
1549            range: &[f64; 2];                           "range.";
1550            actfrcrange: &[f64; 2];                     "actuator force limits.";
1551            solref_limit: &[f64; mjNREF as usize];      "solver reference: tendon limits.";
1552            solimp_limit: &[f64; mjNIMP as usize];      "solver impedance: tendon limits.";
1553            rgba: &[f32; 4];                            "rgba when material omitted.";
1554        ]
1555    }
1556
1557    getter_setter! {[&] with, get, set, [
1558        group: i32;         "group.";
1559        frictionloss: f64;  "friction loss.";
1560        armature: f64;      "inertia associated with tendon velocity.";
1561        margin: f64;        "margin value for tendon limit detection.";
1562        width: f64;         "width for rendering.";
1563    ]}
1564
1565    getter_setter! {
1566        [&] with, get, set, [
1567            limited: MjtLimited [force];       "does tendon have limits (mjtLimited).";
1568            actfrclimited: MjtLimited [force]; "does tendon have actuator force limits."
1569        ]
1570    }
1571
1572    userdata_method!(f64);
1573    string_set_get_with! {[&]
1574        material; "name of material for rendering.";
1575    }
1576
1577    /// Wrap a site corresponding to `name`, using the tendon.
1578    ///
1579    /// # Panics
1580    /// When the `name` contains '\0' characters.
1581    #[allow(deprecated)]
1582    pub fn wrap_site(&mut self, name: &str) -> &mut MjsWrap {
1583        self.try_wrap_site(name).expect("failed to wrap site")
1584    }
1585
1586    /// Fallible version of [`MjsTendon::wrap_site`].
1587    ///
1588    /// # Note
1589    ///
1590    /// <div class="warning">
1591    ///
1592    /// By default, MuJoCo aborts the process on an allocation failure instead of
1593    /// returning null. Under a non-default error configuration MuJoCo writes
1594    /// through the null pointer on allocation failure before returning, so the
1595    /// failure cannot be recovered soundly. Prefer the panicking
1596    /// [`MjsTendon::wrap_site`]. This method may be undeprecated in the future
1597    /// if MuJoCo's upstream C++ code is changed to return null recoverably.
1598    ///
1599    /// </div>
1600    ///
1601    /// # Errors
1602    /// Returns [`MjEditError::AllocationFailed`] if MuJoCo returns a null
1603    /// pointer.
1604    ///
1605    /// # Panics
1606    /// When the `name` contains '\0' characters.
1607    #[deprecated(
1608        since = "5.0.0",
1609        note = "allocation failure cannot be recovered soundly; use `wrap_site`"
1610    )]
1611    pub fn try_wrap_site(&mut self, name: &str) -> Result<&mut MjsWrap, MjEditError> {
1612        let cname = CString::new(name).unwrap();
1613        let wrap_ptr = unsafe { mjs_wrapSite(self, cname.as_ptr()) };
1614        unsafe { wrap_ptr.as_mut() }.ok_or(MjEditError::AllocationFailed)
1615    }
1616
1617    /// Wrap a geom corresponding to `name`, using the tendon.
1618    ///
1619    /// # Panics
1620    /// When `name` or `sidesite` contain '\0' characters.
1621    #[allow(deprecated)]
1622    pub fn wrap_geom(&mut self, name: &str, sidesite: &str) -> &mut MjsWrap {
1623        self.try_wrap_geom(name, sidesite).expect("failed to wrap geom")
1624    }
1625
1626    /// Fallible version of [`MjsTendon::wrap_geom`].
1627    ///
1628    /// # Note
1629    ///
1630    /// <div class="warning">
1631    ///
1632    /// By default, MuJoCo aborts the process on an allocation failure instead of
1633    /// returning null. Under a non-default error configuration MuJoCo writes
1634    /// through the null pointer on allocation failure before returning, so the
1635    /// failure cannot be recovered soundly. Prefer the panicking
1636    /// [`MjsTendon::wrap_geom`]. This method may be undeprecated in the future
1637    /// if MuJoCo's upstream C++ code is changed to return null recoverably.
1638    ///
1639    /// </div>
1640    ///
1641    /// # Errors
1642    /// Returns [`MjEditError::AllocationFailed`] if MuJoCo returns a null
1643    /// pointer.
1644    ///
1645    /// # Panics
1646    /// When `name` or `sidesite` contain '\0' characters.
1647    #[deprecated(
1648        since = "5.0.0",
1649        note = "allocation failure cannot be recovered soundly; use `wrap_geom`"
1650    )]
1651    pub fn try_wrap_geom(&mut self, name: &str, sidesite: &str) -> Result<&mut MjsWrap, MjEditError> {
1652        let cname = CString::new(name).unwrap();
1653        let csidesite = CString::new(sidesite).unwrap();
1654        let wrap_ptr = unsafe { mjs_wrapGeom(
1655            self,
1656            cname.as_ptr(), csidesite.as_ptr()
1657        ) };
1658        unsafe { wrap_ptr.as_mut() }.ok_or(MjEditError::AllocationFailed)
1659    }
1660
1661    /// Wrap a joint corresponding to `name`, using the tendon.
1662    ///
1663    /// # Panics
1664    /// When `name` contains '\0' characters.
1665    #[allow(deprecated)]
1666    pub fn wrap_joint(&mut self, name: &str, coef: f64) -> &mut MjsWrap {
1667        self.try_wrap_joint(name, coef).expect("failed to wrap joint")
1668    }
1669
1670    /// Fallible version of [`MjsTendon::wrap_joint`].
1671    ///
1672    /// # Note
1673    ///
1674    /// <div class="warning">
1675    ///
1676    /// By default, MuJoCo aborts the process on an allocation failure instead of
1677    /// returning null. Under a non-default error configuration MuJoCo writes
1678    /// through the null pointer on allocation failure before returning, so the
1679    /// failure cannot be recovered soundly. Prefer the panicking
1680    /// [`MjsTendon::wrap_joint`]. This method may be undeprecated in the future
1681    /// if MuJoCo's upstream C++ code is changed to return null recoverably.
1682    ///
1683    /// </div>
1684    ///
1685    /// # Errors
1686    /// Returns [`MjEditError::AllocationFailed`] if MuJoCo returns a null
1687    /// pointer.
1688    ///
1689    /// # Panics
1690    /// When `name` contains '\0' characters.
1691    #[deprecated(
1692        since = "5.0.0",
1693        note = "allocation failure cannot be recovered soundly; use `wrap_joint`"
1694    )]
1695    pub fn try_wrap_joint(&mut self, name: &str, coef: f64) -> Result<&mut MjsWrap, MjEditError> {
1696        let cname = CString::new(name).unwrap();
1697        let wrap_ptr = unsafe { mjs_wrapJoint(self, cname.as_ptr(), coef) };
1698        unsafe { wrap_ptr.as_mut() }.ok_or(MjEditError::AllocationFailed)
1699    }
1700
1701    /// Wrap a pulley using the tendon.
1702    #[allow(deprecated)]
1703    pub fn wrap_pulley(&mut self, divisor: f64) -> &mut MjsWrap {
1704        self.try_wrap_pulley(divisor).expect("failed to wrap pulley")
1705    }
1706
1707    /// Fallible version of [`MjsTendon::wrap_pulley`].
1708    ///
1709    /// # Note
1710    ///
1711    /// <div class="warning">
1712    ///
1713    /// By default, MuJoCo aborts the process on an allocation failure instead of
1714    /// returning null. Under a non-default error configuration MuJoCo writes
1715    /// through the null pointer on allocation failure before returning, so the
1716    /// failure cannot be recovered soundly. Prefer the panicking
1717    /// [`MjsTendon::wrap_pulley`]. This method may be undeprecated in the future
1718    /// if MuJoCo's upstream C++ code is changed to return null recoverably.
1719    ///
1720    /// </div>
1721    ///
1722    /// # Errors
1723    /// Returns [`MjEditError::AllocationFailed`] if MuJoCo returns a null
1724    /// pointer.
1725    #[deprecated(
1726        since = "5.0.0",
1727        note = "allocation failure cannot be recovered soundly; use `wrap_pulley`"
1728    )]
1729    pub fn try_wrap_pulley(&mut self, divisor: f64) -> Result<&mut MjsWrap, MjEditError> {
1730        let wrap_ptr = unsafe { mjs_wrapPulley(self, divisor) };
1731        unsafe { wrap_ptr.as_mut() }.ok_or(MjEditError::AllocationFailed)
1732    }
1733
1734    /// Return the number of wrap objects.
1735    pub fn wrap_num(&self) -> usize {
1736        unsafe { mjs_getWrapNum(self) as usize }
1737    }
1738
1739    /// Return an indexed wrap object.
1740    ///
1741    /// # Panics
1742    /// Panics if `i >= wrap_num()`. Use [`MjsTendon::try_wrap`] for a fallible alternative.
1743    pub fn wrap(&self, i: usize) -> &MjsWrap {
1744        self.try_wrap(i).unwrap()
1745    }
1746
1747    /// Fallible version of [`MjsTendon::wrap`].
1748    ///
1749    /// # Errors
1750    /// Returns [`MjEditError::IndexOutOfBounds`] if `i >= wrap_num()`.
1751    pub fn try_wrap(&self, i: usize) -> Result<&MjsWrap, MjEditError> {
1752        let len = self.wrap_num();
1753        // mjs_getWrap aborts the process via mju_error for an out-of-range index, so the bound is
1754        // checked here and turned into a recoverable error instead.
1755        if i >= len {
1756            return Err(MjEditError::IndexOutOfBounds { id: i, len });
1757        }
1758        let ptr = unsafe { mjs_getWrap(self, i as i32) };
1759        // SAFETY: index validated above; mjs_getWrap returns a non-null pointer for in-range indices.
1760        Ok(unsafe { &*ptr })
1761    }
1762
1763    /// Return a mutable indexed wrap object.
1764    ///
1765    /// # Panics
1766    /// Panics if `i >= wrap_num()`. Use [`MjsTendon::try_wrap_mut`] for a fallible alternative.
1767    pub fn wrap_mut(&mut self, i: usize) -> &mut MjsWrap {
1768        self.try_wrap_mut(i).unwrap()
1769    }
1770
1771    /// Fallible version of [`MjsTendon::wrap_mut`].
1772    ///
1773    /// # Errors
1774    /// Returns [`MjEditError::IndexOutOfBounds`] if `i >= wrap_num()`.
1775    pub fn try_wrap_mut(&mut self, i: usize) -> Result<&mut MjsWrap, MjEditError> {
1776        let len = self.wrap_num();
1777        if i >= len {
1778            return Err(MjEditError::IndexOutOfBounds { id: i, len });
1779        }
1780        let ptr = unsafe { mjs_getWrap(self, i as i32) };
1781        // SAFETY: see try_wrap().
1782        Ok(unsafe { &mut *ptr })
1783    }
1784}
1785
1786/***************************
1787** Wrap specification
1788***************************/
1789mjs_struct!(Wrap);
1790impl MjsWrap {
1791    getter_setter! {
1792        [&] with, get, set, [
1793            type_ + _: MjtWrap; "wrap type.";
1794        ]
1795    }
1796
1797    /// Return the side site element.
1798    pub fn side_site(&self) -> Option<&MjsSite> {
1799        let ptr = unsafe { mjs_getWrapSideSite(self) };
1800        if ptr.is_null() { None } else { Some(unsafe { &*ptr }) }
1801    }
1802
1803    /// Return the side site element mutably.
1804    pub fn side_site_mut(&mut self) -> Option<&mut MjsSite> {
1805        let ptr = unsafe { mjs_getWrapSideSite(self) };
1806        if ptr.is_null() { None } else { Some(unsafe { &mut *ptr }) }
1807    }
1808
1809    /// Return the wrap divisor.
1810    pub fn divisor(&self) -> f64 {
1811        unsafe { mjs_getWrapDivisor(self) }
1812    }
1813
1814    /// Return the wrap coefficient.
1815    pub fn coef(&self) -> f64 {
1816        unsafe { mjs_getWrapCoef(self) }
1817    }
1818}
1819
1820/***************************
1821** Numeric specification
1822***************************/
1823mjs_struct!(Numeric [SpecObject]);
1824impl MjsNumeric {
1825    getter_setter! {
1826        [&] with, get, set, [
1827            size: i32 { check_numeric_size, "[`MjEditError::InvalidParameter`] when the size is negative" } => MjEditError;     "size of the numeric array.";
1828        ]
1829    }
1830
1831    vec_set_get! {
1832        data: f64; "initialization data.";
1833    }
1834}
1835
1836/***************************
1837** Text specification
1838***************************/
1839mjs_struct!(Text [SpecObject]);
1840impl MjsText {
1841    string_set_get_with! {[&]
1842        data; "text string.";
1843    }
1844}
1845
1846/***************************
1847** Tuple specification
1848***************************/
1849mjs_struct!(Tuple [SpecObject]);
1850impl MjsTuple {
1851    vec_set! {
1852        // `objtype` is stored as a raw C `int` and, at `compile()` time, used to index the model
1853        // compiler's `object_lists_` array (size `mjNOBJECT`) with no bounds check. Validating every
1854        // element against `mjNOBJECT` rules out the meta `MjtObj` variants (`mjOBJ_FRAME`,
1855        // `mjOBJ_DEFAULT`, `mjOBJ_MODEL`) that would otherwise cause an out-of-bounds read, which is
1856        // what lets this setter be safe.
1857        objtype: MjtObj => i32 { check_objtype, "[`MjEditError::InvalidParameter`] when any value is not a real object type (i.e. not below [`MjtObj::mjNOBJECT`])" } => MjEditError;
1858            "object types. Every value must be a real object type (an `MjtObj` below `mjNOBJECT`).";
1859    }
1860
1861    vec_string_set_append! {
1862        objname; "object names.";
1863    }
1864
1865    vec_set_get! {
1866        objprm: f64; "object parameters.";
1867    }
1868}
1869
1870/***************************
1871** Key specification
1872***************************/
1873mjs_struct!(Key [SpecObject]);
1874impl MjsKey {
1875    getter_setter! {
1876        [&] with, get, set, [
1877            time: f64; "time."
1878        ]
1879    }
1880
1881    vec_set_get! {
1882        qpos: f64; "qpos.";
1883        qvel: f64; "qvel.";
1884        act: f64; "act.";
1885        mpos: f64; "mocap pos.";
1886        mquat: f64; "mocap quat.";
1887        ctrl: f64; "ctrl.";
1888    }
1889}
1890
1891/***************************
1892** Plugin specification
1893***************************/
1894mjs_struct!(Plugin [SpecObject]);
1895impl MjsPlugin {
1896    string_set_get_with! {[&]
1897        name; "instance name.";
1898        plugin_name; "plugin name.";
1899    }
1900
1901    getter_setter! {
1902        [&] with, get, set, [
1903            active: bool; "is the plugin active.";
1904        ]
1905    }
1906}
1907
1908/* Assets */
1909
1910/***************************
1911** Mesh specification
1912***************************/
1913mjs_struct!(Mesh [SpecObject]);
1914impl MjsMesh {
1915    getter_setter! {
1916        [&] with, get, [
1917            refpos: &[f64; 3];            "reference position.";
1918            refquat: &[f64; 4];           "reference orientation.";
1919            scale: &[f64; 3];             "scale vector.";
1920        ]
1921    }
1922
1923    getter_setter! {
1924        get, [
1925            plugin: &MjsPlugin;                     "sdf plugin.";
1926        ]
1927    }
1928
1929    getter_setter! {
1930        [&] with, get, set, [
1931            inertia: MjtMeshInertia;      "inertia type (convex, legacy, exact, shell).";
1932            maxhullvert: i32;             "maximum vertex count for the convex hull.";
1933            octree_maxdepth: i32;         "max octree depth.";
1934        ]
1935    }
1936
1937    getter_setter! {
1938        [&] with, get,set, [
1939            smoothnormal: bool;           "do not exclude large-angle faces from normals.";
1940            needsdf: bool;                "compute sdf from mesh.";
1941        ]
1942    }
1943
1944    string_set_get_with! {[&]
1945        content_type; "content type of file.";
1946        file; "mesh file.";
1947        material; "name of material.";
1948    }
1949
1950    vec_set! {
1951        uservert: f32;               "user vertex data.";
1952        usernormal: f32;             "user normal data.";
1953        usertexcoord: f32;           "user texcoord data.";
1954        userface: i32;               "user vertex indices.";
1955    }
1956
1957    vec_set! {
1958        [unsafe: "Every entry must be in `0..N`, where `N` is the number of user normals: the \
1959                  length of the slice passed to `set_usernormal` divided by 3 (each normal is 3 \
1960                  `f32`: x, y, z)."]
1961            userfacenormal: i32 => i32; "user face normal indices.";
1962        [unsafe: "Every entry must be in `0..ntexcoord` (the number of user texture coordinates), and \
1963                  the slice length must equal the length of the slice passed to `set_userface` (3 per \
1964                  face). Unlike face-normal data, MuJoCo does not validate the texcoord-index length, \
1965                  so an oversized slice overflows the model's face-texcoord buffer at compile time."]
1966            userfacetexcoord: i32 => i32; "user texcoord indices.";
1967    }
1968}
1969
1970/***************************
1971** Hfield specification
1972***************************/
1973mjs_struct!(Hfield [SpecObject]);
1974impl MjsHfield {
1975    getter_setter! {
1976        [&] with, get, [
1977            size: &[f64; 4];              "size of the hfield.";
1978        ]
1979    }
1980
1981    getter_setter! { [&] with, get, set, [
1982        nrow: i32;  "number of rows.";
1983        ncol: i32;  "number of columns.";
1984    ]}
1985
1986    string_set_get_with! {[&]
1987        content_type; "content type of file.";
1988        file; "file: (nrow, ncol, [elevation data]).";
1989    }
1990
1991    /// Sets `userdata`.
1992    pub fn set_userdata<T: AsRef<[f32]>>(&mut self, userdata: T) {
1993        // SAFETY: self.userdata is a valid mjFloatVec pointer for the lifetime of self.
1994        unsafe { write_mjs_vec_f32(userdata.as_ref(), self.userdata) };
1995    }
1996}
1997
1998/***************************
1999** Skin specification
2000***************************/
2001mjs_struct!(Skin [SpecObject]);
2002impl MjsSkin {
2003    getter_setter! {
2004        [&] with, get, [
2005            rgba: &[f32; 4];    "rgba when material is omitted.";
2006        ]
2007    }
2008
2009    getter_setter! {
2010        [&] with, get, set, [
2011            inflate: f32;       "inflate in normal direction.";
2012            group: i32;         "group for visualization.";
2013        ]
2014    }
2015
2016    string_set_get_with! {[&]
2017        material;               "name of material used for rendering.";
2018        file;                   "skin file.";
2019    }
2020
2021    vec_string_set_append! {
2022        bodyname;               "body names.";
2023    }
2024
2025    vec_set! {
2026        vert: f32;              "vertex positions.";
2027        texcoord: f32;          "texture coordinates.";
2028        bindpos: f32;           "bind pos.";
2029        bindquat: f32;          "bind quat.";
2030    }
2031
2032    vec_set! {
2033        [
2034            unsafe:
2035                "The slice length must be a multiple of 3 and every entry must be in `0..nvert`  (the number of skin vertices)."
2036        ] face: i32 => i32; "faces.";
2037    }
2038
2039    vec_vec_append! {
2040        vertid: i32;                     "vertex ids.";
2041        vertweight: f32;                 "vertex weights.";
2042    }
2043}
2044
2045/***************************
2046** Texture specification
2047***************************/
2048mjs_struct!(Texture [SpecObject]);
2049
2050/// # Note -- cube-map files
2051///
2052/// The `cubefiles` field is a **pre-sized** string vector (6 entries, one per cube face).
2053/// Use [`set_cubefile`](Self::set_cubefile) with a [`MjtCubeFace`] variant to assign a
2054/// file to a specific face. The bulk [`set_cubefiles`](Self::set_cubefiles) /
2055/// [`append_cubefiles`](Self::append_cubefiles) methods are also available but
2056/// operate on the vector as a whole.
2057impl MjsTexture {
2058    getter_setter! {
2059        [&] with, get, [
2060            rgb1: &[f64; 3];               "first color for builtin.";
2061            rgb2: &[f64; 3];               "second color for builtin.";
2062            markrgb: &[f64; 3];            "mark color.";
2063            gridsize: &[i32; 2];           "size of grid for composite file; (1,1)-repeat.";
2064            gridlayout: &[c_char; 12];     "row-major: L,R,F,B,U,D for faces; . for unused.";
2065        ]
2066    }
2067
2068    getter_setter! {
2069        [&] with, get, set, [
2070            random: f64;                  "probability of random dots.";
2071            width: i32;                   "image width.";
2072            height: i32;                  "image height.";
2073        ]
2074    }
2075
2076    getter_setter! {
2077        [&] with, get, set, [
2078            // `nchannel` must be `>= 3` whenever a builtin pattern is set
2079            // (`builtin != MjtBuiltin::mjBUILTIN_NONE`); this cross-field invariant is
2080            // enforced at the compile choke point in `MjSpec::compile`.
2081            nchannel: i32; "number of channels.";
2082        ]
2083    }
2084
2085    getter_setter! {
2086        [&] with, get, set, [
2087            type_ + _: MjtTexture [force];        "texture type.";
2088            colorspace: MjtColorSpace [force];    "colorspace.";
2089            builtin: MjtBuiltin [force];          "builtin type.";
2090            mark: MjtMark [force];                "mark type.";
2091        ]
2092    }
2093
2094    vec_string_set_append! {
2095        cubefiles[MjtCubeFace] => cubefile; "different file for each side of the cube.";
2096    }
2097
2098    getter_setter! {[&] with, get, set, [
2099        hflip: bool;    "horizontal flip.";
2100        vflip: bool;    "vertical flip.";
2101    ]}
2102
2103    /// Sets texture `data`.
2104    pub fn set_data<T: bytemuck::NoUninit>(&mut self, data: &[T]) {
2105        // SAFETY: self.data is a valid mjByteVec pointer for the lifetime of self.
2106        unsafe { write_mjs_vec_byte(data, self.data) };
2107    }
2108
2109    string_set_get_with! {[&]
2110        file; "png file to load; use for all sides of cube.";
2111        content_type; "content type of file.";
2112    }
2113}
2114
2115/***************************
2116** Material specification
2117***************************/
2118mjs_struct!(Material [SpecObject]);
2119
2120/// # Note -- texture assignment
2121///
2122/// The `textures` field is a **pre-sized** string vector (`mjNTEXROLE` entries, one per
2123/// [`MjtTextureRole`]). Use [`set_texture`](Self::set_texture) to assign a texture name
2124/// to a specific role (e.g. [`MjtTextureRole::mjTEXROLE_RGB`] for the base colour used by
2125/// the renderer). The bulk [`set_textures`](Self::set_textures) /
2126/// [`append_textures`](Self::append_textures) methods are also available but operate on
2127/// the vector as a whole and may disrupt the pre-sized layout.
2128impl MjsMaterial {
2129    getter_setter! {
2130        [&] with, get, [
2131            rgba: &[f32; 4];                               "rgba color.";
2132            texrepeat: &[f32; 2];    "texture repetition for 2D mapping.";
2133        ]
2134    }
2135
2136    getter_setter! {[&] with, get, set, [
2137        texuniform: bool;       "make texture cube uniform.";
2138    ]}
2139
2140    getter_setter! {
2141        [&] with, get, set, [
2142            emission: f32;                           "emission.";
2143            specular: f32;                           "specular.";
2144            shininess: f32;                         "shininess.";
2145            reflectance: f32;                     "reflectance.";
2146            metallic: f32;                           "metallic.";
2147            roughness: f32;                         "roughness.";
2148        ]
2149    }
2150
2151    vec_string_set_append! {
2152        textures[MjtTextureRole] => texture; "names of textures (empty: none).";
2153    }
2154}
2155
2156
2157/***************************
2158** Body specification
2159***************************/
2160mjs_struct!(Body [SpecObject] {
2161    // Override the delete method to prevent deletion of world.
2162    /// Delete this body from its parent spec.
2163    ///
2164    /// # Deprecated
2165    /// This API is deprecated and will be removed in a future release.
2166    /// Use [`MjSpec::delete_element`](crate::wrappers::MjSpec::delete_element) instead.
2167    ///
2168    /// This method is inherently unsound: deleting a body mutates owner/ancestor graph
2169    /// structures outside the borrowed `&mut self` region.
2170    ///
2171    /// # Errors
2172    /// - Returns [`MjEditError::UnsupportedOperation`] if this is the world body.
2173    /// - Returns [`MjEditError::DeleteFailed`] if MuJoCo's internal deletion fails.
2174    ///
2175    /// # Safety
2176    /// This legacy method is not soundly callable; it exists only for backward compatibility.
2177    unsafe fn delete(&mut self) -> Result<(), MjEditError> {
2178        if self.name() == "world" {
2179            return Err(MjEditError::UnsupportedOperation);
2180        }
2181        unsafe { SpecItem::__delete_default__(self) }
2182    }
2183});
2184
2185impl MjsBody {
2186    add_x_method! { body, site, joint, geom, camera, light }
2187
2188    /// Obtain an immutable reference to a child body with the given `name`.
2189    ///
2190    /// # Panics
2191    /// When the `name` contains '\0' characters, a panic occurs.
2192    pub fn child(&self, name: &str) -> Option<&MjsBody> {
2193        let c_name = CString::new(name).unwrap();
2194        unsafe {
2195            let ptr = mjs_findChild(self, c_name.as_ptr());
2196            if ptr.is_null() { None } else { ptr.as_ref() }
2197        }
2198    }
2199
2200    /// Obtain a mutable reference to a child body with the given `name`.
2201    ///
2202    /// # Panics
2203    /// When the `name` contains '\0' characters, a panic occurs.
2204    pub fn child_mut(&mut self, name: &str) -> Option<&mut MjsBody> {
2205        let c_name = CString::new(name).unwrap();
2206        unsafe {
2207            let ptr = mjs_findChild(self, c_name.as_ptr());
2208            if ptr.is_null() { None } else { ptr.as_mut() }
2209        }
2210    }
2211
2212    /// Dummy mutable FFI method used to simplify access through macros.
2213    ///
2214    /// # Safety
2215    /// Callers must ensure that any mutations performed through the returned reference
2216    /// preserve the invariants that MuJoCo expects for `mjsBody`.
2217    #[inline]
2218    unsafe fn ffi_mut(&mut self) -> &mut Self {
2219        self
2220    }
2221
2222    // Special case
2223    /// Add and return a child frame.
2224    ///
2225    /// Delegates to [`Self::try_add_frame`] and panics if allocation fails.
2226    /// # Panics
2227    /// Panics if MuJoCo fails to allocate the frame.
2228    pub fn add_frame(&mut self) -> &mut MjsFrame {
2229        self.try_add_frame().expect("mjs_addFrame returned null; allocation failed")
2230    }
2231
2232    /// Fallible version of [`Self::add_frame`].
2233    ///
2234    /// # Errors
2235    /// Returns [`MjEditError::AllocationFailed`] when MuJoCo fails to allocate
2236    /// the frame, instead of panicking.
2237    pub fn try_add_frame(&mut self) -> Result<&mut MjsFrame, MjEditError> {
2238        // SAFETY: ffi_mut() returns self unchanged; the coercion to *mut mjsBody is safe.
2239        // ptr::null_mut() for parentframe is valid: the MuJoCo API accepts null to mean
2240        // "attach directly to the body with no parent frame".
2241        let ptr = unsafe { mjs_addFrame(self.ffi_mut(), ptr::null_mut()) };
2242        // SAFETY: ptr.as_mut() returns None for null, handled by ok_or; when non-null the
2243        // pointee is properly aligned and initialized by C++ operator new, and freshly
2244        // allocated so no existing Rust reference aliases it for the returned lifetime.
2245        unsafe { ptr.as_mut() }.ok_or(MjEditError::AllocationFailed)
2246    }
2247}
2248
2249impl MjsBody {
2250    // Complex types with mutable and immutable reference returns.
2251    getter_setter! {
2252        [&] with, get, [
2253            // body frame
2254            pos: &[f64; 3];                   "frame position.";
2255            quat: &[f64; 4];                  "frame orientation.";
2256            alt: &MjsOrientation;             "frame alternative orientation.";
2257
2258            //inertial frame
2259            ipos: &[f64; 3];                  "inertial frame position.";
2260            iquat: &[f64; 4];                 "inertial frame orientation.";
2261            inertia: &[f64; 3];               "diagonal inertia (in i-frame).";
2262            ialt: &MjsOrientation;            "inertial frame alternative orientation.";
2263            fullinertia: &[f64; 6];           "non-axis-aligned inertia matrix.";
2264        ]
2265    }
2266
2267    getter_setter! {
2268        get, [
2269            plugin: &MjsPlugin;                     "passive force plugin.";
2270        ]
2271    }
2272
2273    // Plain types with normal getters and setters.
2274    getter_setter! {
2275        [&] with, get, set, [
2276            mass: f64;                     "mass.";
2277            gravcomp: f64;                 "gravity compensation.";
2278            sleep: MjtSleepPolicy;           "sleep policy.";
2279        ]
2280    }
2281
2282    getter_setter! {
2283        [&] with, get, set, [
2284            mocap: bool;                   "whether this is a mocap body.";
2285            explicitinertial: bool;        "whether to save the body with explicit inertial clause.";
2286        ]
2287    }
2288
2289    userdata_method!(f64);
2290}
2291
2292/// Mutable iterator over items in [`MjsBody`].
2293#[derive(Debug)]
2294pub struct MjsBodyItemIterMut<'a, T> {
2295    /// NonNull pointer to the FFI type [`mjsBody`].
2296    /// [`MjsBody`] is its alias, thus storing it plainly
2297    /// would technically be UB as Rust can't see across
2298    /// boundary to verify . 
2299    ffi_ptr: *mut MjsBody,
2300    last: *mut mjsElement,
2301    recurse: bool,
2302    /// Used for generic implementation of iterator's methods.
2303    item_type: PhantomData<&'a mut T>
2304}
2305
2306impl<'a, T: SpecObject> MjsBodyItemIterMut<'a, T> {
2307    fn new(root: &'a mut MjsBody, recurse: bool) -> Self {
2308        let last = unsafe { mjs_firstChild(root, T::OBJ_TYPE, recurse.into()) };
2309        Self { ffi_ptr: root, last, recurse, item_type: PhantomData }
2310    }
2311}
2312
2313impl<'a, T: SpecObject + 'a> Iterator for MjsBodyItemIterMut<'a, T> {
2314    type Item = &'a mut T;
2315
2316    fn next(&mut self) -> Option<Self::Item> {
2317        if self.last.is_null() {
2318            return None;
2319        }
2320
2321        unsafe {
2322            let out = T::from_element_as_ptr_mut(self.last).as_mut();
2323            self.last = mjs_nextChild(self.ffi_ptr, self.last, self.recurse.into());
2324            out
2325        }
2326    }
2327}
2328
2329impl<'a, T: SpecObject + 'a> std::iter::FusedIterator for MjsBodyItemIterMut<'a, T> {}
2330
2331/// Immutable iterator over items in [`MjsBody`].
2332#[derive(Debug, Clone)]
2333pub struct MjsBodyItemIter<'a, T> {
2334    ffi_ptr: *const MjsBody,
2335    last: *const mjsElement,
2336    recurse: bool,
2337    /// Used for generic implementation of iterator's methods.
2338    item_type: PhantomData<&'a T>
2339}
2340
2341
2342impl<'a, T: SpecObject> MjsBodyItemIter<'a, T> {
2343    fn new(root: &'a MjsBody, recurse: bool) -> Self {
2344        // SAFETY: mjs_firstChild requires a *mut pointer but does not mutate
2345        // the body. The const-to-mut cast is sound because no mutation occurs.
2346        let last = unsafe {
2347            mjs_firstChild(
2348                root,
2349                T::OBJ_TYPE,
2350                recurse.into()
2351            )
2352        };
2353        Self { ffi_ptr: root, last, recurse, item_type: PhantomData }
2354    }
2355}
2356
2357impl<'a, T: SpecObject + 'a> Iterator for MjsBodyItemIter<'a, T> {
2358    type Item = &'a T;
2359
2360    fn next(&mut self) -> Option<Self::Item> {
2361        if self.last.is_null() {
2362            return None;
2363        }
2364        unsafe {
2365            let out = T::from_element_as_ptr_mut(self.last as *mut _).as_ref();
2366            // SAFETY: mjs_nextChild requires *mut but does not mutate. Cast is sound.
2367            self.last = mjs_nextChild(self.ffi_ptr, self.last, self.recurse.into());
2368            out
2369        }
2370    }
2371}
2372
2373// Once self.last is null, next() always returns None.
2374impl<'a, T: SpecObject + 'a> std::iter::FusedIterator for MjsBodyItemIter<'a, T> {}
2375
2376/// Iterator methods.
2377impl MjsBody {
2378    body_get_iter! {[body, joint, geom, site, camera, light, frame] }
2379}
2380
2381/******************************
2382** Tests
2383******************************/
2384#[cfg(test)]
2385mod tests {
2386    use std::io::Write;
2387    use std::path::{Path, PathBuf};
2388    use std::fs;
2389
2390    use super::*;
2391
2392    const MODEL: &str = "\
2393<mujoco>
2394  <worldbody>
2395    <light ambient=\"0.2 0.2 0.2\"/>
2396    <body name=\"ball\" pos=\".2 .2 .1\">
2397        <geom name=\"green_sphere\" size=\".1\" rgba=\"0 1 0 1\" solref=\"0.004 1.0\"/>
2398        <joint name=\"ball\" type=\"free\"/>
2399    </body>
2400    <geom name=\"floor1\" type=\"plane\" size=\"10 10 1\" solref=\"0.004 1.0\"/>
2401  </worldbody>
2402</mujoco>";
2403
2404    #[test]
2405    fn test_parse_xml_string() {
2406        assert!(MjSpec::from_xml_string(MODEL).is_ok(), "failed to parse the model");
2407    }
2408
2409    #[test]
2410    fn test_parse_xml_file() {
2411        const PATH: &str = "./mj_spec_test_parse_xml_file.xml";
2412        let mut file = fs::File::create(PATH).expect("file creation failed");
2413        file.write_all(MODEL.as_bytes()).expect("unable to write to file");
2414        file.flush().unwrap();
2415
2416        let spec = MjSpec::from_xml(PATH);
2417        fs::remove_file(PATH).expect("file removal failed");
2418        assert!(spec.is_ok(), "failed to parse the model");
2419    }
2420
2421    #[test]
2422    fn test_parse_xml_vfs() {
2423        const PATH: &str = "./mj_spec_test_parse_xml_vfs.xml";
2424        let mut vfs = MjVfs::new();
2425        vfs.add_from_buffer(PATH, MODEL.as_bytes()).unwrap();
2426        assert!(MjSpec::from_xml_vfs(PATH, &vfs).is_ok(), "failed to parse the model");
2427    }
2428
2429    #[test]
2430    fn test_basic_edit_compile() {
2431        const TIMESTEP: f64 = 0.010;
2432        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2433        spec.option_mut().timestep = TIMESTEP;  // change time step to 10 ms.
2434
2435        let compiled = spec.compile().expect("could not compile the model");
2436        assert_eq!(compiled.opt().timestep, TIMESTEP);
2437
2438        spec.compile().unwrap();
2439    }
2440
2441    #[test]
2442    fn test_model_name() {
2443        const DEFAULT_MODEL_NAME: &str = "MuJoCo Model";
2444        const NEW_MODEL_NAME: &str = "Test model";
2445
2446        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2447
2448        /* Test read */
2449        assert_eq!(spec.modelname(), DEFAULT_MODEL_NAME);
2450        /* Test write */
2451        spec.set_modelname(NEW_MODEL_NAME);
2452        assert_eq!(spec.modelname(), NEW_MODEL_NAME);
2453
2454        spec.compile().unwrap();
2455    }
2456
2457    #[test]
2458    fn test_item_name() {
2459        const NEW_MODEL_NAME: &str = "Test model";
2460
2461        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2462        let world = spec.world_body_mut();
2463        let body = world.add_body();
2464        assert_eq!(body.name(), "");
2465        body.set_name(NEW_MODEL_NAME).unwrap();
2466        assert_eq!(body.name(), NEW_MODEL_NAME);
2467
2468        spec.compile().unwrap();
2469    }
2470
2471    #[test]
2472    fn test_body_remove() {
2473        const NEW_MODEL_NAME: &str = "Test model";
2474
2475        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2476        let world = spec.world_body_mut();
2477        let body = world.add_body();
2478        body.set_name(NEW_MODEL_NAME).unwrap();
2479
2480        /* Test normal body deletion */
2481        let body_element = {
2482            let body = spec.body_mut(NEW_MODEL_NAME).expect("failed to obtain the body");
2483            body.element_mut_pointer()
2484        };
2485        assert!(unsafe { spec.delete_element(body_element) }.is_ok(), "failed to delete model");
2486        assert!(spec.body(NEW_MODEL_NAME).is_none(), "body was not removed from spec");
2487
2488        /* Test world body deletion */
2489        let world_element = {
2490            let world = spec.world_body_mut();
2491            world.element_mut_pointer()
2492        };
2493        assert!(unsafe { spec.delete_element(world_element) }.is_err(), "the world model should not be deletable");
2494
2495        spec.compile().unwrap();
2496    }
2497
2498    #[test]
2499    fn test_joint_remove() {
2500        const NEW_NAME: &str = "Test model";
2501
2502        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2503        let world = spec.world_body_mut();
2504        let joint = world.add_joint();
2505        joint.set_name(NEW_NAME).unwrap();
2506
2507        /* Test normal body deletion */
2508        let joint_element = {
2509            let joint = spec.joint_mut(NEW_NAME).expect("failed to obtain the body");
2510            joint.element_mut_pointer()
2511        };
2512        assert!(unsafe { spec.delete_element(joint_element) }.is_ok(), "failed to delete model");
2513        assert!(spec.joint(NEW_NAME).is_none(), "body was not removed fom spec");
2514
2515        spec.compile().unwrap();
2516    }
2517
2518    #[test]
2519    fn test_hfield_remove() {
2520        const NEW_NAME: &str = "Test hfield";
2521
2522        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2523        let hfield = spec.add_hfield();
2524        hfield.set_name(NEW_NAME).unwrap();
2525
2526        /* Test normal hfield deletion */
2527        let hfield_element = {
2528            let hfield = spec.hfield_mut(NEW_NAME).expect("failed to obtain the hfield");
2529            hfield.element_mut_pointer()
2530        };
2531        assert!(unsafe { spec.delete_element(hfield_element) }.is_ok(), "failed to delete hfield");
2532        assert!(spec.hfield(NEW_NAME).is_none(), "hfield was not removed from spec");
2533
2534        spec.compile().unwrap();
2535    }
2536
2537    #[test]
2538    fn test_body_userdata() {
2539        const NEW_USERDATA: [f64; 3] = [1.0, 2.0, 3.0];
2540
2541        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2542        let world = spec.world_body_mut();
2543
2544        assert_eq!(world.userdata(), []);
2545
2546        world.set_userdata(NEW_USERDATA);
2547        assert_eq!(world.userdata(), NEW_USERDATA);
2548
2549        spec.compile().unwrap();
2550    }
2551
2552    #[test]
2553    fn test_body_attrs() {
2554        const TEST_VALUE_F64: f64 = 5.25;
2555
2556        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2557        let world = spec.world_body_mut();
2558
2559        world.set_gravcomp(TEST_VALUE_F64);
2560        assert_eq!(world.gravcomp(), TEST_VALUE_F64);
2561
2562        world.pos_mut()[0] = TEST_VALUE_F64;
2563        assert_eq!(world.pos()[0], TEST_VALUE_F64);
2564
2565        spec.compile().unwrap();
2566    }
2567
2568    #[test]
2569    fn test_default() {
2570        const DEFAULT_NAME: &str = "floor";
2571        const NOT_DEFAULT_NAME: &str = "floor-not";
2572
2573        let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
2574
2575        /* Test search */
2576        spec.add_default(DEFAULT_NAME, None);
2577
2578        /* Test delete */
2579        assert!(spec.default(DEFAULT_NAME).is_some());
2580        assert!(spec.default(NOT_DEFAULT_NAME).is_none());
2581
2582        let world = spec.world_body_mut();
2583        let some_body = world.add_body();
2584        some_body.add_joint().with_name("test");
2585        some_body.add_geom().with_size([0.010, 0.0, 0.0]);
2586
2587        let actuator = spec.add_actuator()
2588            .with_trntype(MjtTrn::mjTRN_JOINT);
2589        actuator.set_target("test");
2590        
2591        assert!(actuator.set_default(DEFAULT_NAME).is_ok());
2592
2593        spec.compile().unwrap();
2594    }
2595
2596    #[test]
2597    fn test_actuator_set_to() {
2598        let mut spec = MjSpec::new();
2599        let body = spec.world_body_mut().add_body();
2600        body.add_geom().with_size([0.01, 0.0, 0.0]);
2601        body.add_joint().with_name("hinge").with_type(MjtJoint::mjJNT_HINGE);
2602
2603        let actuator = spec.add_actuator().with_trntype(MjtTrn::mjTRN_JOINT);
2604        actuator.set_target("hinge");
2605
2606        /* motor */
2607        actuator.set_to_motor();
2608        assert_eq!(actuator.gaintype(), MjtGain::mjGAIN_FIXED);
2609        assert_eq!(actuator.biastype(), MjtBias::mjBIAS_NONE);
2610        assert_eq!(actuator.dyntype(), MjtDyn::mjDYN_NONE);
2611        assert_eq!(actuator.gainprm()[0], 1.0);
2612
2613        /* velocity servo */
2614        actuator.set_to_velocity(2.0);
2615        assert_eq!(actuator.gaintype(), MjtGain::mjGAIN_FIXED);
2616        assert_eq!(actuator.biastype(), MjtBias::mjBIAS_AFFINE);
2617        assert_eq!(actuator.gainprm()[0], 2.0);
2618        assert_eq!(actuator.biasprm()[2], -2.0);
2619
2620        /* damper: negative feedback gain is rejected, otherwise affine gain */
2621        assert!(actuator.set_to_damper(-1.0).is_err());
2622        assert!(actuator.set_to_damper(5.0).is_ok());
2623        assert_eq!(actuator.gaintype(), MjtGain::mjGAIN_AFFINE);
2624        assert_eq!(actuator.gainprm()[2], -5.0);
2625
2626        /* adhesion: negative gain is rejected */
2627        assert!(actuator.set_to_adhesion(-1.0).is_err());
2628        assert!(actuator.set_to_adhesion(1.0).is_ok());
2629
2630        /* cylinder: filter dynamics, always succeeds (negative diameter keeps the area) */
2631        actuator.set_to_cylinder(0.1, 0.0, 1.0, -1.0);
2632        assert_eq!(actuator.dyntype(), MjtDyn::mjDYN_FILTER);
2633
2634        /* muscle: negative tausmooth is rejected; negative entries keep MuJoCo's defaults */
2635        assert!(actuator.set_to_muscle([-1.0, -1.0], -1.0, [-1.0, -1.0], -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0).is_err());
2636        actuator.set_to_muscle([-1.0, -1.0], 0.0, [-1.0, -1.0], -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0).unwrap();
2637        assert_eq!(actuator.gaintype(), MjtGain::mjGAIN_MUSCLE);
2638        assert_eq!(actuator.biastype(), MjtBias::mjBIAS_MUSCLE);
2639        assert_eq!(actuator.dyntype(), MjtDyn::mjDYN_MUSCLE);
2640
2641        /* position (builder API): kv and dampratio are mutually exclusive */
2642        assert!(actuator.set_to_position(
2643            PositionConfig::default().with_kp(1.0).with_kv(1.0).with_dampratio(1.0)
2644        ).is_err());
2645        actuator.set_to_position(PositionConfig::default().with_kp(1.0).with_kv(1.0)).unwrap();
2646
2647        /* integrated velocity: integrator dynamics */
2648        actuator.set_to_int_velocity(IntVelocityConfig::default().with_kp(1.0)).unwrap();
2649        assert_eq!(actuator.dyntype(), MjtDyn::mjDYN_INTEGRATOR);
2650
2651        /* dc motor (builder API): without a motor constant MuJoCo cannot derive K > 0 */
2652        assert!(actuator.set_to_dc_motor(DcMotorConfig::default()).is_err());
2653        actuator.set_to_dc_motor(
2654            DcMotorConfig::default().with_motorconst([1.0, 1.0]).with_resistance(1.0)
2655        ).unwrap();
2656        assert_eq!(actuator.gaintype(), MjtGain::mjGAIN_DCMOTOR);
2657        assert_eq!(actuator.biastype(), MjtBias::mjBIAS_DCMOTOR);
2658        assert_eq!(actuator.dyntype(), MjtDyn::mjDYN_DCMOTOR);
2659
2660        /* reset to a plain motor and confirm the spec still compiles */
2661        actuator.set_to_motor();
2662        actuator.set_actearly(false);
2663        actuator.set_ctrllimited(MjtLimited::mjLIMITED_FALSE);
2664        spec.compile().unwrap();
2665    }
2666
2667    #[test]
2668    fn test_save() {
2669        const EXPECTED_XML: &str = "\
2670<mujoco model=\"MuJoCo Model\">
2671  <compiler angle=\"radian\"/>
2672
2673  <worldbody>
2674    <body>
2675      <geom size=\"0.01\"/>
2676      <site pos=\"0 0 0\"/>
2677      <camera pos=\"0 0 0\"/>
2678      <light pos=\"0 0 0\" dir=\"0 0 -1\"/>
2679    </body>
2680  </worldbody>
2681</mujoco>
2682";
2683
2684        let mut spec = MjSpec::new();
2685        let world = spec.world_body_mut();
2686        let body = world.add_body();
2687        body.add_camera();
2688        body.add_geom().with_size([0.010, 0.0, 0.0]);
2689        body.add_light();
2690        body.add_site();
2691
2692        spec.compile().unwrap();
2693        assert_eq!(spec.save_xml_string(1000).unwrap(), EXPECTED_XML);
2694
2695        spec.compile().unwrap();
2696    }
2697
2698    /// `save_xml_string` with a 1-byte buffer must return `XmlBufferTooSmall` and
2699    /// the reported `required_size` must be enough to succeed on retry.
2700    #[test]
2701    fn test_save_xml_string_buffer_too_small() {
2702        let mut spec = MjSpec::new();
2703        spec.world_body_mut().add_body().add_geom().with_size([0.01, 0.0, 0.0]);
2704        spec.compile().unwrap();
2705
2706        let err = spec.save_xml_string(1)
2707            .expect_err("expected XmlBufferTooSmall with a 1-byte buffer");
2708        let required_size = match err {
2709            MjEditError::XmlBufferTooSmall { required_size } => required_size,
2710            other => panic!("expected XmlBufferTooSmall, got {other:?}"),
2711        };
2712        assert!(required_size > 1, "required_size must exceed the original 1-byte buffer");
2713
2714        // Retry with the size MuJoCo reported plus one extra byte for safety
2715        // (MuJoCo uses a strict less-than comparison, so the buffer must be
2716        // at least required_size + 1 to succeed).
2717        let xml = spec.save_xml_string(required_size + 1)
2718            .expect("save_xml_string should succeed with required_size + 1 bytes");
2719        assert!(!xml.is_empty(), "saved XML must be non-empty");
2720    }
2721
2722    #[test]
2723    fn test_site() {
2724        const TEST_MATERIAL: &str = "material 1";
2725        const TEST_POSITION: [f64; 3] = [1.0, 2.0, 3.0];
2726        const SITE_NAME: &str = "test_site";
2727
2728        let mut spec = MjSpec::new();
2729
2730        /* add material */
2731        spec.add_material().with_name(TEST_MATERIAL);
2732
2733        /* add site */
2734        let world = spec.world_body_mut();
2735        world.add_site()
2736            .with_name(SITE_NAME);
2737        let site = spec.site_mut(SITE_NAME).unwrap();
2738
2739        /* material */
2740        assert_eq!(site.material(), "");
2741        site.set_material(TEST_MATERIAL);
2742        assert_eq!(site.material(), TEST_MATERIAL);
2743
2744        /* userdata */
2745        let test_userdata: Vec<f64> = vec![0.0; 5];
2746        assert_eq!(site.userdata(), []);
2747        site.set_userdata(&test_userdata);
2748        assert_eq!(site.userdata(), test_userdata);
2749
2750        /* position */
2751        assert_eq!(site.pos(), &[0.0; 3]);
2752        *site.pos_mut() = TEST_POSITION;
2753        assert_eq!(site.pos(), &TEST_POSITION);
2754
2755        spec.compile().unwrap();
2756    }
2757
2758    #[test]
2759    fn test_frame() {
2760        let mut spec = MjSpec::new();
2761        let world = spec.world_body_mut()
2762            .with_gravcomp(10.0);
2763
2764        world.add_frame()
2765            .with_name("frame_a")
2766            .with_pos([0.5, 0.5, 0.05])
2767            .add_body()
2768            .add_geom()
2769            .with_size([1.0, 0.0, 0.0]);
2770
2771        assert!(spec.frame("frame_a").is_some());
2772        assert!(spec.frame_mut("frame_a").is_some());
2773
2774        spec.compile().unwrap();
2775    }
2776
2777    #[test]
2778    fn test_wrap() {
2779        let mut spec = MjSpec::new();
2780        let world = spec.world_body_mut();
2781        let body1= world.add_body().with_pos([0.0, 0.0, 0.5]);
2782        body1.add_geom().with_size([0.010;3]);
2783        body1.add_site().with_name("ball1");
2784        body1.add_joint().with_type(MjtJoint::mjJNT_FREE);
2785
2786        let body2= world.add_body().with_pos([0.0, 0.0, 0.5]);
2787        body2.add_geom().with_size([0.010;3]);
2788        body2.add_site().with_name("ball2");
2789        body2.add_joint().with_type(MjtJoint::mjJNT_FREE);
2790
2791        let tendon = spec.add_tendon()
2792            .with_range([0.0, 0.25])
2793            .with_rgba([1.0, 0.5, 0.0, 1.0]);  // orange
2794        tendon.wrap_site("ball1");
2795        tendon.wrap_site("ball2");
2796
2797        spec.world_body_mut().add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
2798
2799        spec.compile().unwrap();
2800    }
2801
2802    #[test]
2803    fn test_body_child_and_id() {
2804        let mut spec = MjSpec::new();
2805        let parent = spec.world_body_mut().add_body().with_name("parent");
2806        parent.add_body().with_name("child");
2807
2808        let parent_ref = spec.body("parent").unwrap();
2809        assert!(parent_ref.child("child").is_some());
2810        assert!(parent_ref.child("missing").is_none());
2811        assert_eq!(parent_ref.id(), None);
2812
2813        let parent_mut = spec.body_mut("parent").unwrap();
2814        assert!(parent_mut.child_mut("child").is_some());
2815        assert!(parent_mut.child_mut("missing").is_none());
2816
2817        spec.compile().unwrap();
2818        assert!(spec.body("parent").unwrap().id().is_some());
2819    }
2820
2821    #[test]
2822    fn test_geom() {
2823        const GEOM_NAME: &str = "test_geom";
2824        const GEOM_INVALID_NAME: &str = "geom_test";
2825        let mut spec = MjSpec::new();
2826        spec.world_body_mut().add_geom()
2827            .with_name(GEOM_NAME);
2828
2829        assert!(spec.geom(GEOM_NAME).is_some());
2830        assert!(spec.geom(GEOM_INVALID_NAME).is_none());
2831    }
2832
2833    #[test]
2834    fn test_camera() {
2835        const CAMERA_NAME: &str = "test_cam";
2836        const CAMERA_INVALID_NAME: &str = "cam_test";
2837        let mut spec = MjSpec::new();
2838        spec.world_body_mut().add_camera()
2839            .with_name(CAMERA_NAME);
2840
2841        assert!(spec.camera(CAMERA_NAME).is_some());
2842        assert!(spec.camera(CAMERA_INVALID_NAME).is_none());
2843    }
2844
2845    #[test]
2846    fn test_light() {
2847        const LIGHT_NAME: &str = "test_light";
2848        const LIGHT_INVALID_NAME: &str = "light_test";
2849        let mut spec = MjSpec::new();
2850        spec.world_body_mut().add_light()
2851            .with_name(LIGHT_NAME);
2852
2853        assert!(spec.light(LIGHT_NAME).is_some());
2854        assert!(spec.light(LIGHT_INVALID_NAME).is_none());
2855    }
2856
2857    #[test]
2858    fn test_exclude() {
2859        const EXCLUDE_NAME: &str = "test_exclude";
2860        const EXCLUDE_INVALID_NAME: &str = "exclude_test";
2861        let mut spec = MjSpec::new();
2862
2863        spec.world_body_mut().add_body().with_name("body1-left");
2864        spec.world_body_mut().add_body().with_name("body2-right");
2865
2866        spec.add_exclude()
2867            .with_name(EXCLUDE_NAME)
2868            .with_bodyname1("body1-left")
2869            .with_bodyname2("body2-right");
2870
2871        assert!(spec.exclude(EXCLUDE_NAME).is_some());
2872        assert!(spec.exclude(EXCLUDE_INVALID_NAME).is_none());
2873
2874        assert!(spec.compile().is_ok());
2875    }
2876
2877    #[test]
2878    fn test_mesh() {
2879        let mut spec = MjSpec::new();
2880        let mesh = spec.add_mesh();
2881        assert!(!mesh.needsdf());
2882        mesh.set_needsdf(true);
2883        assert!(mesh.needsdf());
2884
2885        assert!(!mesh.smoothnormal());
2886        mesh.set_smoothnormal(true);
2887        assert!(mesh.smoothnormal());
2888    }
2889
2890    #[test]
2891    fn test_iteration() {
2892        const LAST_BODY_NAME: &str = "subbody";
2893        const LAST_WORLD_BODY_NAME: &str = "body2";
2894        const N_GEOM:   usize = 3;
2895        const N_BODY:   usize = 4;  // three added + world
2896        const N_SITE:   usize = 2;
2897        const N_TENDON: usize = 1;
2898        const N_MESH:   usize = 0;
2899
2900        let mut spec = MjSpec::new();
2901        let world = spec.world_body_mut();
2902        let body1= world.add_body().with_pos([0.0, 0.0, 0.5]);
2903        body1.add_geom().with_size([0.010;3]);
2904        body1.add_site().with_name("ball1");
2905        body1.add_joint().with_type(MjtJoint::mjJNT_FREE);
2906
2907        let body2= world.add_body().with_pos([0.0, 0.0, 0.5]).with_name(LAST_WORLD_BODY_NAME);
2908        body2.add_geom().with_size([0.010;3]);
2909        body2.add_site().with_name("ball2");
2910        body2.add_joint().with_type(MjtJoint::mjJNT_FREE);
2911
2912        body2.add_body().with_name(LAST_BODY_NAME);
2913
2914        let tendon = spec.add_tendon()
2915            .with_range([0.0, 0.25])
2916            .with_rgba([1.0, 0.5, 0.0, 1.0]);  // orange
2917        tendon.wrap_site("ball1");
2918        tendon.wrap_site("ball2");
2919
2920        spec.world_body_mut().add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
2921
2922        // Iter MjSpec
2923        assert_eq!(spec.geom_iter_mut().count(), N_GEOM);
2924        assert_eq!(spec.body_iter_mut().count(), N_BODY);
2925        assert_eq!(spec.site_iter_mut().count(), N_SITE);
2926        assert_eq!(spec.tendon_iter_mut().count(), N_TENDON);
2927        assert_eq!(spec.mesh_iter_mut().count(), N_MESH);
2928        assert_eq!(spec.body_iter_mut().last().unwrap().name(), LAST_BODY_NAME);
2929
2930        // Iter MjsBody
2931        let world = spec.world_body_mut();
2932        assert_eq!(world.geom_iter_mut(true).count(), N_GEOM);
2933        assert_eq!(world.body_iter_mut(true).count(), N_BODY - 1);  // world must now be excluded
2934        assert_eq!(world.site_iter_mut(true).count(), N_SITE);
2935        assert_eq!(world.body_iter_mut(false).last().unwrap().name(), LAST_WORLD_BODY_NAME);
2936    }
2937
2938    /// Tests wrapper method of [`mj_parse`] with VFS.
2939    #[test]
2940    fn test_parse_vfs() {
2941        let mut vfs = MjVfs::new();
2942        vfs.add_from_buffer("hello.xml", MODEL.as_bytes()).unwrap();
2943        let mut spec = MjSpec::from_parse_vfs("hello.xml", "XML", &vfs).unwrap();
2944        let model = spec.compile().unwrap();
2945        assert!(model.geom("floor1").is_some());
2946    }
2947
2948    /// Tests wrapper method of [`mj_parse`] without VFS.
2949    #[test]
2950    fn test_parse_file() {
2951        std::fs::write("test_parse_vfs.xml", MODEL).unwrap();
2952        let mut spec = MjSpec::from_parse("test_parse_vfs.xml", "XML").unwrap();
2953        std::fs::remove_file("test_parse_vfs.xml").unwrap();
2954        let model = spec.compile().unwrap();
2955        assert!(model.geom("floor1").is_some());
2956    }
2957
2958    #[test]
2959    fn test_tendon_wrap_methods() {
2960        let mut spec = MjSpec::new();
2961        spec.world_body_mut().add_body().with_name("body1");
2962        spec.world_body_mut().add_body().with_name("body2");
2963        spec.world_body_mut().add_site().with_name("site1");
2964
2965        let tendon = spec.add_tendon();
2966        tendon.wrap_site("site1");
2967        tendon.wrap_joint("joint1", 0.5);
2968        tendon.wrap_pulley(1.5);
2969
2970        assert_eq!(tendon.wrap_num(), 3);
2971
2972        let wrap = tendon.wrap(1);
2973        assert_eq!(wrap.coef(), 0.5);
2974
2975        let wrap_pulley = tendon.wrap(2);
2976        assert_eq!(wrap_pulley.divisor(), 1.5);
2977    }
2978
2979    #[test]
2980    fn test_tendon_wrap_out_of_bounds() {
2981        let mut spec = MjSpec::new();
2982        spec.world_body_mut().add_site().with_name("site1");
2983
2984        let tendon = spec.add_tendon();
2985        tendon.wrap_site("site1");
2986        assert_eq!(tendon.wrap_num(), 1);
2987
2988        // Index 3 is out of range; the fallible accessor reports it rather than aborting in C.
2989        match tendon.try_wrap(3) {
2990            Err(MjEditError::IndexOutOfBounds { id, len }) => {
2991                assert_eq!(id, 3);
2992                assert_eq!(len, 1);
2993            }
2994            _ => panic!("expected IndexOutOfBounds"),
2995        }
2996    }
2997
2998    #[test]
2999    #[should_panic]
3000    fn test_tendon_wrap_out_of_bounds_panics() {
3001        let mut spec = MjSpec::new();
3002        spec.world_body_mut().add_site().with_name("site1");
3003
3004        let tendon = spec.add_tendon();
3005        tendon.wrap_site("site1");
3006
3007        // The panicking accessor must panic in Rust, not abort the process in C.
3008        let _ = tendon.wrap(3);
3009    }
3010
3011    #[test]
3012    fn test_numeric_vec() {
3013        let mut spec = MjSpec::new();
3014        let numeric = spec.add_numeric();
3015        let name = "test_numeric";
3016        numeric.set_name(name).unwrap();
3017        assert_eq!(numeric.name(), name);
3018
3019        let data = [1.5, 2.5, 3.5, 4.5];
3020        numeric.set_data(&data);
3021        assert_eq!(numeric.data(), &data);
3022
3023        spec.compile().unwrap();
3024    }
3025
3026    #[test]
3027    fn test_text_string() {
3028        let mut spec = MjSpec::new();
3029        let text = spec.add_text();
3030        let name = "test_text";
3031        text.set_name(name).unwrap();
3032        assert_eq!(text.name(), name);
3033
3034        let content = "Hello MuJoCo!";
3035        text.set_data(content);
3036        assert_eq!(text.data(), content);
3037
3038        spec.compile().unwrap();
3039    }
3040
3041    #[test]
3042    fn test_tuple_names_and_params() {
3043        let mut spec = MjSpec::new();
3044        spec.world_body_mut().add_body().with_name("body1");
3045        spec.world_body_mut().add_body().with_name("body2");
3046
3047        let tuple_name = "test_tuple";
3048        let obj_param = [1.0, 2.0];
3049
3050        let tuple = spec.add_tuple();
3051        tuple.set_name(tuple_name).unwrap();
3052        assert_eq!(tuple.name(), tuple_name);
3053
3054        tuple.set_objname("body1 body2");
3055        tuple.set_objprm(&obj_param);
3056        tuple.set_objtype(&[MjtObj::mjOBJ_BODY, MjtObj::mjOBJ_BODY]).unwrap();
3057
3058        assert_eq!(tuple.objprm(), &obj_param);
3059
3060        spec.compile().unwrap();
3061
3062        // Verify via XML as objname has no spec getter
3063        let xml = spec.save_xml_string(2000).unwrap();
3064        assert!(xml.contains("objname=\"body1\""));
3065        assert!(xml.contains("objname=\"body2\""));
3066        assert!(xml.contains("prm=\"1\""));
3067        assert!(xml.contains("prm=\"2\""));
3068    }
3069
3070    /// Tests that wrapping sites on a tendon produces a compiled model
3071    /// with correct ntendon, nwrap, wrap types, and wrap object IDs.
3072    #[test]
3073    fn test_tendon_wrap_site_compiled_model() {
3074        let mut spec = MjSpec::new();
3075        let world = spec.world_body_mut();
3076
3077        let b1 = world.add_body().with_pos([0.0, 0.0, 0.5]);
3078        b1.add_geom().with_size([0.01; 3]);
3079        b1.add_site().with_name("s1");
3080        b1.add_joint().with_type(MjtJoint::mjJNT_FREE);
3081
3082        let b2 = world.add_body().with_pos([1.0, 0.0, 0.5]);
3083        b2.add_geom().with_size([0.01; 3]);
3084        b2.add_site().with_name("s2");
3085        b2.add_joint().with_type(MjtJoint::mjJNT_FREE);
3086
3087        world.add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
3088
3089        let tendon = spec.add_tendon().with_range([0.0, 1.0]);
3090        tendon.wrap_site("s1");
3091        tendon.wrap_site("s2");
3092
3093        let model = spec.compile().unwrap();
3094
3095        assert_eq!(model.ffi().ntendon, 1, "expected one tendon");
3096        assert_eq!(model.ffi().nwrap, 2, "expected two wrap elements");
3097
3098        // Verify wrap types are mjWRAP_SITE (= 1)
3099        let wrap_types = model.wrap_type();
3100        assert_eq!(wrap_types[0], MjtWrap::mjWRAP_SITE);
3101        assert_eq!(wrap_types[1], MjtWrap::mjWRAP_SITE);
3102
3103        // Verify wrap object IDs point to the correct sites
3104        let wrap_objid = model.wrap_objid();
3105        let s1_id = model.site("s1").unwrap().id as i32;
3106        let s2_id = model.site("s2").unwrap().id as i32;
3107        assert_eq!(wrap_objid[0], s1_id);
3108        assert_eq!(wrap_objid[1], s2_id);
3109    }
3110
3111    /// Test that MjsTendon `limited` correctly round-trips all three enum states
3112    /// (FALSE, TRUE, AUTO), which would fail if the field were `bool`.
3113    #[test]
3114    fn test_tendon_limited_tristate() {
3115        use crate::mujoco_c::mjtLimited_::*;
3116
3117        let mut spec = MjSpec::new();
3118        let world = spec.world_body_mut();
3119
3120        let b1 = world.add_body().with_pos([0.0, 0.0, 0.5]);
3121        b1.add_geom().with_size([0.01; 3]);
3122        b1.add_site().with_name("s1");
3123        b1.add_joint().with_type(MjtJoint::mjJNT_FREE);
3124
3125        let b2 = world.add_body().with_pos([1.0, 0.0, 0.5]);
3126        b2.add_geom().with_size([0.01; 3]);
3127        b2.add_site().with_name("s2");
3128        b2.add_joint().with_type(MjtJoint::mjJNT_FREE);
3129
3130        world.add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
3131
3132        // Create 3 tendons, one for each LIMITED enum value
3133        for (name, val) in [("t_false", mjLIMITED_FALSE), ("t_true", mjLIMITED_TRUE), ("t_auto", mjLIMITED_AUTO)] {
3134            let t = spec.add_tendon()
3135                .with_name(name)
3136                .with_range([0.0, 1.0])
3137                .with_limited(val);
3138            t.wrap_site("s1");
3139            t.wrap_site("s2");
3140        }
3141
3142        // Verify before compilation: getter round-trip
3143        for (name, expected) in [("t_false", mjLIMITED_FALSE), ("t_true", mjLIMITED_TRUE), ("t_auto", mjLIMITED_AUTO)] {
3144            let t = spec.tendon(name).expect("tendon not found");
3145            assert_eq!(t.limited(), expected,
3146                "Before compile: tendon '{}' limited should be {:?}", name, expected);
3147        }
3148
3149        // Compile and verify the compiled model's tendon_limited field
3150        let model = spec.compile().unwrap();
3151        let tendon_limited = model.tendon_limited();
3152        // After compilation, enum values resolve to bool: FALSE->false, TRUE->true, AUTO->resolved
3153        assert!(!tendon_limited[0], "Compiled tendon 0 limited should be false");
3154        assert!(tendon_limited[1], "Compiled tendon 1 limited should be true");
3155        // AUTO resolves to a concrete bool in the compiled model (always true or false)
3156        let _ = tendon_limited[2];
3157    }
3158
3159    /// Test that MjsTendon `actfrclimited` correctly round-trips all three enum
3160    /// states (FALSE, TRUE, AUTO).
3161    #[test]
3162    fn test_tendon_actfrclimited_tristate() {
3163        use crate::mujoco_c::mjtLimited_::*;
3164
3165        let mut spec = MjSpec::new();
3166        let world = spec.world_body_mut();
3167
3168        let b1 = world.add_body().with_pos([0.0, 0.0, 0.5]);
3169        b1.add_geom().with_size([0.01; 3]);
3170        b1.add_site().with_name("s1");
3171        b1.add_joint().with_type(MjtJoint::mjJNT_FREE);
3172
3173        let b2 = world.add_body().with_pos([1.0, 0.0, 0.5]);
3174        b2.add_geom().with_size([0.01; 3]);
3175        b2.add_site().with_name("s2");
3176        b2.add_joint().with_type(MjtJoint::mjJNT_FREE);
3177
3178        world.add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
3179
3180        // Set actfrclimited to each variant (with actfrcrange for TRUE/AUTO)
3181        for (name, val) in [("t_false", mjLIMITED_FALSE), ("t_true", mjLIMITED_TRUE), ("t_auto", mjLIMITED_AUTO)] {
3182            let t = spec.add_tendon()
3183                .with_name(name)
3184                .with_range([0.0, 1.0])
3185                .with_actfrcrange([-1.0, 1.0])
3186                .with_actfrclimited(val);
3187            t.wrap_site("s1");
3188            t.wrap_site("s2");
3189        }
3190
3191        // Verify round-trip before compilation
3192        for (name, expected) in [("t_false", mjLIMITED_FALSE), ("t_true", mjLIMITED_TRUE), ("t_auto", mjLIMITED_AUTO)] {
3193            let t = spec.tendon(name).expect("tendon not found");
3194            assert_eq!(t.actfrclimited(), expected,
3195                "Before compile: tendon '{}' actfrclimited should be {:?}", name, expected);
3196        }
3197
3198        // Must compile without error
3199        spec.compile().unwrap();
3200    }
3201
3202    /// Test that MjsJoint `align` correctly round-trips all three enum states
3203    /// (FALSE, TRUE, AUTO), which would fail if the field were `i32`.
3204    #[test]
3205    fn test_joint_align_tristate() {
3206        use crate::mujoco_c::mjtAlignFree_::*;
3207
3208        let mut spec = MjSpec::new();
3209        let world = spec.world_body_mut();
3210        world.add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
3211
3212        // Create 3 free joints, one for each align state
3213        for (name, val) in [("j_false", mjALIGNFREE_FALSE), ("j_true", mjALIGNFREE_TRUE), ("j_auto", mjALIGNFREE_AUTO)] {
3214            let body = world.add_body().with_pos([0.0, 0.0, 1.0]);
3215            body.add_geom().with_size([0.1; 3]);
3216            body.add_joint()
3217                .with_name(name)
3218                .with_type(MjtJoint::mjJNT_FREE)
3219                .with_align(val);
3220        }
3221
3222        // Verify round-trip before compilation
3223        for (name, expected) in [("j_false", mjALIGNFREE_FALSE), ("j_true", mjALIGNFREE_TRUE), ("j_auto", mjALIGNFREE_AUTO)] {
3224            let j = spec.joint(name).expect("joint not found");
3225            assert_eq!(j.align(), expected,
3226                "Before compile: joint '{}' align should be {:?}", name, expected);
3227        }
3228
3229        // Compile and verify -- AUTO should resolve, FALSE/TRUE should remain
3230        let model = spec.compile().unwrap();
3231        let jnt_count = model.ffi().njnt as usize;
3232        assert_eq!(jnt_count, 3, "expected 3 joints");
3233
3234        // Must compile without error -- the key correctness is the round-trip above;
3235        // compilation proves MuJoCo accepted the enum values.
3236    }
3237
3238    /// Test that MjsJoint `limited` also correctly round-trips all three states
3239    /// since it was also changed to MjtLimited.
3240    #[test]
3241    fn test_joint_limited_tristate() {
3242        use crate::mujoco_c::mjtLimited_::*;
3243
3244        let mut spec = MjSpec::new();
3245        let world = spec.world_body_mut();
3246        world.add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
3247
3248        for (name, val) in [("j_false", mjLIMITED_FALSE), ("j_true", mjLIMITED_TRUE), ("j_auto", mjLIMITED_AUTO)] {
3249            let body = world.add_body().with_pos([0.0, 0.0, 1.0]);
3250            body.add_geom().with_size([0.1; 3]);
3251            body.add_joint()
3252                .with_name(name)
3253                .with_type(MjtJoint::mjJNT_SLIDE)
3254                .with_range([0.0, 1.0])
3255                .with_limited(val);
3256        }
3257
3258        // Verify round-trip before compilation
3259        for (name, expected) in [("j_false", mjLIMITED_FALSE), ("j_true", mjLIMITED_TRUE), ("j_auto", mjLIMITED_AUTO)] {
3260            let j = spec.joint(name).expect("joint not found");
3261            assert_eq!(j.limited(), expected,
3262                "Before compile: joint '{}' limited should be {:?}", name, expected);
3263        }
3264
3265        // Compile -- AUTO resolves based on range presence
3266        let model = spec.compile().unwrap();
3267        let jnt_limited = model.jnt_limited();
3268        assert!(!jnt_limited[0]);
3269        assert!(jnt_limited[1]);
3270        // AUTO with range present should resolve to true
3271        assert!(jnt_limited[2], "Joint with limited=AUTO and range should resolve to true");
3272    }
3273
3274    /// Parsing invalid XML must return Err with a non-empty message.
3275    #[test]
3276    fn test_parse_xml_string_invalid() {
3277        let result = MjSpec::from_xml_string("<not valid mujoco xml>");
3278        assert!(result.is_err(), "parsing invalid XML must return Err");
3279        let msg = result.unwrap_err().to_string();
3280        assert!(!msg.is_empty(), "error message must not be empty for invalid XML");
3281    }
3282
3283    /// Parsing via VFS must produce a model with the expected properties, not just succeed.
3284    #[test]
3285    fn test_parse_xml_vfs_content() {
3286        const PATH: &str = "./mj_spec_test_parse_xml_vfs_content.xml";
3287        let mut vfs = MjVfs::new();
3288        vfs.add_from_buffer(PATH, MODEL.as_bytes()).unwrap();
3289        let mut spec = MjSpec::from_xml_vfs(PATH, &vfs).expect("VFS parse failed");
3290        let model = spec.compile().expect("compile failed");
3291
3292        // MODEL has: worldbody + 1 named body ("ball") = 2 bodies total (world + ball)
3293        assert_eq!(model.ffi().nbody, 2, "expected 2 bodies (world + ball)");
3294        // MODEL has: 1 free joint on "ball"
3295        assert_eq!(model.ffi().njnt, 1, "expected 1 joint");
3296        // MODEL has: 1 sphere geom + 1 plane geom = 2 geoms
3297        assert_eq!(model.ffi().ngeom, 2, "expected 2 geoms (sphere + floor)");
3298    }
3299
3300    /// Parsing via XML file must produce a model with the expected properties.
3301    #[test]
3302    fn test_parse_xml_file_content() {
3303        const PATH: &str = "./mj_spec_test_parse_xml_file_content.xml";
3304        let mut file = fs::File::create(PATH).expect("file creation failed");
3305        file.write_all(MODEL.as_bytes()).expect("unable to write");
3306        file.flush().unwrap();
3307
3308        let result = MjSpec::from_xml(PATH);
3309        fs::remove_file(PATH).expect("file removal failed");
3310
3311        let mut spec = result.expect("file parse failed");
3312        let model = spec.compile().expect("compile failed");
3313
3314        assert_eq!(model.ffi().nbody, 2, "expected 2 bodies (world + ball)");
3315        assert_eq!(model.ffi().njnt, 1, "expected 1 joint");
3316        assert_eq!(model.ffi().ngeom, 2, "expected 2 geoms (sphere + floor)");
3317    }
3318
3319    /// `from_parse` accepts `PathBuf` and `&Path` in addition to `&str`.
3320    #[test]
3321    fn test_from_parse_path_types() {
3322        const PATH: &str = "./mj_spec_test_from_parse_path_types.xml";
3323        let mut file = fs::File::create(PATH).expect("file creation failed");
3324        file.write_all(MODEL.as_bytes()).expect("write failed");
3325        file.flush().unwrap();
3326
3327        // &str
3328        assert!(MjSpec::from_parse(PATH, "").is_ok());
3329        // String
3330        assert!(MjSpec::from_parse(String::from(PATH), "").is_ok());
3331        // &Path
3332        assert!(MjSpec::from_parse(Path::new(PATH), "").is_ok());
3333        // PathBuf
3334        assert!(MjSpec::from_parse(PathBuf::from(PATH), "").is_ok());
3335
3336        fs::remove_file(PATH).expect("file removal failed");
3337    }
3338
3339    /// `from_parse_vfs` accepts `PathBuf` and `&Path`.
3340    #[test]
3341    fn test_from_parse_vfs_path_types() {
3342        const PATH: &str = "./mj_spec_test_from_parse_vfs_path_types.xml";
3343        let mut vfs = MjVfs::new();
3344        vfs.add_from_buffer(PATH, MODEL.as_bytes()).unwrap();
3345
3346        // &str
3347        assert!(MjSpec::from_parse_vfs(PATH, "", &vfs).is_ok());
3348        // PathBuf
3349        assert!(MjSpec::from_parse_vfs(PathBuf::from(PATH), "", &vfs).is_ok());
3350        // &Path
3351        assert!(MjSpec::from_parse_vfs(Path::new(PATH), "", &vfs).is_ok());
3352    }
3353
3354    /// `save_xml` accepts `PathBuf` and `&Path` in addition to `&str`.
3355    #[test]
3356    fn test_save_xml_path_types() {
3357        let mut spec = MjSpec::new();
3358        spec.world_body_mut().add_body().add_geom().with_size([0.01, 0.0, 0.0]);
3359        spec.compile().unwrap();
3360
3361        let paths: [PathBuf; 3] = [
3362            PathBuf::from("./mj_spec_save_xml_str.xml"),
3363            PathBuf::from("./mj_spec_save_xml_pathbuf.xml"),
3364            PathBuf::from("./mj_spec_save_xml_path.xml"),
3365        ];
3366
3367        // &str
3368        spec.save_xml(paths[0].to_str().unwrap()).unwrap();
3369        // PathBuf
3370        spec.save_xml(paths[1].clone()).unwrap();
3371        // &Path
3372        spec.save_xml(paths[2].as_path()).unwrap();
3373
3374        for p in &paths {
3375            let content = fs::read_to_string(p).expect("saved file should be readable");
3376            assert!(content.contains("<mujoco"), "saved XML should contain <mujoco tag");
3377            fs::remove_file(p).expect("cleanup failed");
3378        }
3379    }
3380
3381    #[test]
3382    fn test_material_set_texture() {
3383        let mut spec = MjSpec::new();
3384        let world = spec.world_body_mut();
3385        world.add_geom()
3386            .with_type(MjtGeom::mjGEOM_PLANE)
3387            .with_size([1.0, 1.0, 0.01])
3388            .with_material("floor");
3389
3390        spec.add_texture()
3391            .with_name("floor")
3392            .with_type(MjtTexture::mjTEXTURE_2D)
3393            .with_builtin(MjtBuiltin::mjBUILTIN_CHECKER)
3394            .with_rgb1([0.9, 0.9, 0.9])
3395            .with_rgb2([0.1, 0.1, 0.1])
3396            .with_width(512)
3397            .with_height(512);
3398
3399        let mat = spec.add_material().with_name("floor");
3400        mat.set_texture(MjtTextureRole::mjTEXROLE_RGB, "floor");
3401
3402        let model = spec.compile().unwrap();
3403        let xml = spec.save_xml_string(8192).unwrap();
3404        assert!(xml.contains("texture=\"floor\""), "XML should reference the floor texture");
3405
3406        let mat_info = model.material("floor").unwrap();
3407        let mat_view = mat_info.view(&model);
3408        let tex_id = mat_view.texid;
3409        assert_ne!(tex_id[MjtTextureRole::mjTEXROLE_RGB as usize], -1,
3410            "RGB texture slot should be resolved (not -1)");
3411    }
3412
3413    /// A builtin texture with `nchannel < 3` must be rejected by `compile()` rather than
3414    /// heap-overflowing in MuJoCo's builtin generators (which write 3 bytes per pixel).
3415    #[test]
3416    fn test_builtin_texture_nchannel_rejected() {
3417        let mut spec = MjSpec::new();
3418        spec.add_texture()
3419            .with_name("badtex")
3420            .with_type(MjtTexture::mjTEXTURE_2D)
3421            .with_builtin(MjtBuiltin::mjBUILTIN_CHECKER)
3422            .with_rgb1([0.9, 0.9, 0.9])
3423            .with_rgb2([0.1, 0.1, 0.1])
3424            .with_width(64)
3425            .with_height(64)
3426            .set_nchannel(1);
3427
3428        let err = spec.compile().unwrap_err();
3429        assert!(matches!(&err, MjEditError::CompileFailed(msg) if msg.contains("nchannel")),
3430            "compile must reject nchannel < 3 builtin texture, got {err:?}");
3431
3432        // nchannel == 3 (and a builtin pattern) compiles cleanly.
3433        let mut ok_spec = MjSpec::new();
3434        ok_spec.add_texture()
3435            .with_name("goodtex")
3436            .with_type(MjtTexture::mjTEXTURE_2D)
3437            .with_builtin(MjtBuiltin::mjBUILTIN_CHECKER)
3438            .with_rgb1([0.9, 0.9, 0.9])
3439            .with_rgb2([0.1, 0.1, 0.1])
3440            .with_width(64)
3441            .with_height(64)
3442            .set_nchannel(3);
3443        assert!(ok_spec.compile().is_ok(), "nchannel == 3 builtin texture should compile");
3444
3445        // nchannel < 3 with NO builtin pattern must not trip this guard. Such a texture still
3446        // fails to compile (it has no pixel source), but with MuJoCo's own error message rather
3447        // than the nchannel guard's, proving the guard is correctly scoped to the builtin path.
3448        let mut no_builtin = MjSpec::new();
3449        no_builtin.add_texture()
3450            .with_name("plain")
3451            .with_type(MjtTexture::mjTEXTURE_2D)
3452            .with_width(64)
3453            .with_height(64)
3454            .set_nchannel(1);
3455        assert!(matches!(no_builtin.compile().unwrap_err(),
3456                MjEditError::CompileFailed(msg) if !msg.contains("nchannel")),
3457            "nchannel < 3 without a builtin pattern should not trip the nchannel guard");
3458    }
3459
3460    /// Verifies `MjsFlex::cellcount` (read-only `&[i32; 3]`) and `order` (read-write `i32`)
3461    /// by parsing a minimal flexcomp model and reading/writing through the spec.
3462    #[test]
3463    fn test_mjs_flex_cellcount_and_order() {
3464        const FLEX_MODEL: &str = "\
3465<mujoco>\
3466  <worldbody>\
3467    <body name=\"pin\" pos=\"0 0 1\">\
3468      <flexcomp type=\"grid\" count=\"3 3 1\" spacing=\".1 .1 .1\" mass=\"1\"\
3469                name=\"myflex\" radius=\"0.001\" dim=\"2\">\
3470        <elasticity young=\"1e4\" poisson=\"0.0\"/>\
3471      </flexcomp>\
3472    </body>\
3473  </worldbody>\
3474</mujoco>";
3475
3476        let mut spec = MjSpec::from_xml_string(FLEX_MODEL).expect("failed to parse flex model");
3477        let flex = spec.flex("myflex").expect("flex 'myflex' not found in spec");
3478
3479        /* Verify field dimensions */
3480        assert_eq!(flex.cellcount().len(), 3);
3481
3482        /* Verify write-read roundtrip for order */
3483        {
3484            let flex_mut = spec.flex_mut("myflex").unwrap();
3485            flex_mut.set_order(2);
3486        }
3487        assert_eq!(spec.flex("myflex").unwrap().order(), 2);
3488
3489        {
3490            let flex_mut = spec.flex_mut("myflex").unwrap();
3491            flex_mut.set_order(1);
3492        }
3493        assert_eq!(spec.flex("myflex").unwrap().order(), 1);
3494    }
3495
3496    /// Verifies the sensor's objtype protection works.
3497    #[test]
3498    #[should_panic]
3499    fn test_sensor_objtype_failure() {
3500        let mut spec = MjSpec::new();
3501        spec.add_sensor()
3502            .with_objtype(MjtObj::mjOBJ_FRAME);
3503    }
3504
3505    /// Verifies the sensor's reftype protection works.
3506    #[test]
3507    #[should_panic]
3508    fn test_sensor_reftype_failure() {
3509        let mut spec = MjSpec::new();
3510        spec.add_sensor()
3511            .with_reftype(MjtObj::mjOBJ_FRAME);
3512    }
3513
3514    /// Verifies the fallible sensor objtype/reftype setters reject meta variants and accept real ones.
3515    #[test]
3516    fn test_sensor_objtype_reftype_setters() {
3517        let mut spec = MjSpec::new();
3518        let sensor = spec.add_sensor();
3519
3520        assert!(matches!(
3521            sensor.set_objtype(MjtObj::mjOBJ_MODEL),
3522            Err(MjEditError::InvalidParameter(_))
3523        ));
3524        assert!(matches!(
3525            sensor.set_reftype(MjtObj::mjOBJ_DEFAULT),
3526            Err(MjEditError::InvalidParameter(_))
3527        ));
3528        assert!(sensor.set_objtype(MjtObj::mjOBJ_SITE).is_ok());
3529        assert!(sensor.set_reftype(MjtObj::mjOBJ_BODY).is_ok());
3530    }
3531
3532    /// Verifies the tuple's objtype protection rejects meta object types and leaves the
3533    /// slice unwritten, while accepting real object types.
3534    #[test]
3535    fn test_tuple_objtype_validation() {
3536        let mut spec = MjSpec::new();
3537        let tuple = spec.add_tuple();
3538
3539        assert!(matches!(
3540            tuple.set_objtype(&[MjtObj::mjOBJ_BODY, MjtObj::mjOBJ_FRAME]),
3541            Err(MjEditError::InvalidParameter(_))
3542        ));
3543        assert!(tuple.set_objtype(&[MjtObj::mjOBJ_BODY, MjtObj::mjOBJ_GEOM]).is_ok());
3544    }
3545
3546    /// Verifies the numeric size setter rejects a negative size (which would undersize the
3547    /// `numeric_data` allocation in the model compiler) and accepts a non-negative one.
3548    #[test]
3549    fn test_numeric_size_validation() {
3550        let mut spec = MjSpec::new();
3551        let numeric = spec.add_numeric();
3552
3553        assert!(matches!(
3554            numeric.set_size(-1),
3555            Err(MjEditError::InvalidParameter(_))
3556        ));
3557        assert!(numeric.set_size(4).is_ok());
3558    }
3559}