mujoco_rs/wrappers/
mj_model.rs

1//! MjModel related.
2use std::ffi::{c_int, CStr, CString, NulError};
3use std::io::{self, Error, ErrorKind};
4use std::path::Path;
5use std::ptr;
6
7use super::mj_auxiliary::{MjVfs, MjVisual, MjStatistic};
8use crate::wrappers::mj_option::MjOption;
9use crate::wrappers::mj_data::MjData;
10use super::mj_primitive::*;
11use crate::mujoco_c::*;
12
13use crate::{
14    view_creator, info_method, info_with_view,
15    mj_view_indices, mj_model_nx_to_mapping, mj_model_nx_to_nitem,
16    array_slice_dyn, getter_setter
17};
18
19
20/*******************************************/
21// Types
22/// Constants which are powers of 2. They are used as bitmasks for the field ``disableflags`` of `mjOption`.
23/// At runtime this field is ``m->opt.disableflags``. The number of these constants is given by ``mjNDISABLE`` which is
24/// also the length of the global string array `mjDISABLESTRING` with text descriptions of these flags.
25pub type MjtDisableBit = mjtDisableBit;
26
27/// Constants which are powers of 2. They are used as bitmasks for the field ``enableflags`` of `mjOption`.
28/// At runtime this field is ``m->opt.enableflags``. The number of these constants is given by ``mjNENABLE`` which is also
29/// the length of the global string array `mjENABLESTRING` with text descriptions of these flags.
30pub type MjtEnableBit = mjtEnableBit;
31
32/// Primitive joint types. These values are used in ``m->jnt_type``. The numbers in the comments indicate how many
33/// positional coordinates each joint type has. Note that ball joints and rotational components of free joints are
34/// represented as unit quaternions - which have 4 positional coordinates but 3 degrees of freedom each.
35pub type MjtJoint = mjtJoint;
36
37/// Geometric types supported by MuJoCo. The first group are "official" geom types that can be used in the model. The
38/// second group are geom types that cannot be used in the model but are used by the visualizer to add decorative
39/// elements. These values are used in ``m->geom_type`` and ``m->site_type``.
40pub type MjtGeom = mjtGeom;
41
42/// Dynamic modes for cameras and lights, specifying how the camera/light position and orientation are computed. These
43/// values are used in ``m->cam_mode`` and ``m->light_mode``.
44pub type MjtCamLight = mjtCamLight;
45
46/// The type of a light source describing how its position, orientation and other properties will interact with the
47/// objects in the scene. These values are used in ``m->light_type``.
48pub type MjtLightType = mjtLightType;
49
50/// Texture types, specifying how the texture will be mapped. These values are used in ``m->tex_type``.
51pub type MjtTexture = mjtTexture;
52
53/// Texture roles, specifying how the renderer should interpret the texture.  Note that the MuJoCo built-in renderer only
54/// uses RGB textures.  These values are used to store the texture index in the material's array ``m->mat_texid``.
55pub type MjtTextureRole = mjtTextureRole;
56
57/// Type of color space encoding for textures.
58pub type MjtColorSpace = mjtColorSpace;
59
60/// Numerical integrator types. These values are used in ``m->opt.integrator``.
61pub type MjtIntegrator = mjtIntegrator;
62
63/// Available friction cone types. These values are used in ``m->opt.cone``.
64pub type MjtCone = mjtCone;
65
66/// Available Jacobian types. These values are used in ``m->opt.jacobian``.
67pub type MjtJacobian = mjtJacobian;
68
69/// Available constraint solver algorithms. These values are used in ``m->opt.solver``.
70pub type MjtSolver = mjtSolver;
71
72/// Equality constraint types. These values are used in ``m->eq_type``.
73pub type MjtEq = mjtEq;
74
75/// Tendon wrapping object types. These values are used in ``m->wrap_type``.
76pub type MjtWrap = mjtWrap;
77
78/// Actuator transmission types. These values are used in ``m->actuator_trntype``.
79pub type MjtTrn = mjtTrn;
80
81/// Actuator dynamics types. These values are used in ``m->actuator_dyntype``.
82pub type MjtDyn = mjtDyn;
83
84/// Actuator gain types. These values are used in ``m->actuator_gaintype``.
85pub type MjtGain = mjtGain;
86
87/// Actuator bias types. These values are used in ``m->actuator_biastype``.
88pub type MjtBias = mjtBias;
89
90/// MuJoCo object types. These are used, for example, in the support functions `mj_name2id` and
91/// `mj_id2name` to convert between object names and integer ids.
92pub type MjtObj = mjtObj;
93
94/// Sensor types. These values are used in ``m->sensor_type``.
95pub type MjtSensor = mjtSensor;
96
97/// These are the compute stages for the skipstage parameters of `mj_forwardSkip` and
98/// `mj_inverseSkip`.
99pub type MjtStage = mjtStage;
100
101/// These are the possible sensor data types, used in ``mjData.sensor_datatype``.
102pub type MjtDataType = mjtDataType;
103
104/// Types of data fields returned by contact sensors.
105pub type MjtConDataField = mjtConDataField;
106
107/// Types of frame alignment of elements with their parent bodies. Used as shortcuts during `mj_kinematics` in the
108/// last argument to `mj_local2global`.
109pub type MjtSameFrame = mjtSameFrame;
110
111/// Types of flex self-collisions midphase.
112pub type MjtFlexSelf = mjtFlexSelf;
113
114/// Formulas used to combine SDFs when calling mjc_distance and mjc_gradient.
115pub type MjtSDFType = mjtSDFType;
116
117/*******************************************/
118
119/// A Rust-safe wrapper around mjModel.
120/// Automatically clean after itself on destruction.
121#[derive(Debug)]
122pub struct MjModel(*mut mjModel);
123
124// Allow usage in threaded contexts as the data won't be shared anywhere outside Rust,
125// except in the C++ code.
126unsafe impl Send for MjModel {}
127unsafe impl Sync for MjModel {}
128
129
130impl MjModel {
131    /// Loads the model from an XML file. To load from a virtual file system, use [`MjModel::from_xml_vfs`].
132    pub fn from_xml<T: AsRef<Path>>(path: T) -> Result<Self, Error> {
133        Self::from_xml_file(path, None)
134    }
135
136    /// Loads the model from an XML file, located in a virtual file system (`vfs`).
137    pub fn from_xml_vfs<T: AsRef<Path>>(path: T, vfs: &MjVfs) -> Result<Self, Error> {
138        Self::from_xml_file(path, Some(vfs))
139    }
140
141    fn from_xml_file<T: AsRef<Path>>(path: T, vfs: Option<&MjVfs>) -> Result<Self, Error> {
142        let mut error_buffer = [0i8; 100];
143        unsafe {
144            let path = CString::new(path.as_ref().to_str().expect("invalid utf")).unwrap();
145            let raw_ptr = mj_loadXML(
146                path.as_ptr(), vfs.map_or(ptr::null(), |v| v.ffi()),
147                &mut error_buffer as *mut i8, error_buffer.len() as c_int
148            );
149
150            Self::check_raw_model(raw_ptr, &error_buffer)
151        }
152    }
153
154    /// Loads the model from an XML string.
155    pub fn from_xml_string(data: &str) -> Result<Self, Error> {
156        let mut vfs = MjVfs::new();
157        let filename = "model.xml";
158
159        // Add the file into a virtual file system
160        vfs.add_from_buffer(filename, data.as_bytes())?;
161
162        let mut error_buffer = [0i8; 100];
163        unsafe {
164            let filename_c = CString::new(filename).unwrap();
165            let raw_ptr = mj_loadXML(
166                filename_c.as_ptr(), vfs.ffi(),
167                &mut error_buffer as *mut i8, error_buffer.len() as c_int
168            );
169
170            Self::check_raw_model(raw_ptr, &error_buffer)
171        }
172    }
173
174    /// Loads the model from MJB raw data.
175    pub fn from_buffer(data: &[u8]) -> Result<Self, Error> {
176        unsafe {
177            // Create a virtual FS since we don't have direct access to the load buffer function (or at least it isn't officially exposed).
178            // let raw_ptr = mj_loadModelBuffer(data.as_ptr() as *const c_void, data.len() as i32);
179            let mut vfs = MjVfs::new();
180            let filename = "model.mjb";
181
182            // Add the file into a virtual file system
183            vfs.add_from_buffer(filename, data)?;
184
185            // Load the model from the virtual file system
186            let filename_c = CString::new(filename).unwrap();
187            let raw_model = mj_loadModel(filename_c.as_ptr(), vfs.ffi());
188            Self::check_raw_model(raw_model, &[0])
189        }
190    }
191
192    /// Creates a [`MjModel`] from a raw pointer.
193    pub(crate) fn from_raw(ptr: *mut mjModel) -> Result<Self, Error> {
194        unsafe { Self::check_raw_model(ptr, &[0]) }
195    }
196
197    /// Saves the last XML loaded.
198    pub fn save_last_xml(&self, filename: &str) -> io::Result<()> {
199        let mut error = [0i8; 100];
200        unsafe {
201            let cstring = CString::new(filename)?;
202            match mj_saveLastXML(
203                cstring.as_ptr(), self.ffi(),
204                error.as_mut_ptr(), (error.len() - 1) as i32
205            ) {
206                1 => Ok(()),
207                0 => {
208                    let cstr_error = String::from_utf8_lossy(
209                        // Reinterpret as u8 data. This does not affect the data as it is ASCII
210                        // encoded and thus negative values aren't possible.
211                        std::slice::from_raw_parts(error.as_ptr() as *const u8, error.len())
212                    );
213                    Err(Error::new(ErrorKind::Other, cstr_error))
214                },
215                _ => unreachable!()
216            }
217        }
218    }
219
220    /// Creates a new [`MjData`] instances linked to this model.
221    pub fn make_data(&self) -> MjData<&Self> {
222        MjData::new(self)
223    }
224
225    /// Handles the pointer to the model.
226    /// # Safety
227    /// `error_buffer` must have at least on element, where the last element must be 0.
228    unsafe fn check_raw_model(ptr_model: *mut mjModel, error_buffer: &[i8]) -> Result<Self, Error> {
229        if ptr_model.is_null() {
230            Err(Error::new(
231                ErrorKind::UnexpectedEof,
232                unsafe { CStr::from_ptr(error_buffer.as_ptr().cast()).to_string_lossy().into_owned() }
233            ))
234        }
235        else {
236            Ok(Self(ptr_model))
237        }
238    }
239
240    info_method! { Model, ffi(), actuator, [
241        trntype: 1, dyntype: 1, gaintype: 1, biastype: 1, trnid: 2, actadr: 1, actnum: 1, group: 1, ctrllimited: 1,
242        forcelimited: 1, actlimited: 1, dynprm: mjNDYN as usize, gainprm: mjNGAIN as usize, biasprm: mjNBIAS as usize, 
243        actearly: 1, ctrlrange: 2, forcerange: 2, actrange: 2, gear: 6, cranklength: 1, acc0: 1, 
244        length0: 1, lengthrange: 2
245    ], [], []}
246
247    info_method! { Model, ffi(), sensor, [
248        r#type: 1, datatype: 1, needstage: 1,
249        objtype: 1, objid: 1, reftype: 1, refid: 1, intprm: mjNSENS as usize,
250        dim: 1, adr: 1, cutoff: 1, noise: 1
251    ], [], []}
252
253
254    info_method! { Model, ffi(), tendon, [
255        adr: 1, num: 1, matid: 1, group: 1, limited: 1,
256        actfrclimited: 1, width: 1, solref_lim: mjNREF as usize,
257        solimp_lim: mjNIMP as usize, solref_fri: mjNREF as usize, solimp_fri: mjNIMP as usize,
258        range: 2, actfrcrange: 2, margin: 1, stiffness: 1,
259        damping: 1, armature: 1, frictionloss: 1, lengthspring: 2,
260        length0: 1, invweight0: 1, rgba: 4
261    ], [], []}
262
263    info_method! { Model, ffi(), joint, [
264        r#type: 1, qposadr: 1, dofadr: 1, bodyid: 1, group: 1,
265        limited: 1, actfrclimited: 1, actgravcomp: 1, solref: mjNREF as usize,
266        solimp: mjNIMP as usize, pos: 3, axis: 3, stiffness: 1,
267        range: 2, actfrcrange: 2, margin: 1
268    ], [], []}
269
270    info_method! { Model, ffi(), geom, [
271        r#type: 1, contype: 1, conaffinity: 1, condim: 1, bodyid: 1, dataid: 1, matid: 1,
272        group: 1, priority: 1, plugin: 1, sameframe: 1, solmix: 1, solref: mjNREF as usize,
273        solimp: mjNIMP as usize,
274        size: 3, aabb: 6, rbound: 1, pos: 3, quat: 4, friction: 3, margin: 1, gap: 1,
275        fluid: mjNFLUID as usize, rgba: 4
276    ], [], []}
277
278    info_method! { Model, ffi(), body, [
279        parentid: 1, rootid: 1, weldid: 1, mocapid: 1,
280        jntnum: 1, jntadr: 1, dofnum: 1, dofadr: 1,
281        treeid: 1, geomnum: 1, geomadr: 1, simple: 1,
282        sameframe: 1, pos: 3, quat: 4, ipos: 3, iquat: 4,
283        mass: 1, subtreemass: 1, inertia: 3, invweight0: 2,
284        gravcomp: 1, margin: 1, plugin: 1,
285        contype: 1, conaffinity: 1, bvhadr: 1, bvhnum: 1
286    ], [], []}
287
288    info_method! { Model, ffi(), camera, [
289        mode: 1, bodyid: 1, targetbodyid: 1, pos: 3, quat: 4,
290        poscom0: 3, pos0: 3, mat0: 9, orthographic: 1, fovy: 1,
291        ipd: 1, resolution: 2, sensorsize: 2, intrinsic: 4
292    ], [], []}
293
294    info_method! { Model, ffi(), key, [
295        time: 1
296    ], [
297        qpos: nq, qvel: nv, act: na, mpos: nmocap * 3, mquat: nmocap * 4,
298        ctrl: nu
299    ], []}
300
301    info_method! { Model, ffi(), tuple, [
302        size: 1
303    ], [], [
304        objtype: ntupledata, objid: ntupledata, objprm: ntupledata
305    ]}
306
307    info_method! { Model, ffi(), texture, [
308        r#type: 1, colorspace: 1, height: 1, width: 1, nchannel: 1, pathadr: 1
309    ], [], [
310        data: ntexdata
311    ]}
312
313    info_method! { Model, ffi(), site, [
314        r#type: 1, bodyid: 1, group: 1, sameframe: 1, size: 3,
315        pos: 3, quat: 4, rgba: 4, matid: 1
316    ], [user: nuser_site], []}
317
318    info_method! { Model, ffi(), pair, [
319        dim: 1, geom1: 1, geom2: 1, signature: 1, solref: mjNREF as usize,
320        solreffriction: mjNREF as usize, solimp: mjNIMP as usize, margin: 1,
321        gap: 1, friction: 5
322    ], [], []}
323
324    info_method! { Model, ffi(), numeric, [
325        size: 1
326    ], [], [data: nnumericdata]}
327
328
329    info_method! { Model, ffi(), material, [
330        texuniform: 1,
331        texrepeat: 2,
332        emission: 1,
333        specular: 1,
334        shininess: 1,
335        reflectance: 1,
336        metallic: 1,
337        roughness: 1,
338        rgba: 4,
339        texid: MjtTextureRole::mjNTEXROLE as usize
340    ], [], [] }
341
342
343    info_method! { Model, ffi(), light, [
344        mode: 1, bodyid: 1, targetbodyid: 1, r#type: 1, texid: 1, castshadow: 1, bulbradius: 1,
345        intensity: 1, range: 1, active: 1, pos: 3, dir: 3, poscom0: 3, pos0: 3, dir0: 3,
346        attenuation: 3, cutoff: 1, exponent: 1, ambient: 3, diffuse: 3, specular: 3
347    ], [], []}
348
349    info_method! { Model, ffi(), equality, [
350        r#type: 1,          // mjtEq enum
351        obj1id: 1,
352        obj2id: 1,
353        objtype: 1,       // mjtObj enum
354        active0: 1,
355        solref: mjNREF as usize,
356        solimp: mjNIMP as usize,
357        data: mjNEQDATA as usize
358    ], [], []}
359
360    info_method! { Model, ffi(), hfield, [
361        size: 4,
362        nrow: 1,
363        ncol: 1,
364        pathadr: 1
365    ], [], [
366        data: nhfielddata
367    ]}
368
369    /// Deprecated alias for [`MjModel::name_to_id`].
370    #[deprecated]
371    pub fn name2id(&self, type_: MjtObj, name: &str) -> i32 {
372        self.name_to_id(type_, name)
373    }
374
375    /// Translates `name` to the correct id. Wrapper around `mj_name2id`.
376    /// # Panics
377    /// When the `name` contains '\0' characters, a panic occurs.
378    pub fn name_to_id(&self, type_: MjtObj, name: &str) -> i32 {
379        let c_string = CString::new(name).unwrap();
380        unsafe {
381            mj_name2id(self.0, type_ as i32, c_string.as_ptr())
382        }
383    }
384
385    /* Partially auto-generated */
386
387    /// Clones the model.
388    pub fn clone(&self) -> Option<MjModel> {
389        let ptr = unsafe { mj_copyModel(ptr::null_mut(), self.ffi()) };
390        if ptr.is_null() {
391            None
392        }
393        else {
394            Some(MjModel(ptr))
395        }
396    }
397
398    /// Save model to binary MJB file or memory buffer; buffer has precedence when given.
399    /// # Panics
400    /// When the `filename` contains '\0' characters, a panic occurs.
401    pub fn save(&self, filename: Option<&str>, buffer: Option<&mut [u8]>) {
402        let c_filename = filename.map(|f| CString::new(f).unwrap());
403        let (buffer_ptr, buffer_len) = if let Some(b) = buffer {
404            (b.as_mut_ptr(), b.len())
405        }
406        else {
407            (ptr::null_mut(), 0)
408        };
409        let c_filename_ptr = c_filename.as_ref().map_or(ptr::null(), |f| f.as_ptr());
410
411        unsafe { mj_saveModel(
412            self.ffi(), c_filename_ptr,
413            buffer_ptr as *mut std::ffi::c_void, buffer_len as i32
414        ) };
415    }
416
417    /// Return size of buffer needed to hold model.
418    pub fn size(&self) -> i32 {
419        unsafe { mj_sizeModel(self.ffi()) }
420    }
421
422    /// Print mjModel to text file, specifying format.
423    /// float_format must be a valid printf-style format string for a single float value.
424    pub fn print_formatted(&self, filename: &str, float_format: &str) -> Result<(), NulError> {
425        let c_filename = CString::new(filename)?;
426        let c_float_format = CString::new(float_format)?;
427        unsafe { mj_printFormattedModel(self.ffi(), c_filename.as_ptr(), c_float_format.as_ptr()) }
428        Ok(())
429    }
430
431    /// Print model to text file.
432    pub fn print(&self, filename: &str) -> Result<(), NulError> {
433        let c_filename = CString::new(filename)?;
434        unsafe { mj_printModel(self.ffi(), c_filename.as_ptr()) }
435        Ok(())
436    }
437
438    /// Return size of state specification. The bits of the integer spec correspond to element fields of [`MjtState`](crate::wrappers::mj_data::MjtState).
439    pub fn state_size(&self, spec: u32) -> i32 {
440        unsafe { mj_stateSize(self.ffi(), spec) }
441    }
442
443    /// Determine type of friction cone.
444    pub fn is_pyramidal(&self) -> bool {
445        unsafe { mj_isPyramidal(self.ffi()) == 1 }
446    }
447
448    /// Determine type of constraint Jacobian.
449    pub fn is_sparse(&self) -> bool {
450        unsafe { mj_isSparse(self.ffi()) == 1 }
451    }
452
453    /// Determine type of solver (PGS is dual, CG and Newton are primal).
454    pub fn is_dual(&self) -> bool {
455        unsafe { mj_isDual(self.ffi()) == 1 }
456    }
457
458    /// Get name of object with the specified [`MjtObj`] type and id, returns NULL if name not found.
459    /// Wraps ``mj_id2name``.
460    pub fn id_to_name(&self, type_: MjtObj, id: i32) -> Option<&str> {
461        let ptr = unsafe { mj_id2name(self.ffi(), type_ as i32, id) };
462        if ptr.is_null() {
463            None
464        }
465        else {
466            let cstr = unsafe { CStr::from_ptr(ptr).to_str().unwrap() };
467            Some(cstr)
468        }
469    }
470
471    /// Sum all body masses.
472    pub fn get_totalmass(&self) -> MjtNum {
473        unsafe { mj_getTotalmass(self.ffi()) }
474    }
475
476    /// Scale body masses and inertias to achieve specified total mass.
477    pub fn set_totalmass(&mut self, newmass: MjtNum) {
478        unsafe { mj_setTotalmass(self.ffi_mut(), newmass) }
479    }
480
481    /* FFI */
482    /// Returns a reference to the wrapped FFI struct.
483    pub fn ffi(&self) -> &mjModel {
484        unsafe { self.0.as_ref().unwrap() }
485    }
486
487    /// Returns a mutable reference to the wrapped FFI struct.
488    pub unsafe fn ffi_mut(&mut self) -> &mut mjModel {
489        unsafe { self.0.as_mut().unwrap() }
490    }
491
492    /// Returns a direct pointer to the underlying model.
493    /// THIS IS NOT TO BE USED.
494    /// It is only meant for the viewer code, which currently still depends
495    /// on mutable pointers to model and data. This will be removed in the future.
496    pub(crate) unsafe fn __raw(&self) -> *mut mjModel {
497        self.0
498    }
499}
500
501
502/// Public attribute methods.
503impl MjModel {
504    /// Compilation signature.
505    pub fn signature(&self) -> u64 {
506        self.ffi().signature
507    }
508
509    getter_setter! {get, [
510        [ffi] nq: i32; "number of generalized coordinates = dim(qpos).";
511        [ffi] nv: i32; "number of degrees of freedom = dim(qvel).";
512        [ffi] nu: i32; "number of actuators/controls = dim(ctrl).";
513        [ffi] na: i32; "number of activation states = dim(act).";
514        [ffi] nbody: i32; "number of bodies.";
515        [ffi] nbvh: i32; "number of total bounding volumes in all bodies.";
516        [ffi] nbvhstatic: i32; "number of static bounding volumes (aabb stored in mjModel).";
517        [ffi] nbvhdynamic: i32; "number of dynamic bounding volumes (aabb stored in mjData).";
518        [ffi] noct: i32; "number of total octree cells in all meshes.";
519        [ffi] njnt: i32; "number of joints.";
520        [ffi] ntree: i32; "number of kinematic trees under world body.";
521        [ffi] nM: i32; "number of non-zeros in sparse inertia matrix.";
522        [ffi] nB: i32; "number of non-zeros in sparse body-dof matrix.";
523        [ffi] nC: i32; "number of non-zeros in sparse reduced dof-dof matrix.";
524        [ffi] nD: i32; "number of non-zeros in sparse dof-dof matrix.";
525        [ffi] ngeom: i32; "number of geoms.";
526        [ffi] nsite: i32; "number of sites.";
527        [ffi] ncam: i32; "number of cameras.";
528        [ffi] nlight: i32; "number of lights.";
529        [ffi] nflex: i32; "number of flexes.";
530        [ffi] nflexnode: i32; "number of dofs in all flexes.";
531        [ffi] nflexvert: i32; "number of vertices in all flexes.";
532        [ffi] nflexedge: i32; "number of edges in all flexes.";
533        [ffi] nflexelem: i32; "number of elements in all flexes.";
534        [ffi] nflexelemdata: i32; "number of element vertex ids in all flexes.";
535        [ffi] nflexelemedge: i32; "number of element edge ids in all flexes.";
536        [ffi] nflexshelldata: i32; "number of shell fragment vertex ids in all flexes.";
537        [ffi] nflexevpair: i32; "number of element-vertex pairs in all flexes.";
538        [ffi] nflextexcoord: i32; "number of vertices with texture coordinates.";
539        [ffi] nmesh: i32; "number of meshes.";
540        [ffi] nmeshvert: i32; "number of vertices in all meshes.";
541        [ffi] nmeshnormal: i32; "number of normals in all meshes.";
542        [ffi] nmeshtexcoord: i32; "number of texcoords in all meshes.";
543        [ffi] nmeshface: i32; "number of triangular faces in all meshes.";
544        [ffi] nmeshgraph: i32; "number of ints in mesh auxiliary data.";
545        [ffi] nmeshpoly: i32; "number of polygons in all meshes.";
546        [ffi] nmeshpolyvert: i32; "number of vertices in all polygons.";
547        [ffi] nmeshpolymap: i32; "number of polygons in vertex map.";
548        [ffi] nskin: i32; "number of skins.";
549        [ffi] nskinvert: i32; "number of vertices in all skins.";
550        [ffi] nskintexvert: i32; "number of vertices with texcoords in all skins.";
551        [ffi] nskinface: i32; "number of triangular faces in all skins.";
552        [ffi] nskinbone: i32; "number of bones in all skins.";
553        [ffi] nskinbonevert: i32; "number of vertices in all skin bones.";
554        [ffi] nhfield: i32; "number of heightfields.";
555        [ffi] nhfielddata: i32; "number of data points in all heightfields.";
556        [ffi] ntex: i32; "number of textures.";
557        [ffi] ntexdata: i32; "number of bytes in texture rgb data.";
558        [ffi] nmat: i32; "number of materials.";
559        [ffi] npair: i32; "number of predefined geom pairs.";
560        [ffi] nexclude: i32; "number of excluded geom pairs.";
561        [ffi] neq: i32; "number of equality constraints.";
562        [ffi] ntendon: i32; "number of tendons.";
563        [ffi] nwrap: i32; "number of wrap objects in all tendon paths.";
564        [ffi] nsensor: i32; "number of sensors.";
565        [ffi] nnumeric: i32; "number of numeric custom fields.";
566        [ffi] nnumericdata: i32; "number of mjtNums in all numeric fields.";
567        [ffi] ntext: i32; "number of text custom fields.";
568        [ffi] ntextdata: i32; "number of mjtBytes in all text fields.";
569        [ffi] ntuple: i32; "number of tuple custom fields.";
570        [ffi] ntupledata: i32; "number of objects in all tuple fields.";
571        [ffi] nkey: i32; "number of keyframes.";
572        [ffi] nmocap: i32; "number of mocap bodies.";
573        [ffi] nplugin: i32; "number of plugin instances.";
574        [ffi] npluginattr: i32; "number of chars in all plugin config attributes.";
575        [ffi] nuser_body: i32; "number of mjtNums in body_user.";
576        [ffi] nuser_jnt: i32; "number of mjtNums in jnt_user.";
577        [ffi] nuser_geom: i32; "number of mjtNums in geom_user.";
578        [ffi] nuser_site: i32; "number of mjtNums in site_user.";
579        [ffi] nuser_cam: i32; "number of mjtNums in cam_user.";
580        [ffi] nuser_tendon: i32; "number of mjtNums in tendon_user.";
581        [ffi] nuser_actuator: i32; "number of mjtNums in actuator_user.";
582        [ffi] nuser_sensor: i32; "number of mjtNums in sensor_user.";
583        [ffi] nnames: i32; "number of chars in all names.";
584        [ffi] npaths: i32; "number of chars in all paths.";
585        [ffi] nnames_map: i32; "number of slots in the names hash map.";
586        [ffi] nJmom: i32; "number of non-zeros in sparse actuator_moment matrix.";
587        [ffi] ngravcomp: i32; "number of bodies with nonzero gravcomp.";
588        [ffi] nemax: i32; "number of potential equality-constraint rows.";
589        [ffi] njmax: i32; "number of available rows in constraint Jacobian (legacy).";
590        [ffi] nconmax: i32; "number of potential contacts in contact list (legacy).";
591        [ffi] nuserdata: i32; "number of mjtNums reserved for the user.";
592        [ffi] nsensordata: i32; "number of mjtNums in sensor data vector.";
593        [ffi] npluginstate: i32; "number of mjtNums in plugin state vector.";
594        [ffi] narena: MjtSize; "number of bytes in the mjData arena (inclusive of stack).";
595        [ffi] nbuffer: MjtSize; "number of bytes in buffer.";
596    ]}
597
598    getter_setter! {get, [
599        [ffi, ffi_mut] opt: &MjOption; "physics options.";
600        [ffi, ffi_mut] vis: &MjVisual; "visualization options.";
601        [ffi, ffi_mut] stat: &MjStatistic; "model statistics.";
602    ]}
603}
604
605/// Array slices.
606impl MjModel {
607    array_slice_dyn! {
608        qpos0: &[MjtNum; "qpos values at default pose"; ffi().nq],
609        qpos_spring: &[MjtNum; "reference pose for springs"; ffi().nq],
610        body_parentid: &[i32; "id of body's parent"; ffi().nbody],
611        body_rootid: &[i32; "id of root above body"; ffi().nbody],
612        body_weldid: &[i32; "id of body that this body is welded to"; ffi().nbody],
613        body_mocapid: &[i32; "id of mocap data; -1: none"; ffi().nbody],
614        body_jntnum: &[i32; "number of joints for this body"; ffi().nbody],
615        body_jntadr: &[i32; "start addr of joints; -1: no joints"; ffi().nbody],
616        body_dofnum: &[i32; "number of motion degrees of freedom"; ffi().nbody],
617        body_dofadr: &[i32; "start addr of dofs; -1: no dofs"; ffi().nbody],
618        body_treeid: &[i32; "id of body's kinematic tree; -1: static"; ffi().nbody],
619        body_geomnum: &[i32; "number of geoms"; ffi().nbody],
620        body_geomadr: &[i32; "start addr of geoms; -1: no geoms"; ffi().nbody],
621        body_simple: &[MjtByte; "1: diag M; 2: diag M, sliders only"; ffi().nbody],
622        body_sameframe: &[MjtSameFrame [cast]; "same frame as inertia"; ffi().nbody],
623        body_pos: &[[MjtNum; 3] [cast]; "position offset rel. to parent body"; ffi().nbody],
624        body_quat: &[[MjtNum; 4] [cast]; "orientation offset rel. to parent body"; ffi().nbody],
625        body_ipos: &[[MjtNum; 3] [cast]; "local position of center of mass"; ffi().nbody],
626        body_iquat: &[[MjtNum; 4] [cast]; "local orientation of inertia ellipsoid"; ffi().nbody],
627        body_mass: &[MjtNum; "mass"; ffi().nbody],
628        body_subtreemass: &[MjtNum; "mass of subtree starting at this body"; ffi().nbody],
629        body_inertia: &[[MjtNum; 3] [cast]; "diagonal inertia in ipos/iquat frame"; ffi().nbody],
630        body_invweight0: &[[MjtNum; 2] [cast]; "mean inv inert in qpos0 (trn, rot)"; ffi().nbody],
631        body_gravcomp: &[MjtNum; "antigravity force, units of body weight"; ffi().nbody],
632        body_margin: &[MjtNum; "MAX over all geom margins"; ffi().nbody],
633        body_plugin: &[i32; "plugin instance id; -1: not in use"; ffi().nbody],
634        body_contype: &[i32; "OR over all geom contypes"; ffi().nbody],
635        body_conaffinity: &[i32; "OR over all geom conaffinities"; ffi().nbody],
636        body_bvhadr: &[i32; "address of bvh root"; ffi().nbody],
637        body_bvhnum: &[i32; "number of bounding volumes"; ffi().nbody],
638        bvh_depth: &[i32; "depth in the bounding volume hierarchy"; ffi().nbvh],
639        bvh_child: &[[i32; 2] [cast]; "left and right children in tree"; ffi().nbvh],
640        bvh_nodeid: &[i32; "geom or elem id of node; -1: non-leaf"; ffi().nbvh],
641        bvh_aabb: &[[MjtNum; 6] [cast]; "local bounding box (center, size)"; ffi().nbvhstatic],
642        oct_depth: &[i32; "depth in the octree"; ffi().noct],
643        oct_child: &[[i32; 8] [cast]; "children of octree node"; ffi().noct],
644        oct_aabb: &[[MjtNum; 6] [cast]; "octree node bounding box (center, size)"; ffi().noct],
645        oct_coeff: &[[MjtNum; 8] [cast]; "octree interpolation coefficients"; ffi().noct],
646        jnt_type: &[MjtJoint [cast]; "type of joint"; ffi().njnt],
647        jnt_qposadr: &[i32; "start addr in 'qpos' for joint's data"; ffi().njnt],
648        jnt_dofadr: &[i32; "start addr in 'qvel' for joint's data"; ffi().njnt],
649        jnt_bodyid: &[i32; "id of joint's body"; ffi().njnt],
650        jnt_group: &[i32; "group for visibility"; ffi().njnt],
651        jnt_limited: &[bool [cast]; "does joint have limits"; ffi().njnt],
652        jnt_actfrclimited: &[bool [cast]; "does joint have actuator force limits"; ffi().njnt],
653        jnt_actgravcomp: &[bool [cast]; "is gravcomp force applied via actuators"; ffi().njnt],
654        jnt_solref: &[[MjtNum; mjNREF as usize] [cast]; "constraint solver reference: limit"; ffi().njnt],
655        jnt_solimp: &[[MjtNum; mjNIMP as usize] [cast]; "constraint solver impedance: limit"; ffi().njnt],
656        jnt_pos: &[[MjtNum; 3] [cast]; "local anchor position"; ffi().njnt],
657        jnt_axis: &[[MjtNum; 3] [cast]; "local joint axis"; ffi().njnt],
658        jnt_stiffness: &[MjtNum; "stiffness coefficient"; ffi().njnt],
659        jnt_range: &[[MjtNum; 2] [cast]; "joint limits"; ffi().njnt],
660        jnt_actfrcrange: &[[MjtNum; 2] [cast]; "range of total actuator force"; ffi().njnt],
661        jnt_margin: &[MjtNum; "min distance for limit detection"; ffi().njnt],
662        dof_bodyid: &[i32; "id of dof's body"; ffi().nv],
663        dof_jntid: &[i32; "id of dof's joint"; ffi().nv],
664        dof_parentid: &[i32; "id of dof's parent; -1: none"; ffi().nv],
665        dof_treeid: &[i32; "id of dof's kinematic tree"; ffi().nv],
666        dof_Madr: &[i32; "dof address in M-diagonal"; ffi().nv],
667        dof_simplenum: &[i32; "number of consecutive simple dofs"; ffi().nv],
668        dof_solref: &[[MjtNum; mjNREF as usize] [cast]; "constraint solver reference:frictionloss"; ffi().nv],
669        dof_solimp: &[[MjtNum; mjNIMP as usize] [cast]; "constraint solver impedance:frictionloss"; ffi().nv],
670        dof_frictionloss: &[MjtNum; "dof friction loss"; ffi().nv],
671        dof_armature: &[MjtNum; "dof armature inertia/mass"; ffi().nv],
672        dof_damping: &[MjtNum; "damping coefficient"; ffi().nv],
673        dof_invweight0: &[MjtNum; "diag. inverse inertia in qpos0"; ffi().nv],
674        dof_M0: &[MjtNum; "diag. inertia in qpos0"; ffi().nv],
675        geom_type: &[MjtGeom [cast]; "geometric type"; ffi().ngeom],
676        geom_contype: &[i32; "geom contact type"; ffi().ngeom],
677        geom_conaffinity: &[i32; "geom contact affinity"; ffi().ngeom],
678        geom_condim: &[i32; "contact dimensionality (1, 3, 4, 6)"; ffi().ngeom],
679        geom_bodyid: &[i32; "id of geom's body"; ffi().ngeom],
680        geom_dataid: &[i32; "id of geom's mesh/hfield; -1: none"; ffi().ngeom],
681        geom_matid: &[i32; "material id for rendering; -1: none"; ffi().ngeom],
682        geom_group: &[i32; "group for visibility"; ffi().ngeom],
683        geom_priority: &[i32; "geom contact priority"; ffi().ngeom],
684        geom_plugin: &[i32; "plugin instance id; -1: not in use"; ffi().ngeom],
685        geom_sameframe: &[MjtSameFrame [cast]; "same frame as body"; ffi().ngeom],
686        geom_solmix: &[MjtNum; "mixing coef for solref/imp in geom pair"; ffi().ngeom],
687        geom_solref: &[[MjtNum; mjNREF as usize] [cast]; "constraint solver reference: contact"; ffi().ngeom],
688        geom_solimp: &[[MjtNum; mjNIMP as usize] [cast]; "constraint solver impedance: contact"; ffi().ngeom],
689        geom_size: &[[MjtNum; 3] [cast]; "geom-specific size parameters"; ffi().ngeom],
690        geom_aabb: &[[MjtNum; 6] [cast]; "bounding box, (center, size)"; ffi().ngeom],
691        geom_rbound: &[MjtNum; "radius of bounding sphere"; ffi().ngeom],
692        geom_pos: &[[MjtNum; 3] [cast]; "local position offset rel. to body"; ffi().ngeom],
693        geom_quat: &[[MjtNum; 4] [cast]; "local orientation offset rel. to body"; ffi().ngeom],
694        geom_friction: &[[MjtNum; 3] [cast]; "friction for (slide, spin, roll)"; ffi().ngeom],
695        geom_margin: &[MjtNum; "detect contact if dist<margin"; ffi().ngeom],
696        geom_gap: &[MjtNum; "include in solver if dist<margin-gap"; ffi().ngeom],
697        geom_fluid: &[[MjtNum; mjNFLUID as usize] [cast]; "fluid interaction parameters"; ffi().ngeom],
698        geom_rgba: &[[f32; 4] [cast]; "rgba when material is omitted"; ffi().ngeom],
699        site_type: &[MjtGeom [cast]; "geom type for rendering"; ffi().nsite],
700        site_bodyid: &[i32; "id of site's body"; ffi().nsite],
701        site_matid: &[i32; "material id for rendering; -1: none"; ffi().nsite],
702        site_group: &[i32; "group for visibility"; ffi().nsite],
703        site_sameframe: &[MjtSameFrame [cast]; "same frame as body"; ffi().nsite],
704        site_size: &[[MjtNum; 3] [cast]; "geom size for rendering"; ffi().nsite],
705        site_pos: &[[MjtNum; 3] [cast]; "local position offset rel. to body"; ffi().nsite],
706        site_quat: &[[MjtNum; 4] [cast]; "local orientation offset rel. to body"; ffi().nsite],
707        site_rgba: &[[f32; 4] [cast]; "rgba when material is omitted"; ffi().nsite],
708        cam_mode: &[MjtCamLight [cast]; "camera tracking mode"; ffi().ncam],
709        cam_bodyid: &[i32; "id of camera's body"; ffi().ncam],
710        cam_targetbodyid: &[i32; "id of targeted body; -1: none"; ffi().ncam],
711        cam_pos: &[[MjtNum; 3] [cast]; "position rel. to body frame"; ffi().ncam],
712        cam_quat: &[[MjtNum; 4] [cast]; "orientation rel. to body frame"; ffi().ncam],
713        cam_poscom0: &[[MjtNum; 3] [cast]; "global position rel. to sub-com in qpos0"; ffi().ncam],
714        cam_pos0: &[[MjtNum; 3] [cast]; "global position rel. to body in qpos0"; ffi().ncam],
715        cam_mat0: &[[MjtNum; 9] [cast]; "global orientation in qpos0"; ffi().ncam],
716        cam_orthographic: &[i32; "orthographic camera; 0: no, 1: yes"; ffi().ncam],
717        cam_fovy: &[MjtNum; "y field-of-view (ortho ? len : deg)"; ffi().ncam],
718        cam_ipd: &[MjtNum; "inter-pupilary distance"; ffi().ncam],
719        cam_resolution: &[[i32; 2] [cast]; "resolution: pixels [width, height]"; ffi().ncam],
720        cam_sensorsize: &[[f32; 2] [cast]; "sensor size: length [width, height]"; ffi().ncam],
721        cam_intrinsic: &[[f32; 4] [cast]; "[focal length; principal point]"; ffi().ncam],
722        light_mode: &[MjtCamLight [cast]; "light tracking mode"; ffi().nlight],
723        light_bodyid: &[i32; "id of light's body"; ffi().nlight],
724        light_targetbodyid: &[i32; "id of targeted body; -1: none"; ffi().nlight],
725        light_type: &[MjtLightType [cast]; "spot, directional, etc."; ffi().nlight],
726        light_texid: &[i32; "texture id for image lights"; ffi().nlight],
727        light_castshadow: &[bool [cast]; "does light cast shadows"; ffi().nlight],
728        light_bulbradius: &[f32; "light radius for soft shadows"; ffi().nlight],
729        light_intensity: &[f32; "intensity, in candela"; ffi().nlight],
730        light_range: &[f32; "range of effectiveness"; ffi().nlight],
731        light_active: &[bool [cast]; "is light on"; ffi().nlight],
732        light_pos: &[[MjtNum; 3] [cast]; "position rel. to body frame"; ffi().nlight],
733        light_dir: &[[MjtNum; 3] [cast]; "direction rel. to body frame"; ffi().nlight],
734        light_poscom0: &[[MjtNum; 3] [cast]; "global position rel. to sub-com in qpos0"; ffi().nlight],
735        light_pos0: &[[MjtNum; 3] [cast]; "global position rel. to body in qpos0"; ffi().nlight],
736        light_dir0: &[[MjtNum; 3] [cast]; "global direction in qpos0"; ffi().nlight],
737        light_attenuation: &[[f32; 3] [cast]; "OpenGL attenuation (quadratic model)"; ffi().nlight],
738        light_cutoff: &[f32; "OpenGL cutoff"; ffi().nlight],
739        light_exponent: &[f32; "OpenGL exponent"; ffi().nlight],
740        light_ambient: &[[f32; 3] [cast]; "ambient rgb (alpha=1)"; ffi().nlight],
741        light_diffuse: &[[f32; 3] [cast]; "diffuse rgb (alpha=1)"; ffi().nlight],
742        light_specular: &[[f32; 3] [cast]; "specular rgb (alpha=1)"; ffi().nlight],
743        flex_contype: &[i32; "flex contact type"; ffi().nflex],
744        flex_conaffinity: &[i32; "flex contact affinity"; ffi().nflex],
745        flex_condim: &[i32; "contact dimensionality (1, 3, 4, 6)"; ffi().nflex],
746        flex_priority: &[i32; "flex contact priority"; ffi().nflex],
747        flex_solmix: &[MjtNum; "mix coef for solref/imp in contact pair"; ffi().nflex],
748        flex_solref: &[[MjtNum; mjNREF as usize] [cast]; "constraint solver reference: contact"; ffi().nflex],
749        flex_solimp: &[[MjtNum; mjNIMP as usize] [cast]; "constraint solver impedance: contact"; ffi().nflex],
750        flex_friction: &[[MjtNum; 3] [cast]; "friction for (slide, spin, roll)"; ffi().nflex],
751        flex_margin: &[MjtNum; "detect contact if dist<margin"; ffi().nflex],
752        flex_gap: &[MjtNum; "include in solver if dist<margin-gap"; ffi().nflex],
753        flex_internal: &[bool [cast]; "internal flex collision enabled"; ffi().nflex],
754        flex_selfcollide: &[MjtFlexSelf [cast]; "self collision mode"; ffi().nflex],
755        flex_activelayers: &[i32; "number of active element layers, 3D only"; ffi().nflex],
756        flex_passive: &[i32; "passive collisions enabled"; ffi().nflex],
757        flex_dim: &[i32; "1: lines, 2: triangles, 3: tetrahedra"; ffi().nflex],
758        flex_matid: &[i32; "material id for rendering"; ffi().nflex],
759        flex_group: &[i32; "group for visibility"; ffi().nflex],
760        flex_interp: &[i32; "interpolation (0: vertex, 1: nodes)"; ffi().nflex],
761        flex_nodeadr: &[i32; "first node address"; ffi().nflex],
762        flex_nodenum: &[i32; "number of nodes"; ffi().nflex],
763        flex_vertadr: &[i32; "first vertex address"; ffi().nflex],
764        flex_vertnum: &[i32; "number of vertices"; ffi().nflex],
765        flex_edgeadr: &[i32; "first edge address"; ffi().nflex],
766        flex_edgenum: &[i32; "number of edges"; ffi().nflex],
767        flex_elemadr: &[i32; "first element address"; ffi().nflex],
768        flex_elemnum: &[i32; "number of elements"; ffi().nflex],
769        flex_elemdataadr: &[i32; "first element vertex id address"; ffi().nflex],
770        flex_elemedgeadr: &[i32; "first element edge id address"; ffi().nflex],
771        flex_shellnum: &[i32; "number of shells"; ffi().nflex],
772        flex_shelldataadr: &[i32; "first shell data address"; ffi().nflex],
773        flex_evpairadr: &[i32; "first evpair address"; ffi().nflex],
774        flex_evpairnum: &[i32; "number of evpairs"; ffi().nflex],
775        flex_texcoordadr: &[i32; "address in flex_texcoord; -1: none"; ffi().nflex],
776        flex_nodebodyid: &[i32; "node body ids"; ffi().nflexnode],
777        flex_vertbodyid: &[i32; "vertex body ids"; ffi().nflexvert],
778        flex_edge: &[[i32; 2] [cast]; "edge vertex ids (2 per edge)"; ffi().nflexedge],
779        flex_edgeflap: &[[i32; 2] [cast]; "adjacent vertex ids (dim=2 only)"; ffi().nflexedge],
780        flex_elem: &[i32; "element vertex ids (dim+1 per elem)"; ffi().nflexelemdata],
781        flex_elemtexcoord: &[i32; "element texture coordinates (dim+1)"; ffi().nflexelemdata],
782        flex_elemedge: &[i32; "element edge ids"; ffi().nflexelemedge],
783        flex_elemlayer: &[i32; "element distance from surface, 3D only"; ffi().nflexelem],
784        flex_shell: &[i32; "shell fragment vertex ids (dim per frag)"; ffi().nflexshelldata],
785        flex_evpair: &[[i32; 2] [cast]; "(element, vertex) collision pairs"; ffi().nflexevpair],
786        flex_vert: &[[MjtNum; 3] [cast]; "vertex positions in local body frames"; ffi().nflexvert],
787        flex_vert0: &[[MjtNum; 3] [cast]; "vertex positions in qpos0 on [0, 1]^d"; ffi().nflexvert],
788        flex_node: &[[MjtNum; 3] [cast]; "node positions in local body frames"; ffi().nflexnode],
789        flex_node0: &[[MjtNum; 3] [cast]; "Cartesian node positions in qpos0"; ffi().nflexnode],
790        flexedge_length0: &[MjtNum; "edge lengths in qpos0"; ffi().nflexedge],
791        flexedge_invweight0: &[MjtNum; "edge inv. weight in qpos0"; ffi().nflexedge],
792        flex_radius: &[MjtNum; "radius around primitive element"; ffi().nflex],
793        flex_stiffness: &[[MjtNum; 21] [cast]; "finite element stiffness matrix"; ffi().nflexelem],
794        flex_bending: &[[MjtNum; 17] [cast]; "bending stiffness"; ffi().nflexedge],
795        flex_damping: &[MjtNum; "Rayleigh's damping coefficient"; ffi().nflex],
796        flex_edgestiffness: &[MjtNum; "edge stiffness"; ffi().nflex],
797        flex_edgedamping: &[MjtNum; "edge damping"; ffi().nflex],
798        flex_edgeequality: &[bool [cast]; "is edge equality constraint defined"; ffi().nflex],
799        flex_rigid: &[bool [cast]; "are all vertices in the same body"; ffi().nflex],
800        flexedge_rigid: &[bool [cast]; "are both edge vertices in same body"; ffi().nflexedge],
801        flex_centered: &[bool [cast]; "are all vertex coordinates (0,0,0)"; ffi().nflex],
802        flex_flatskin: &[bool [cast]; "render flex skin with flat shading"; ffi().nflex],
803        flex_bvhadr: &[i32; "address of bvh root; -1: no bvh"; ffi().nflex],
804        flex_bvhnum: &[i32; "number of bounding volumes"; ffi().nflex],
805        flex_rgba: &[[f32; 4] [cast]; "rgba when material is omitted"; ffi().nflex],
806        flex_texcoord: &[[f32; 2] [cast]; "vertex texture coordinates"; ffi().nflextexcoord],
807        mesh_vertadr: &[i32; "first vertex address"; ffi().nmesh],
808        mesh_vertnum: &[i32; "number of vertices"; ffi().nmesh],
809        mesh_faceadr: &[i32; "first face address"; ffi().nmesh],
810        mesh_facenum: &[i32; "number of faces"; ffi().nmesh],
811        mesh_bvhadr: &[i32; "address of bvh root"; ffi().nmesh],
812        mesh_bvhnum: &[i32; "number of bvh"; ffi().nmesh],
813        mesh_octadr: &[i32; "address of octree root"; ffi().nmesh],
814        mesh_octnum: &[i32; "number of octree nodes"; ffi().nmesh],
815        mesh_normaladr: &[i32; "first normal address"; ffi().nmesh],
816        mesh_normalnum: &[i32; "number of normals"; ffi().nmesh],
817        mesh_texcoordadr: &[i32; "texcoord data address; -1: no texcoord"; ffi().nmesh],
818        mesh_texcoordnum: &[i32; "number of texcoord"; ffi().nmesh],
819        mesh_graphadr: &[i32; "graph data address; -1: no graph"; ffi().nmesh],
820        mesh_vert: &[[f32; 3] [cast]; "vertex positions for all meshes"; ffi().nmeshvert],
821        mesh_normal: &[[f32; 3] [cast]; "normals for all meshes"; ffi().nmeshnormal],
822        mesh_texcoord: &[[f32; 2] [cast]; "vertex texcoords for all meshes"; ffi().nmeshtexcoord],
823        mesh_face: &[[i32; 3] [cast]; "vertex face data"; ffi().nmeshface],
824        mesh_facenormal: &[[i32; 3] [cast]; "normal face data"; ffi().nmeshface],
825        mesh_facetexcoord: &[[i32; 3] [cast]; "texture face data"; ffi().nmeshface],
826        mesh_graph: &[i32; "convex graph data"; ffi().nmeshgraph],
827        mesh_scale: &[[MjtNum; 3] [cast]; "scaling applied to asset vertices"; ffi().nmesh],
828        mesh_pos: &[[MjtNum; 3] [cast]; "translation applied to asset vertices"; ffi().nmesh],
829        mesh_quat: &[[MjtNum; 4] [cast]; "rotation applied to asset vertices"; ffi().nmesh],
830        mesh_pathadr: &[i32; "address of asset path for mesh; -1: none"; ffi().nmesh],
831        mesh_polynum: &[i32; "number of polygons per mesh"; ffi().nmesh],
832        mesh_polyadr: &[i32; "first polygon address per mesh"; ffi().nmesh],
833        mesh_polynormal: &[[MjtNum; 3] [cast]; "all polygon normals"; ffi().nmeshpoly],
834        mesh_polyvertadr: &[i32; "polygon vertex start address"; ffi().nmeshpoly],
835        mesh_polyvertnum: &[i32; "number of vertices per polygon"; ffi().nmeshpoly],
836        mesh_polyvert: &[i32; "all polygon vertices"; ffi().nmeshpolyvert],
837        mesh_polymapadr: &[i32; "first polygon address per vertex"; ffi().nmeshvert],
838        mesh_polymapnum: &[i32; "number of polygons per vertex"; ffi().nmeshvert],
839        mesh_polymap: &[i32; "vertex to polygon map"; ffi().nmeshpolymap],
840        skin_matid: &[i32; "skin material id; -1: none"; ffi().nskin],
841        skin_group: &[i32; "group for visibility"; ffi().nskin],
842        skin_rgba: &[[f32; 4] [cast]; "skin rgba"; ffi().nskin],
843        skin_inflate: &[f32; "inflate skin in normal direction"; ffi().nskin],
844        skin_vertadr: &[i32; "first vertex address"; ffi().nskin],
845        skin_vertnum: &[i32; "number of vertices"; ffi().nskin],
846        skin_texcoordadr: &[i32; "texcoord data address; -1: no texcoord"; ffi().nskin],
847        skin_faceadr: &[i32; "first face address"; ffi().nskin],
848        skin_facenum: &[i32; "number of faces"; ffi().nskin],
849        skin_boneadr: &[i32; "first bone in skin"; ffi().nskin],
850        skin_bonenum: &[i32; "number of bones in skin"; ffi().nskin],
851        skin_vert: &[[f32; 3] [cast]; "vertex positions for all skin meshes"; ffi().nskinvert],
852        skin_texcoord: &[[f32; 2] [cast]; "vertex texcoords for all skin meshes"; ffi().nskintexvert],
853        skin_face: &[[i32; 3] [cast]; "triangle faces for all skin meshes"; ffi().nskinface],
854        skin_bonevertadr: &[i32; "first vertex in each bone"; ffi().nskinbone],
855        skin_bonevertnum: &[i32; "number of vertices in each bone"; ffi().nskinbone],
856        skin_bonebindpos: &[[f32; 3] [cast]; "bind pos of each bone"; ffi().nskinbone],
857        skin_bonebindquat: &[[f32; 4] [cast]; "bind quat of each bone"; ffi().nskinbone],
858        skin_bonebodyid: &[i32; "body id of each bone"; ffi().nskinbone],
859        skin_bonevertid: &[i32; "mesh ids of vertices in each bone"; ffi().nskinbonevert],
860        skin_bonevertweight: &[f32; "weights of vertices in each bone"; ffi().nskinbonevert],
861        skin_pathadr: &[i32; "address of asset path for skin; -1: none"; ffi().nskin],
862        hfield_size: &[[MjtNum; 4] [cast]; "(x, y, z_top, z_bottom)"; ffi().nhfield],
863        hfield_nrow: &[i32; "number of rows in grid"; ffi().nhfield],
864        hfield_ncol: &[i32; "number of columns in grid"; ffi().nhfield],
865        hfield_adr: &[i32; "address in hfield_data"; ffi().nhfield],
866        hfield_data: &[f32; "elevation data"; ffi().nhfielddata],
867        hfield_pathadr: &[i32; "address of hfield asset path; -1: none"; ffi().nhfield],
868        tex_type: &[MjtTexture [cast]; "texture type"; ffi().ntex],
869        tex_colorspace: &[MjtColorSpace [cast]; "texture colorspace"; ffi().ntex],
870        tex_height: &[i32; "number of rows in texture image"; ffi().ntex],
871        tex_width: &[i32; "number of columns in texture image"; ffi().ntex],
872        tex_nchannel: &[i32; "number of channels in texture image"; ffi().ntex],
873        tex_adr: &[i32; "start address in tex_data"; ffi().ntex],
874        tex_data: &[MjtByte; "pixel values"; ffi().ntexdata],
875        tex_pathadr: &[i32; "address of texture asset path; -1: none"; ffi().ntex],
876        mat_texid: &[[i32; MjtTextureRole::mjNTEXROLE as usize] [cast]; "indices of textures; -1: none"; ffi().nmat],
877        mat_texuniform: &[bool [cast]; "make texture cube uniform"; ffi().nmat],
878        mat_texrepeat: &[[f32; 2] [cast]; "texture repetition for 2d mapping"; ffi().nmat],
879        mat_emission: &[f32; "emission (x rgb)"; ffi().nmat],
880        mat_specular: &[f32; "specular (x white)"; ffi().nmat],
881        mat_shininess: &[f32; "shininess coef"; ffi().nmat],
882        mat_reflectance: &[f32; "reflectance (0: disable)"; ffi().nmat],
883        mat_metallic: &[f32; "metallic coef"; ffi().nmat],
884        mat_roughness: &[f32; "roughness coef"; ffi().nmat],
885        mat_rgba: &[[f32; 4] [cast]; "rgba"; ffi().nmat],
886        pair_dim: &[i32; "contact dimensionality"; ffi().npair],
887        pair_geom1: &[i32; "id of geom1"; ffi().npair],
888        pair_geom2: &[i32; "id of geom2"; ffi().npair],
889        pair_signature: &[i32; "body1 << 16 + body2"; ffi().npair],
890        pair_solref: &[[MjtNum; mjNREF as usize] [cast]; "solver reference: contact normal"; ffi().npair],
891        pair_solreffriction: &[[MjtNum; mjNREF as usize] [cast]; "solver reference: contact friction"; ffi().npair],
892        pair_solimp: &[[MjtNum; mjNIMP as usize] [cast]; "solver impedance: contact"; ffi().npair],
893        pair_margin: &[MjtNum; "detect contact if dist<margin"; ffi().npair],
894        pair_gap: &[MjtNum; "include in solver if dist<margin-gap"; ffi().npair],
895        pair_friction: &[[MjtNum; 5] [cast]; "tangent1, 2, spin, roll1, 2"; ffi().npair],
896        exclude_signature: &[i32; "body1 << 16 + body2"; ffi().nexclude],
897        eq_type: &[MjtEq [cast]; "constraint type"; ffi().neq],
898        eq_obj1id: &[i32; "id of object 1"; ffi().neq],
899        eq_obj2id: &[i32; "id of object 2"; ffi().neq],
900        eq_objtype: &[MjtObj [cast]; "type of both objects"; ffi().neq],
901        eq_active0: &[bool [cast]; "initial enable/disable constraint state"; ffi().neq],
902        eq_solref: &[[MjtNum; mjNREF as usize] [cast]; "constraint solver reference"; ffi().neq],
903        eq_solimp: &[[MjtNum; mjNIMP as usize] [cast]; "constraint solver impedance"; ffi().neq],
904        eq_data: &[[MjtNum; mjNEQDATA as usize] [cast]; "numeric data for constraint"; ffi().neq],
905        tendon_adr: &[i32; "address of first object in tendon's path"; ffi().ntendon],
906        tendon_num: &[i32; "number of objects in tendon's path"; ffi().ntendon],
907        tendon_matid: &[i32; "material id for rendering"; ffi().ntendon],
908        tendon_group: &[i32; "group for visibility"; ffi().ntendon],
909        tendon_limited: &[bool [cast]; "does tendon have length limits"; ffi().ntendon],
910        tendon_actfrclimited: &[bool [cast]; "does tendon have actuator force limits"; ffi().ntendon],
911        tendon_width: &[MjtNum; "width for rendering"; ffi().ntendon],
912        tendon_solref_lim: &[[MjtNum; mjNREF as usize] [cast]; "constraint solver reference: limit"; ffi().ntendon],
913        tendon_solimp_lim: &[[MjtNum; mjNIMP as usize] [cast]; "constraint solver impedance: limit"; ffi().ntendon],
914        tendon_solref_fri: &[[MjtNum; mjNREF as usize] [cast]; "constraint solver reference: friction"; ffi().ntendon],
915        tendon_solimp_fri: &[[MjtNum; mjNIMP as usize] [cast]; "constraint solver impedance: friction"; ffi().ntendon],
916        tendon_range: &[[MjtNum; 2] [cast]; "tendon length limits"; ffi().ntendon],
917        tendon_actfrcrange: &[[MjtNum; 2] [cast]; "range of total actuator force"; ffi().ntendon],
918        tendon_margin: &[MjtNum; "min distance for limit detection"; ffi().ntendon],
919        tendon_stiffness: &[MjtNum; "stiffness coefficient"; ffi().ntendon],
920        tendon_damping: &[MjtNum; "damping coefficient"; ffi().ntendon],
921        tendon_armature: &[MjtNum; "inertia associated with tendon velocity"; ffi().ntendon],
922        tendon_frictionloss: &[MjtNum; "loss due to friction"; ffi().ntendon],
923        tendon_lengthspring: &[[MjtNum; 2] [cast]; "spring resting length range"; ffi().ntendon],
924        tendon_length0: &[MjtNum; "tendon length in qpos0"; ffi().ntendon],
925        tendon_invweight0: &[MjtNum; "inv. weight in qpos0"; ffi().ntendon],
926        tendon_rgba: &[[f32; 4] [cast]; "rgba when material is omitted"; ffi().ntendon],
927        wrap_type: &[MjtWrap [cast]; "wrap object type"; ffi().nwrap],
928        wrap_objid: &[i32; "object id: geom, site, joint"; ffi().nwrap],
929        wrap_prm: &[MjtNum; "divisor, joint coef, or site id"; ffi().nwrap],
930        actuator_trntype: &[MjtTrn [cast]; "transmission type"; ffi().nu],
931        actuator_dyntype: &[MjtDyn [cast]; "dynamics type"; ffi().nu],
932        actuator_gaintype: &[MjtGain [cast]; "gain type"; ffi().nu],
933        actuator_biastype: &[MjtBias [cast]; "bias type"; ffi().nu],
934        actuator_trnid: &[[i32; 2] [cast]; "transmission id: joint, tendon, site"; ffi().nu],
935        actuator_actadr: &[i32; "first activation address; -1: stateless"; ffi().nu],
936        actuator_actnum: &[i32; "number of activation variables"; ffi().nu],
937        actuator_group: &[i32; "group for visibility"; ffi().nu],
938        actuator_ctrllimited: &[bool [cast]; "is control limited"; ffi().nu],
939        actuator_actlimited: &[bool [cast]; "is activation limited"; ffi().nu],
940        actuator_dynprm: &[[MjtNum; mjNDYN as usize] [cast]; "dynamics parameters"; ffi().nu],
941        actuator_gainprm: &[[MjtNum; mjNGAIN as usize] [cast]; "gain parameters"; ffi().nu],
942        actuator_biasprm: &[[MjtNum; mjNBIAS as usize] [cast]; "bias parameters"; ffi().nu],
943        actuator_actearly: &[bool [cast]; "step activation before force"; ffi().nu],
944        actuator_ctrlrange: &[[MjtNum; 2] [cast]; "range of controls"; ffi().nu],
945        actuator_forcerange: &[[MjtNum; 2] [cast]; "range of forces"; ffi().nu],
946        actuator_actrange: &[[MjtNum; 2] [cast]; "range of activations"; ffi().nu],
947        actuator_gear: &[[MjtNum; 6] [cast]; "scale length and transmitted force"; ffi().nu],
948        actuator_cranklength: &[MjtNum; "crank length for slider-crank"; ffi().nu],
949        actuator_acc0: &[MjtNum; "acceleration from unit force in qpos0"; ffi().nu],
950        actuator_length0: &[MjtNum; "actuator length in qpos0"; ffi().nu],
951        actuator_lengthrange: &[[MjtNum; 2] [cast]; "feasible actuator length range"; ffi().nu],
952        actuator_plugin: &[i32; "plugin instance id; -1: not a plugin"; ffi().nu],
953        sensor_type: &[MjtSensor [cast]; "sensor type"; ffi().nsensor],
954        sensor_datatype: &[MjtDataType [cast]; "numeric data type"; ffi().nsensor],
955        sensor_needstage: &[MjtStage [cast]; "required compute stage"; ffi().nsensor],
956        sensor_objtype: &[MjtObj [cast]; "type of sensorized object"; ffi().nsensor],
957        sensor_objid: &[i32; "id of sensorized object"; ffi().nsensor],
958        sensor_reftype: &[MjtObj [cast]; "type of reference frame"; ffi().nsensor],
959        sensor_refid: &[i32; "id of reference frame; -1: global frame"; ffi().nsensor],
960        sensor_intprm: &[[i32; mjNSENS as usize] [cast]; "sensor parameters"; ffi().nsensor],
961        sensor_dim: &[i32; "number of scalar outputs"; ffi().nsensor],
962        sensor_adr: &[i32; "address in sensor array"; ffi().nsensor],
963        sensor_cutoff: &[MjtNum; "cutoff for real and positive; 0: ignore"; ffi().nsensor],
964        sensor_noise: &[MjtNum; "noise standard deviation"; ffi().nsensor],
965        sensor_plugin: &[i32; "plugin instance id; -1: not a plugin"; ffi().nsensor],
966        plugin: &[i32; "globally registered plugin slot number"; ffi().nplugin],
967        plugin_stateadr: &[i32; "address in the plugin state array"; ffi().nplugin],
968        plugin_statenum: &[i32; "number of states in the plugin instance"; ffi().nplugin],
969        plugin_attr: &[i8; "config attributes of plugin instances"; ffi().npluginattr],
970        plugin_attradr: &[i32; "address to each instance's config attrib"; ffi().nplugin],
971        numeric_adr: &[i32; "address of field in numeric_data"; ffi().nnumeric],
972        numeric_size: &[i32; "size of numeric field"; ffi().nnumeric],
973        numeric_data: &[MjtNum; "array of all numeric fields"; ffi().nnumericdata],
974        text_adr: &[i32; "address of text in text_data"; ffi().ntext],
975        text_size: &[i32; "size of text field (strlen+1)"; ffi().ntext],
976        text_data: &[i8; "array of all text fields (0-terminated)"; ffi().ntextdata],
977        tuple_adr: &[i32; "address of text in text_data"; ffi().ntuple],
978        tuple_size: &[i32; "number of objects in tuple"; ffi().ntuple],
979        tuple_objtype: &[i32; "array of object types in all tuples"; ffi().ntupledata],
980        tuple_objid: &[i32; "array of object ids in all tuples"; ffi().ntupledata],
981        tuple_objprm: &[MjtNum; "array of object params in all tuples"; ffi().ntupledata],
982        key_time: &[MjtNum; "key time"; ffi().nkey],
983        name_bodyadr: &[i32; "body name pointers"; ffi().nbody],
984        name_jntadr: &[i32; "joint name pointers"; ffi().njnt],
985        name_geomadr: &[i32; "geom name pointers"; ffi().ngeom],
986        name_siteadr: &[i32; "site name pointers"; ffi().nsite],
987        name_camadr: &[i32; "camera name pointers"; ffi().ncam],
988        name_lightadr: &[i32; "light name pointers"; ffi().nlight],
989        name_flexadr: &[i32; "flex name pointers"; ffi().nflex],
990        name_meshadr: &[i32; "mesh name pointers"; ffi().nmesh],
991        name_skinadr: &[i32; "skin name pointers"; ffi().nskin],
992        name_hfieldadr: &[i32; "hfield name pointers"; ffi().nhfield],
993        name_texadr: &[i32; "texture name pointers"; ffi().ntex],
994        name_matadr: &[i32; "material name pointers"; ffi().nmat],
995        name_pairadr: &[i32; "geom pair name pointers"; ffi().npair],
996        name_excludeadr: &[i32; "exclude name pointers"; ffi().nexclude],
997        name_eqadr: &[i32; "equality constraint name pointers"; ffi().neq],
998        name_tendonadr: &[i32; "tendon name pointers"; ffi().ntendon],
999        name_actuatoradr: &[i32; "actuator name pointers"; ffi().nu],
1000        name_sensoradr: &[i32; "sensor name pointers"; ffi().nsensor],
1001        name_numericadr: &[i32; "numeric name pointers"; ffi().nnumeric],
1002        name_textadr: &[i32; "text name pointers"; ffi().ntext],
1003        name_tupleadr: &[i32; "tuple name pointers"; ffi().ntuple],
1004        name_keyadr: &[i32; "keyframe name pointers"; ffi().nkey],
1005        name_pluginadr: &[i32; "plugin instance name pointers"; ffi().nplugin],
1006        names: &[i8; "names of all objects, 0-terminated"; ffi().nnames],
1007        names_map: &[i32; "internal hash map of names"; ffi().nnames_map],
1008        paths: &[i8; "paths to assets, 0-terminated"; ffi().npaths],
1009        B_rownnz: &[i32; "body-dof: non-zeros in each row"; ffi().nbody],
1010        B_rowadr: &[i32; "body-dof: row addresses"; ffi().nbody],
1011        B_colind: &[i32; "body-dof: column indices"; ffi().nB],
1012        M_rownnz: &[i32; "reduced inertia: non-zeros in each row"; ffi().nv],
1013        M_rowadr: &[i32; "reduced inertia: row addresses"; ffi().nv],
1014        M_colind: &[i32; "reduced inertia: column indices"; ffi().nC],
1015        mapM2M: &[i32; "index mapping from qM to M"; ffi().nC],
1016        D_rownnz: &[i32; "full inertia: non-zeros in each row"; ffi().nv],
1017        D_rowadr: &[i32; "full inertia: row addresses"; ffi().nv],
1018        D_diag: &[i32; "full inertia: index of diagonal element"; ffi().nv],
1019        D_colind: &[i32; "full inertia: column indices"; ffi().nD],
1020        mapM2D: &[i32; "index mapping from M to D"; ffi().nD],
1021        mapD2M: &[i32; "index mapping from D to M"; ffi().nC]
1022    }
1023
1024    array_slice_dyn! {
1025        sublen_dep {
1026            key_qpos: &[[MjtNum; ffi().nq] [cast]; "key position"; ffi().nkey],
1027            key_qvel: &[[MjtNum; ffi().nv] [cast]; "key velocity"; ffi().nkey],
1028            key_act: &[[MjtNum; ffi().na] [cast]; "key activation"; ffi().nkey],
1029            key_ctrl: &[[MjtNum; ffi().nu] [cast]; "key control"; ffi().nkey],
1030
1031            sensor_user: &[[MjtNum; ffi().nuser_sensor] [cast]; "user data"; ffi().nsensor],
1032            actuator_user: &[[MjtNum; ffi().nuser_actuator] [cast]; "user data"; ffi().nu],
1033            tendon_user: &[[MjtNum; ffi().nuser_tendon] [cast]; "user data"; ffi().ntendon],
1034            cam_user: &[[MjtNum; ffi().nuser_cam] [cast]; "user data"; ffi().ncam],
1035            site_user: &[[MjtNum; ffi().nuser_site] [cast]; "user data"; ffi().nsite],
1036            geom_user: &[[MjtNum; ffi().nuser_geom] [cast]; "user data"; ffi().ngeom],
1037            jnt_user: &[[MjtNum; ffi().nuser_jnt] [cast]; "user data"; ffi().njnt],
1038            body_user: &[[MjtNum; ffi().nuser_body] [cast]; "user data"; ffi().nbody]
1039        }
1040    }
1041}
1042
1043impl Drop for MjModel {
1044    fn drop(&mut self) {
1045        unsafe {
1046            mj_deleteModel(self.0);
1047        }
1048    }
1049}
1050
1051
1052/**************************************************************************************************/
1053// Actuator view
1054/**************************************************************************************************/
1055info_with_view!(Model, actuator, actuator_,
1056    [
1057        trntype: MjtTrn, dyntype: MjtDyn, gaintype: MjtGain, biastype: MjtBias, trnid: i32,
1058        actadr: i32, actnum: i32, group: i32, ctrllimited: bool,
1059        forcelimited: bool, actlimited: bool, dynprm: MjtNum, gainprm: MjtNum, biasprm: MjtNum,
1060        actearly: bool, ctrlrange: MjtNum, forcerange: MjtNum, actrange: MjtNum,
1061        gear: MjtNum, cranklength: MjtNum, acc0: MjtNum, length0: MjtNum, lengthrange: MjtNum
1062    ], []
1063);
1064
1065
1066/**************************************************************************************************/
1067// Sensor view
1068/**************************************************************************************************/
1069info_with_view!(Model, sensor, sensor_,
1070    [
1071        r#type: MjtSensor, datatype: MjtDataType, needstage: MjtStage,
1072        objtype: MjtObj, objid: i32, reftype: MjtObj, refid: i32, intprm: i32,
1073        dim: i32, adr: i32, cutoff: MjtNum, noise: MjtNum
1074    ], []
1075);
1076
1077
1078/**************************************************************************************************/
1079// Tendon view
1080/**************************************************************************************************/
1081info_with_view!(Model, tendon, tendon_,
1082    [
1083        adr: i32, num: i32, matid: i32, group: i32, limited: bool,
1084        actfrclimited: bool, width: MjtNum, solref_lim: MjtNum,
1085        solimp_lim: MjtNum, solref_fri: MjtNum, solimp_fri: MjtNum,
1086        range: MjtNum, actfrcrange: MjtNum, margin: MjtNum, stiffness: MjtNum,
1087        damping: MjtNum, armature: MjtNum, frictionloss: MjtNum, lengthspring: MjtNum,
1088        length0: MjtNum, invweight0: MjtNum, rgba: f32
1089    ], []
1090);
1091
1092
1093/**************************************************************************************************/
1094// Joint view
1095/**************************************************************************************************/
1096info_with_view!(Model, joint, jnt_,
1097    [
1098        r#type: MjtJoint, qposadr: i32, dofadr: i32, bodyid: i32, group: i32,
1099        limited: bool, actfrclimited: bool, actgravcomp: bool, solref: MjtNum,
1100        solimp: MjtNum, pos: MjtNum, axis: MjtNum, stiffness: MjtNum,
1101        range: MjtNum, actfrcrange: MjtNum, margin: MjtNum
1102    ], []
1103);
1104
1105/**************************************************************************************************/
1106// Geom view
1107/**************************************************************************************************/
1108info_with_view!(Model, geom, geom_,
1109    [
1110        r#type: MjtGeom, contype: i32, conaffinity: i32, condim: i32, bodyid: i32, dataid: i32, matid: i32,
1111        group: i32, priority: i32, plugin: i32, sameframe: MjtSameFrame, solmix: MjtNum, solref: MjtNum, solimp: MjtNum,
1112        size: MjtNum, aabb: MjtNum, rbound: MjtNum, pos: MjtNum, quat: MjtNum, friction: MjtNum, margin: MjtNum, gap: MjtNum,
1113        fluid: MjtNum, rgba: f32
1114    ], []
1115);
1116
1117/**************************************************************************************************/
1118// Body view
1119/**************************************************************************************************/
1120info_with_view!(Model, body, body_,
1121    [
1122        parentid: i32, rootid: i32, weldid: i32, mocapid: i32,
1123        jntnum: i32, jntadr: i32, dofnum: i32, dofadr: i32,
1124        treeid: i32, geomnum: i32, geomadr: i32, simple: MjtByte,
1125        sameframe: MjtSameFrame, pos: MjtNum, quat: MjtNum, ipos: MjtNum, iquat: MjtNum,
1126        mass: MjtNum, subtreemass: MjtNum, inertia: MjtNum, invweight0: MjtNum,
1127        gravcomp: MjtNum, margin: MjtNum, plugin: i32,
1128        contype: i32, conaffinity: i32, bvhadr: i32, bvhnum: i32
1129    ], []
1130);
1131
1132
1133/**************************************************************************************************/
1134// Camera view
1135/**************************************************************************************************/
1136info_with_view!(Model, camera, cam_,
1137    [
1138        mode: MjtCamLight, bodyid: i32, targetbodyid: i32, pos: MjtNum, quat: MjtNum,
1139        poscom0: MjtNum, pos0: MjtNum, mat0: MjtNum, orthographic: bool, fovy: MjtNum,
1140        ipd: MjtNum, resolution: i32, sensorsize: f32, intrinsic: f32
1141    ], []
1142);
1143
1144/**************************************************************************************************/
1145// KeyFrame view
1146/**************************************************************************************************/
1147info_with_view!(Model, key, key_,
1148    [
1149        time: MjtNum, qpos: MjtNum, qvel: MjtNum, act: MjtNum, mpos: MjtNum,
1150        mquat: MjtNum, ctrl: MjtNum
1151    ], []
1152);
1153
1154/**************************************************************************************************/
1155// Tuple view
1156/**************************************************************************************************/
1157info_with_view!(Model, tuple, tuple_,
1158    [
1159        size: i32, objtype: MjtObj, objid: i32, objprm: MjtNum
1160    ], []
1161);
1162
1163
1164/**************************************************************************************************/
1165// Texture view
1166/**************************************************************************************************/
1167info_with_view!(Model, texture, tex_,
1168    [
1169        r#type: MjtTexture, colorspace: MjtColorSpace, height: i32, width: i32, nchannel: i32,
1170        data: MjtByte
1171    ], [pathadr: i32]
1172);
1173
1174/**************************************************************************************************/
1175// Site view
1176/**************************************************************************************************/
1177info_with_view!(Model, site, site_,
1178    [
1179        r#type: MjtGeom, bodyid: i32, group: i32, sameframe: MjtSameFrame, size: MjtNum,
1180        pos: MjtNum, quat: MjtNum, user: MjtNum, rgba: f32
1181    ], [matid: i32]
1182);
1183
1184/**************************************************************************************************/
1185// Pair view
1186/**************************************************************************************************/
1187info_with_view!(Model, pair, pair_,
1188    [
1189        dim: i32, geom1: i32, geom2: i32, signature: i32, solref: MjtNum, solreffriction: MjtNum,
1190        solimp: MjtNum, margin: MjtNum, gap: MjtNum, friction: MjtNum
1191    ], []
1192);
1193
1194
1195/**************************************************************************************************/
1196// Numeric view
1197/**************************************************************************************************/
1198info_with_view!(Model, numeric, numeric_,
1199    [
1200        size: i32, data: MjtNum
1201    ], []
1202);
1203
1204/**************************************************************************************************/
1205// Material view
1206/**************************************************************************************************/
1207info_with_view!(Model, material, mat_,
1208    [
1209        texuniform: bool,
1210        texrepeat: f32,
1211        emission: f32,
1212        specular: f32,
1213        shininess: f32,
1214        reflectance: f32,
1215        metallic: f32,
1216        roughness: f32,
1217        rgba: f32,
1218        texid: i32
1219    ], []
1220);
1221
1222/**************************************************************************************************/
1223// Light view
1224/**************************************************************************************************/
1225info_with_view!(Model, light, light_,
1226    [
1227        mode: MjtCamLight, bodyid: i32, targetbodyid: i32, r#type: MjtLightType, texid: i32, castshadow: bool,
1228        bulbradius: f32, intensity: f32, range: f32, active: bool, pos: MjtNum, dir: MjtNum,
1229        poscom0: MjtNum, pos0: MjtNum, dir0: MjtNum, attenuation: f32, cutoff: f32, exponent: f32,
1230        ambient: f32, diffuse: f32, specular: f32
1231    ], []
1232);
1233
1234/**************************************************************************************************/
1235// Equality view
1236/**************************************************************************************************/
1237info_with_view!(Model, equality, eq_,
1238    [
1239        r#type: MjtEq,
1240        obj1id: i32,
1241        obj2id: i32,
1242        objtype: MjtObj,
1243        active0: bool,
1244        solref: MjtNum,
1245        solimp: MjtNum,
1246        data: MjtNum
1247    ], []
1248);
1249
1250
1251/**************************************************************************************************/
1252// Height field view
1253/**************************************************************************************************/
1254info_with_view!(Model, hfield, hfield_,
1255    [
1256        size: MjtNum,
1257        nrow: i32,
1258        ncol: i32,
1259        data: f32,
1260        pathadr: i32
1261    ], []
1262);
1263
1264#[cfg(test)]
1265mod tests {
1266    use crate::assert_relative_eq;
1267
1268    use super::*;
1269    use std::fs;
1270
1271    const EXAMPLE_MODEL: &str = stringify!(
1272    <mujoco>
1273        <worldbody>
1274            <light name="lamp_light1"
1275                mode="fixed" type="directional" castshadow="false" bulbradius="0.5" intensity="250"
1276                range="10" active="true" pos="0 0 0" dir="0 0 -1" attenuation="0.1 0.05 0.01"
1277                cutoff="60" exponent="2" ambient="0.1 0.1 0.25" diffuse="0.5 1 1" specular="1 1.5 1"/>
1278
1279            <light name="lamp_light2"
1280                mode="fixed" type="spot" castshadow="true" bulbradius="0.2" intensity="500"
1281                range="10" active="true" pos="0 0 0" dir="0 0 -1" attenuation="0.1 0.05 0.01"
1282                cutoff="45" exponent="2" ambient="0.1 0.1 0.1" diffuse="1 1 1" specular="1 1 1"/>
1283
1284            <camera name="cam1" fovy="50" resolution="100 200"/>
1285
1286            <light ambient="0.2 0.2 0.2"/>
1287            <body name="ball">
1288                <geom name="green_sphere" pos=".2 .2 .2" size=".1" rgba="0 1 0 1"/>
1289                <joint name="ball" type="free" axis="1 1 1"/>
1290                <site name="touch" size="1" type="box"/>
1291            </body>
1292
1293            <body name="ball1" pos="-.5 0 0">
1294                <geom size=".1" rgba="0 1 0 1" mass="1"/>
1295                <joint type="free"/>
1296                <site name="ball1" size=".1 .1 .1" pos="0 0 0" rgba="0 1 0 0.2" type="box"/>
1297                <site name="ball12" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1298                <site name="ball13" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1299            </body>
1300
1301            <body name="ball2"  pos=".5 0 0">
1302                <geom name="ball2" size=".5" rgba="0 1 1 1" mass="1"/>
1303                <joint name="ball2" type="free"/>
1304                <site name="ball2" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1305                <site name="ball22" size="0.5 0.25 0.5" pos="5 1 3" rgba="1 2 3 1" type="box"/>
1306                <site name="ball23" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1307            </body>
1308
1309            <geom name="floor" type="plane" size="10 10 1" euler="5 0 0"/>
1310
1311            <body name="slider">
1312                <geom name="rod" type="cylinder" size="1 10 0" euler="90 0 0" pos="0 0 10"/>
1313                <joint name="rod" type="slide" axis="0 1 0" range="0 1"/>
1314            </body>
1315
1316            <body name="ball3"  pos="0 0 5">
1317                <geom name="ball31" size=".5" rgba="0 1 1 1" mass="1"/>
1318                <joint type="slide"/>
1319            </body>
1320
1321            <body name="ball32"  pos="0 0 -5">
1322                <geom name="ball32" size=".5" rgba="0 1 1 1" mass="1"/>
1323                <joint type="slide"/>
1324            </body>
1325
1326            <body name="eq_body1" pos="0 0 0">
1327                <geom size="0.1"/>
1328            </body>
1329            <body name="eq_body2" pos="1 0 0">
1330                <geom size="0.1"/>
1331            </body>
1332            <body name="eq_body3" pos="0 0 0">
1333                <geom size="0.1"/>
1334            </body>
1335            <body name="eq_body4" pos="1 0 0">
1336                <geom size="0.1"/>
1337            </body>
1338        </worldbody>
1339
1340        
1341        <equality>
1342            <connect name="eq1" body1="eq_body1" body2="eq_body2" anchor="15 0 10"/>
1343            <connect name="eq2" body1="eq_body2" body2="eq_body1" anchor="-5 0 10"/>
1344            <connect name="eq3" body1="eq_body3" body2="eq_body4" anchor="0 5 0"/>
1345            <connect name="eq4" body1="eq_body4" body2="eq_body3" anchor="5 5 10"/>
1346        </equality>
1347
1348
1349        <actuator>
1350            <general name="slider" joint="rod" biastype="affine" ctrlrange="0 1" dynprm="1 2 3 4 5 6 7 8 9 10" gaintype="fixed"/>
1351            <general name="slider2" joint="ball2" biastype="affine" ctrlrange="0 1" dynprm="10 9 8 7 6 5 4 3 2 1" gaintype="fixed"/>
1352        </actuator>
1353
1354        <sensor>
1355            <touch name="touch" site="touch"/>
1356        </sensor>
1357
1358        <tendon>
1359            <spatial name="tendon1" limited="false" range="0 5" rgba="0 .5 2 3" width=".5">
1360                <site site="ball1"/>
1361                <site site="ball2"/>
1362            </spatial>
1363        </tendon>
1364
1365        <tendon>
1366            <spatial name="tendon2" limited="true" range="0 1" rgba="0 .1 1 1" width=".005">
1367                <site site="ball1"/>
1368                <site site="ball2"/>
1369            </spatial>
1370        </tendon>
1371
1372        <tendon>
1373            <spatial name="tendon3" limited="false" range="0 5" rgba=".5 .2 .4 .3" width=".25">
1374                <site site="ball1"/>
1375                <site site="ball2"/>
1376            </spatial>
1377        </tendon>
1378
1379        <!-- Contact pair between the two geoms -->
1380        <contact>
1381            <pair name="geom_pair" geom1="ball31" geom2="ball32" condim="3" solref="0.02 1"
1382                solreffriction="0.01 0.5" solimp="0.0 0.95 0.001 0.5 2" margin="0.001" gap="0"
1383                friction="1.0 0.8 0.6 0.0 0.0">
1384            </pair>
1385        </contact>
1386
1387        <!-- A keyframe with qpos/qvel/ctrl etc. -->
1388        <keyframe>
1389            <!-- adjust nq/nv/nu in <default> or body definitions to match
1390                lengths in your test constants -->
1391            <key name="pose0"
1392                time="0.0"
1393                qpos="1.1 1.2 1.3 1.1 0.2 0.3 0.1 1.2 0.3 1.1 0.2 1.3 0.1 1.2 0.3 1.1 0.2 0.3 0.1 0.2 0.3 0.1 0.2 0.0"
1394                qvel="0.5 5.0 5.0 0.0 1.0 0.0 0.0 5.0 0.0 5.0 1.0 5.0 0.0 1.0 5.0 0.0 1.0 0.0 0.0 1.0 0.0"
1395                ctrl="0.5 0.5"/>
1396            <key name="pose1"
1397                time="1.5"
1398                qpos="0.1 0.2 0.3 0.1 0.2 0.3 0.1 0.2 0.3 0.1 0.2 0.3 0.1 0.2 0.3 0.1 0.2 0.3 0.1 0.2 0.3 0.1 0.2 0.0"
1399                qvel="0.0 1.0 0.0 0.0 1.0 0.0 0.0 1.0 0.0 0.0 1.0 0.0 0.0 1.0 0.0 0.0 1.0 0.0 0.0 1.0 0.0"
1400                ctrl="0.5 0.0"/>
1401        </keyframe>
1402
1403        <custom>
1404            <tuple name="tuple_example">
1405                <!-- First entry: a body -->
1406                <element objtype="body" objname="ball2" prm="0.5"/>
1407                <!-- Second entry: a site -->
1408                <element objtype="site" objname="ball1" prm="1.0"/>
1409            </tuple>
1410
1411            <!-- Numeric element with a single value -->
1412            <numeric name="gain_factor1" size="5" data="3.14159 0 0 0 3.14159"/>
1413            <numeric name="gain_factor2" size="3" data="1.25 5.5 10.0"/>
1414        </custom>
1415
1416        <!-- Texture definition -->
1417        <asset>
1418            <texture name="wall_tex"
1419                type="2d"
1420                colorspace="sRGB"
1421                width="128"
1422                height="128"
1423                nchannel="3"
1424                builtin="flat"
1425                rgb1="0.6 0.6 0.6"
1426                rgb2="0.6 0.6 0.6"
1427                mark="none"/>
1428
1429            <!-- Material definition -->
1430            <material name="wood_material"
1431                rgba="0.8 0.5 0.3 1"
1432                emission="0.1"
1433                specular="0.5"
1434                shininess="0.7"
1435                reflectance="0.2"
1436                metallic="0.3"
1437                roughness="0.4"
1438                texuniform="true"
1439                texrepeat="2 2"/>
1440
1441            <!-- Material definition -->
1442            <material name="also_wood_material"
1443                rgba="0.8 0.5 0.3 1"
1444                emission="0.1"
1445                specular="0.5"
1446                shininess="0.7"
1447                reflectance="0.2"
1448                metallic="0.3"
1449                roughness="0.5"
1450                texuniform="false"
1451                texrepeat="2 2"/>
1452
1453            <hfield name="hf1" nrow="2" ncol="3" size="1 1 1 0.1"/>
1454            <hfield name="hf2" nrow="5" ncol="3" size="1 1 1 5.25"/>
1455            <hfield name="hf3" nrow="2" ncol="3" size="1 1 1 0.1"/>
1456        </asset>
1457    </mujoco>
1458);
1459
1460    /// Tests if the model can be loaded and then saved.
1461    #[test]
1462    fn test_model_load_save() {
1463        const MODEL_SAVE_XML_PATH: &str = "./__TMP_MODEL1.xml";
1464        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1465        model.save_last_xml(MODEL_SAVE_XML_PATH).expect("could not save the model XML.");      
1466        fs::remove_file(MODEL_SAVE_XML_PATH).unwrap();
1467    }
1468
1469    #[test]
1470    fn test_actuator_model_view() {
1471        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1472        let actuator_model_info = model.actuator("slider").unwrap();
1473        let view = actuator_model_info.view(&model);
1474
1475        /* Test read */
1476        assert_eq!(view.biastype[0], MjtBias::mjBIAS_AFFINE);
1477        assert_eq!(&view.ctrlrange[..], [0.0, 1.0]);
1478        assert_eq!(view.ctrllimited[0], true);
1479        assert_eq!(view.forcelimited[0], false);
1480        assert_eq!(view.trntype[0], MjtTrn::mjTRN_JOINT);
1481        assert_eq!(view.gaintype[0], MjtGain::mjGAIN_FIXED);
1482
1483        /* Test direct array slice correspondance */
1484        assert_eq!(view.dynprm[..], model.actuator_dynprm()[actuator_model_info.id]);
1485
1486        /* Test write */
1487        let mut view_mut = actuator_model_info.view_mut(&mut model);
1488        view_mut.gaintype[0] = MjtGain::mjGAIN_AFFINE;
1489        assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_AFFINE);
1490        view_mut.zero();
1491        assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_FIXED);
1492    }
1493
1494    #[test]
1495    fn test_sensor_model_view() {
1496        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1497        let sensor_model_info = model.sensor("touch").unwrap();
1498        let view = sensor_model_info.view(&model);
1499        
1500        /* Test read */
1501        assert_eq!(view.dim[0], 1);
1502        assert_eq!(view.objtype[0], MjtObj::mjOBJ_SITE);
1503        assert_eq!(view.noise[0], 0.0);
1504        assert_eq!(view.r#type[0], MjtSensor::mjSENS_TOUCH);
1505
1506        /* Test write */
1507        let mut view_mut = sensor_model_info.view_mut(&mut model);
1508        view_mut.noise[0] = 1.0;
1509        assert_eq!(view_mut.noise[0], 1.0);
1510    }
1511
1512    #[test]
1513    fn test_tendon_model_view() {
1514        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1515        let tendon_model_info = model.tendon("tendon2").unwrap();
1516        let view = tendon_model_info.view(&model);
1517        
1518        /* Test read */
1519        assert_eq!(&view.range[..], [0.0, 1.0]);
1520        assert_eq!(view.limited[0], true);
1521        assert_eq!(view.width[0], 0.005);
1522
1523        /* Test alignment with the array slice */
1524        let tendon_id = tendon_model_info.id;
1525        assert_eq!(view.width[0], model.tendon_width()[tendon_id]);
1526        assert_eq!(*view.range, model.tendon_range()[tendon_id]);
1527        assert_eq!(view.limited[0], model.tendon_limited()[tendon_id]);
1528
1529        /* Test write */
1530        let mut view_mut = tendon_model_info.view_mut(&mut model);
1531        view_mut.frictionloss[0] = 5e-2;
1532        assert_eq!(view_mut.frictionloss[0], 5e-2);
1533    }
1534
1535    #[test]
1536    fn test_joint_model_view() {
1537        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1538        let model_info = model.joint("rod").unwrap();
1539        let view = model_info.view(&model);
1540        
1541        /* Test read */
1542        assert_eq!(view.r#type[0], MjtJoint::mjJNT_SLIDE);
1543        assert_eq!(view.limited[0], true);
1544        assert_eq!(&view.axis[..], [0.0, 1.0 , 0.0]);
1545
1546        /* Test write */
1547        let mut view_mut = model_info.view_mut(&mut model);
1548        view_mut.axis.copy_from_slice(&[1.0, 0.0, 0.0]);
1549        assert_eq!(&view_mut.axis[..], [1.0, 0.0 , 0.0]);
1550    }
1551
1552    #[test]
1553    fn test_geom_model_view() {
1554        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1555        let model_info = model.geom("ball2").unwrap();
1556        let view = model_info.view(&model);
1557        
1558        /* Test read */
1559        assert_eq!(view.r#type[0], MjtGeom::mjGEOM_SPHERE);
1560        assert_eq!(view.size[0], 0.5);
1561
1562        /* Test write */
1563        let mut view_mut = model_info.view_mut(&mut model);
1564        view_mut.size[0] = 1.0;
1565        assert_eq!(view_mut.size[0], 1.0);
1566    }
1567
1568    #[test]
1569    fn test_body_model_view() {
1570        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1571        let model_info = model.body("ball2").unwrap();
1572        let view = model_info.view(&model);
1573        
1574        /* Test read */
1575        model.body_pos()[model_info.id];
1576        assert_eq!(view.pos[0], 0.5);
1577
1578        /* Test alignment with slice */
1579        let body_id = model_info.id;
1580        assert_eq!(model.body_sameframe()[body_id], view.sameframe[0]);
1581
1582        /* Test write */
1583        let mut view_mut = model_info.view_mut(&mut model);
1584        view_mut.pos[0] = 1.0;
1585        assert_eq!(view_mut.pos[0], 1.0);
1586    }
1587
1588
1589    #[test]
1590    fn test_camera_model_view() {
1591        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1592        let model_info = model.camera("cam1").unwrap();
1593        let view = model_info.view(&model);
1594
1595        /* Test read */
1596        assert_eq!(&view.resolution[..], [100, 200]);
1597        assert_eq!(view.fovy[0], 50.0);
1598
1599        /* Test write */
1600        let mut view_mut = model_info.view_mut(&mut model);
1601        view_mut.fovy[0] = 60.0;
1602        assert_eq!(view_mut.fovy[0], 60.0);
1603    }
1604
1605    #[test]
1606    fn test_id_2name_valid() {
1607        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1608
1609        // Body with id=1 should exist ("box")
1610        let name = model.id_to_name(MjtObj::mjOBJ_BODY, 1);
1611        assert_eq!(name, Some("ball"));
1612    }
1613
1614    #[test]
1615    fn test_model_prints() {
1616        const TMP_FILE: &str = "tmpprint.txt";
1617        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1618        assert!(model.print(TMP_FILE).is_ok());
1619        fs::remove_file(TMP_FILE).unwrap();
1620
1621        assert!(model.print_formatted(TMP_FILE, "%.2f").is_ok());
1622        fs::remove_file(TMP_FILE).unwrap();
1623    }
1624
1625    #[test]
1626    fn test_id_2name_invalid() {
1627        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1628
1629        // Invalid id should return None
1630        let name = model.id_to_name(MjtObj::mjOBJ_BODY, 9999);
1631        assert_eq!(name, None);
1632    }
1633
1634    #[test]
1635    fn test_totalmass_set_and_get() {
1636        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1637
1638        let mass_before = model.get_totalmass();
1639        model.set_totalmass(5.0);
1640        let mass_after = model.get_totalmass();
1641
1642        assert_relative_eq!(mass_after, 5.0, epsilon = 1e-9);
1643        assert_ne!(mass_before, mass_after);
1644    }
1645
1646    /// Tests if copying the model works without any memory problems.
1647    #[test]
1648    fn test_copy_model() {
1649        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1650        assert!(model.clone().is_some());
1651    }
1652
1653    #[test]
1654    fn test_model_save() {
1655        const MODEL_SAVE_PATH: &str = "./__TMP_MODEL2.mjb";
1656        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1657        model.save(Some(MODEL_SAVE_PATH), None);
1658
1659        let saved_data = fs::read(MODEL_SAVE_PATH).unwrap();
1660        let mut data = vec![0; saved_data.len()];
1661        model.save(None, Some(&mut data));
1662
1663        assert_eq!(saved_data, data);
1664        fs::remove_file(MODEL_SAVE_PATH).unwrap();
1665
1666        /* Test virtual file system load */
1667        assert!(MjModel::from_buffer(&saved_data).is_ok());
1668    }
1669
1670    #[test]
1671    fn test_site_view() {
1672        // <site name="ball22" size="0 0.25 0" pos="5 1 3" rgba="1 2 3 1" type="box"/>
1673        const BODY_NAME: &str = "ball2";
1674        const SITE_NAME: &str = "ball22";
1675        const SITE_SIZE: [f64; 3] = [0.5, 0.25, 0.5];
1676        const SITE_POS: [f64; 3] = [5.0, 1.0, 3.0];
1677        const SITE_RGBA: [f32; 4] = [1.0, 2.0, 3.0, 1.0];
1678        const SITE_TYPE: MjtGeom = MjtGeom::mjGEOM_BOX;
1679
1680        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1681        let info_ball = model.body(BODY_NAME).unwrap();
1682        let info_site = model.site(SITE_NAME).unwrap();
1683        let view_site = info_site.view(&model);
1684
1685        /* Check if all the attributes given match */
1686        assert_eq!(info_site.name, SITE_NAME);
1687        assert_eq!(view_site.size[..], SITE_SIZE);
1688        assert_eq!(view_site.pos[..], SITE_POS);
1689        assert_eq!(view_site.rgba[..], SITE_RGBA);
1690        assert_eq!(view_site.r#type[0], SITE_TYPE);
1691
1692        assert_eq!(view_site.bodyid[0] as usize, info_ball.id)
1693    }
1694
1695    #[test]
1696    fn test_pair_view() {
1697        const PAIR_NAME: &str = "geom_pair";
1698        const DIM: i32 = 3;
1699        const GEOM1_NAME: &str = "ball31";
1700        const GEOM2_NAME: &str = "ball32";
1701        const SOLREF: [f64; mjNREF as usize] = [0.02, 1.0];
1702        const SOLREFFRICTION: [f64; mjNREF as usize] = [0.01, 0.5];
1703        const SOLIMP: [f64; mjNIMP as usize] = [0., 0.95, 0.001, 0.5, 2.0];
1704        const MARGIN: f64 = 0.001;
1705        const GAP: f64 = 0.0;
1706        const FRICTION: [f64; 5] = [1.0, 0.8, 0.6, 0.0, 0.0];
1707
1708        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1709        let info_pair = model.pair(PAIR_NAME).unwrap();
1710        let view_pair = info_pair.view(&model);
1711
1712        let geom1_info = model.geom(GEOM1_NAME).unwrap();
1713        let geom2_info = model.geom(GEOM2_NAME).unwrap();
1714
1715        // signature =  body1 << 16 + body2 according to MuJoCo's documentation.
1716        let signature = ((geom1_info.view(&model).bodyid[0] as u32) << 16) + geom2_info.view(&model).bodyid[0] as u32;
1717
1718        assert_eq!(view_pair.dim[0], DIM);
1719        assert_eq!(view_pair.geom1[0] as usize, geom1_info.id);
1720        assert_eq!(view_pair.geom2[0] as usize, geom2_info.id);
1721        assert_eq!(view_pair.signature[0] as u32, signature);
1722        assert_eq!(view_pair.solref[..], SOLREF);
1723        assert_eq!(view_pair.solreffriction[..], SOLREFFRICTION);
1724        assert_eq!(view_pair.solimp[..], SOLIMP);
1725        assert_eq!(view_pair.margin[0], MARGIN);
1726        assert_eq!(view_pair.gap[0], GAP);
1727        assert_eq!(view_pair.friction[..], FRICTION);
1728    }
1729
1730    #[test]
1731    fn test_key_view() {
1732        const KEY_NAME: &str = "pose1";
1733        const TIME: f64 = 1.5;
1734        const QVEL: &[f64] = &[0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0];
1735        const ACT: &[f64]  = &[];
1736        const CTRL: &[f64] = &[0.5, 0.0];
1737
1738        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1739        let info_key = model.key(KEY_NAME).unwrap();
1740        let view_key = info_key.view(&model);
1741
1742        assert_eq!(view_key.time[0], TIME);
1743        // Don't test qpos, as it does some magic angle conversions, making the tests fail.
1744        // If all the other succeed, assume qpos works too (as its the exact same logic).
1745        assert_eq!(&view_key.qvel[..model.ffi().nv as usize], QVEL);
1746        assert_eq!(&view_key.act[..model.ffi().na as usize], ACT);
1747        assert_eq!(&view_key.ctrl[..model.ffi().nu as usize], CTRL);
1748    }
1749
1750    #[test]
1751    fn test_tuple_view() {
1752        const TUPLE_NAME: &str = "tuple_example";
1753        const SIZE: i32 = 2;
1754        const OBJTYPE: &[MjtObj] = &[MjtObj::mjOBJ_BODY, MjtObj::mjOBJ_SITE];
1755        const OBJPRM: &[f64]  = &[0.5, 1.0];
1756
1757        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1758        let info_tuple = model.tuple(TUPLE_NAME).unwrap();
1759        let view_tuple = info_tuple.view(&model);
1760
1761        let objid = &[
1762            model.body("ball2").unwrap().id as i32,
1763            model.site("ball1").unwrap().id as i32,
1764        ];
1765
1766        assert_eq!(view_tuple.size[0], SIZE);
1767        assert_eq!(&view_tuple.objtype[..SIZE as usize], OBJTYPE);
1768        assert_eq!(&view_tuple.objid[..SIZE as usize], objid);
1769        assert_eq!(&view_tuple.objprm[..SIZE as usize], OBJPRM);
1770    }
1771
1772    #[test]
1773    fn test_texture_view() {
1774        const TEX_NAME: &str = "wall_tex";
1775        const TYPE: MjtTexture = MjtTexture::mjTEXTURE_2D;          // for example, 2 = 2D texture
1776        const COLORSPACE: MjtColorSpace = MjtColorSpace::mjCOLORSPACE_SRGB;    // e.g. RGB
1777        const HEIGHT: i32 = 128;
1778        const WIDTH: i32 = 128;
1779        const NCHANNEL: i32 = 3;
1780
1781        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1782        let info_tex = model.texture(TEX_NAME).unwrap();
1783        let view_tex = info_tex.view(&model);
1784
1785        assert_eq!(view_tex.r#type[0], TYPE);
1786        assert_eq!(view_tex.colorspace[0], COLORSPACE);
1787        assert_eq!(view_tex.height[0], HEIGHT);
1788        assert_eq!(view_tex.width[0], WIDTH);
1789        assert_eq!(view_tex.nchannel[0], NCHANNEL);
1790
1791        assert_eq!(view_tex.data.len(), (WIDTH * HEIGHT * NCHANNEL) as usize);
1792    }
1793
1794    #[test]
1795    fn test_numeric_view() {
1796        const NUMERIC_NAME: &str = "gain_factor2";
1797        const SIZE: i32 = 3;
1798        const DATA: [f64; 3] = [1.25, 5.5, 10.0];
1799
1800        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1801        let info_numeric = model.numeric(NUMERIC_NAME).unwrap();
1802        let view_numeric = info_numeric.view(&model);
1803
1804        assert_eq!(view_numeric.size[0], SIZE);
1805        assert_eq!(view_numeric.data[..SIZE as usize], DATA);
1806    }
1807
1808    #[test]
1809    fn test_material_view() {
1810        const MATERIAL_NAME: &str = "also_wood_material";
1811
1812        const TEXUNIFORM: bool = false;
1813        const TEXREPEAT: [f32; 2] = [2.0, 2.0];
1814        const EMISSION: f32 = 0.1;
1815        const SPECULAR: f32 = 0.5;
1816        const SHININESS: f32 = 0.7;
1817        const REFLECTANCE: f32 = 0.2;
1818        const METALLIC: f32 = 0.3;
1819        const ROUGHNESS: f32 = 0.5;
1820        const RGBA: [f32; 4] = [0.8, 0.5, 0.3, 1.0];
1821        const TEXID: i32 = -1;
1822
1823        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1824        let info_material = model.material(MATERIAL_NAME).unwrap();
1825        let view_material = info_material.view(&model);
1826
1827        assert_eq!(view_material.texuniform[0], TEXUNIFORM);
1828        assert_eq!(view_material.texrepeat[..], TEXREPEAT);
1829        assert_eq!(view_material.emission[0], EMISSION);
1830        assert_eq!(view_material.specular[0], SPECULAR);
1831        assert_eq!(view_material.shininess[0], SHININESS);
1832        assert_eq!(view_material.reflectance[0], REFLECTANCE);
1833        assert_eq!(view_material.metallic[0], METALLIC);
1834        assert_eq!(view_material.roughness[0], ROUGHNESS);
1835        assert_eq!(view_material.rgba[..], RGBA);
1836        assert_eq!(view_material.texid[0], TEXID);
1837    }
1838
1839    #[test]
1840    fn test_light_view() {
1841        const LIGHT_NAME: &str = "lamp_light2";
1842        const MODE: MjtCamLight = MjtCamLight::mjCAMLIGHT_FIXED;
1843        const BODYID: usize = 0;       // lamp body id
1844        const TYPE: MjtLightType = MjtLightType::mjLIGHT_SPOT;           // spot light, adjust if mjLightType differs
1845        const TEXID: i32 = -1;
1846        const CASTSHADOW: bool = true;
1847        const BULBRADIUS: f32 = 0.2;
1848        const INTENSITY: f32 = 500.0;
1849        const RANGE: f32 = 10.0;
1850        const ACTIVE: bool = true;
1851
1852        const POS: [MjtNum; 3] = [0.0, 0.0, 0.0];
1853        const DIR: [MjtNum; 3] = [0.0, 0.0, -1.0];
1854        const POS0: [MjtNum; 3] = [0.0, 0.0, 0.0];
1855        const DIR0: [MjtNum; 3] = [0.0, 0.0, -1.0];
1856        const ATTENUATION: [f32; 3] = [0.1, 0.05, 0.01];
1857        const CUTOFF: f32 = 45.0;
1858        const EXPONENT: f32 = 2.0;
1859        const AMBIENT: [f32; 3] = [0.1, 0.1, 0.1];
1860        const DIFFUSE: [f32; 3] = [1.0, 1.0, 1.0];
1861        const SPECULAR: [f32; 3] = [1.0, 1.0, 1.0];
1862
1863        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1864        let info_light = model.light(LIGHT_NAME).unwrap();
1865        let view_light = info_light.view(&model);
1866
1867        assert_eq!(view_light.mode[0], MODE);
1868        assert_eq!(view_light.bodyid[0] as usize, BODYID);
1869        assert_eq!(view_light.targetbodyid[0], -1);
1870        assert_eq!(view_light.r#type[0], TYPE);
1871        assert_eq!(view_light.texid[0], TEXID);
1872        assert_eq!(view_light.castshadow[0], CASTSHADOW);
1873        assert_eq!(view_light.bulbradius[0], BULBRADIUS);
1874        assert_eq!(view_light.intensity[0], INTENSITY);
1875        assert_eq!(view_light.range[0], RANGE);
1876        assert_eq!(view_light.active[0], ACTIVE);
1877
1878        assert_eq!(view_light.pos[..], POS);
1879        assert_eq!(view_light.dir[..], DIR);
1880        assert_eq!(view_light.pos0[..], POS0);
1881        assert_eq!(view_light.dir0[..], DIR0);
1882        assert_eq!(view_light.attenuation[..], ATTENUATION);
1883        assert_eq!(view_light.cutoff[0], CUTOFF);
1884        assert_eq!(view_light.exponent[0], EXPONENT);
1885        assert_eq!(view_light.ambient[..], AMBIENT);
1886        assert_eq!(view_light.diffuse[..], DIFFUSE);
1887        assert_eq!(view_light.specular[..], SPECULAR);
1888    }
1889
1890    #[test]
1891    fn test_connect_eq_view() {
1892        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1893
1894        // Take the third equality constraint
1895        let info_eq = model.equality("eq3").unwrap();
1896        let view_eq = info_eq.view(&model);
1897
1898        // Check type
1899        assert_eq!(view_eq.r#type[0], MjtEq::mjEQ_CONNECT);
1900
1901        // Check connected bodies
1902        assert_eq!(view_eq.obj1id[0], model.name_to_id(MjtObj::mjOBJ_BODY, "eq_body3"));
1903        assert_eq!(view_eq.obj2id[0], model.name_to_id(MjtObj::mjOBJ_BODY, "eq_body4"));
1904        assert_eq!(view_eq.objtype[0], MjtObj::mjOBJ_BODY);
1905
1906        // Check active
1907        assert_eq!(view_eq.active0[0], true);
1908
1909        // Check anchor position stored in eq_data
1910        let anchor = &view_eq.data[0..3];
1911        assert_eq!(anchor[0], 0.0);
1912        assert_eq!(anchor[1], 5.0);
1913        assert_eq!(anchor[2], 0.0);
1914    }
1915
1916    #[test]
1917    fn test_hfield_view() {
1918        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1919
1920        // Access first height field
1921        let info_hf = model.hfield("hf2").unwrap();
1922        let view_hf = info_hf.view(&model);
1923
1924        // Expected values
1925        let expected_size: [f64; 4] = [1.0, 1.0, 1.0, 5.25]; // radius_x, radius_y, elevation_z, base_z
1926        let expected_nrow = 5;
1927        let expected_ncol = 3;
1928        let expected_data: [f32; 15] = [0.0; 15];
1929
1930        // Assertions
1931        assert_eq!(view_hf.size[..], expected_size);
1932        assert_eq!(view_hf.nrow[0], expected_nrow);
1933        assert_eq!(view_hf.ncol[0], expected_ncol);
1934
1935        // hfield_data length should match nrow * ncol
1936        assert_eq!(view_hf.data.len(), (expected_nrow * expected_ncol) as usize);
1937        assert_eq!(view_hf.data[..], expected_data[..]);
1938
1939        // Pathadr is -1 (no external file)
1940        assert_eq!(view_hf.pathadr[0], -1);
1941    }
1942}