mujoco_rs/wrappers/
mj_model.rs

1//! Module for mjModel
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};
17
18
19/*******************************************/
20// Types
21/// Constants which are powers of 2. They are used as bitmasks for the field ``disableflags`` of `mjOption`.
22/// At runtime this field is ``m->opt.disableflags``. The number of these constants is given by ``mjNDISABLE`` which is
23/// also the length of the global string array `mjDISABLESTRING` with text descriptions of these flags.
24pub type MjtDisableBit = mjtDisableBit;
25
26/// Constants which are powers of 2. They are used as bitmasks for the field ``enableflags`` of `mjOption`.
27/// At runtime this field is ``m->opt.enableflags``. The number of these constants is given by ``mjNENABLE`` which is also
28/// the length of the global string array `mjENABLESTRING` with text descriptions of these flags.
29pub type MjtEnableBit = mjtEnableBit;
30
31/// Primitive joint types. These values are used in ``m->jnt_type``. The numbers in the comments indicate how many
32/// positional coordinates each joint type has. Note that ball joints and rotational components of free joints are
33/// represented as unit quaternions - which have 4 positional coordinates but 3 degrees of freedom each.
34pub type MjtJoint = mjtJoint;
35
36/// Geometric types supported by MuJoCo. The first group are "official" geom types that can be used in the model. The
37/// second group are geom types that cannot be used in the model but are used by the visualizer to add decorative
38/// elements. These values are used in ``m->geom_type`` and ``m->site_type``.
39pub type MjtGeom = mjtGeom;
40
41/// Dynamic modes for cameras and lights, specifying how the camera/light position and orientation are computed. These
42/// values are used in ``m->cam_mode`` and ``m->light_mode``.
43pub type MjtCamLight = mjtCamLight;
44
45/// The type of a light source describing how its position, orientation and other properties will interact with the
46/// objects in the scene. These values are used in ``m->light_type``.
47pub type MjtLightType = mjtLightType;
48
49/// Texture types, specifying how the texture will be mapped. These values are used in ``m->tex_type``.
50pub type MjtTexture = mjtTexture;
51
52/// Texture roles, specifying how the renderer should interpret the texture.  Note that the MuJoCo built-in renderer only
53/// uses RGB textures.  These values are used to store the texture index in the material's array ``m->mat_texid``.
54pub type MjtTextureRole = mjtTextureRole;
55
56/// Type of color space encoding for textures.
57pub type MjtColorSpace = mjtColorSpace;
58
59/// Numerical integrator types. These values are used in ``m->opt.integrator``.
60pub type MjtIntegrator = mjtIntegrator;
61
62/// Available friction cone types. These values are used in ``m->opt.cone``.
63pub type MjtCone = mjtCone;
64
65/// Available Jacobian types. These values are used in ``m->opt.jacobian``.
66pub type MjtJacobian = mjtJacobian;
67
68/// Available constraint solver algorithms. These values are used in ``m->opt.solver``.
69pub type MjtSolver = mjtSolver;
70
71/// Equality constraint types. These values are used in ``m->eq_type``.
72pub type MjtEq = mjtEq;
73
74/// Tendon wrapping object types. These values are used in ``m->wrap_type``.
75pub type MjtWrap = mjtWrap;
76
77/// Actuator transmission types. These values are used in ``m->actuator_trntype``.
78pub type MjtTrn = mjtTrn;
79
80/// Actuator dynamics types. These values are used in ``m->actuator_dyntype``.
81pub type MjtDyn = mjtDyn;
82
83/// Actuator gain types. These values are used in ``m->actuator_gaintype``.
84pub type MjtGain = mjtGain;
85
86/// Actuator bias types. These values are used in ``m->actuator_biastype``.
87pub type MjtBias = mjtBias;
88
89/// MuJoCo object types. These are used, for example, in the support functions `mj_name2id` and
90/// `mj_id2name` to convert between object names and integer ids.
91pub type MjtObj = mjtObj;
92
93/// Sensor types. These values are used in ``m->sensor_type``.
94pub type MjtSensor = mjtSensor;
95
96/// These are the compute stages for the skipstage parameters of `mj_forwardSkip` and
97/// `mj_inverseSkip`.
98pub type MjtStage = mjtStage;
99
100/// These are the possible sensor data types, used in ``mjData.sensor_datatype``.
101pub type MjtDataType = mjtDataType;
102
103/// Types of data fields returned by contact sensors.
104pub type MjtConDataField = mjtConDataField;
105
106/// Types of frame alignment of elements with their parent bodies. Used as shortcuts during `mj_kinematics` in the
107/// last argument to `mj_local2global`.
108pub type MjtSameFrame = mjtSameFrame;
109
110/// Types of flex self-collisions midphase.
111pub type MjtFlexSelf = mjtFlexSelf;
112
113/// Formulas used to combine SDFs when calling mjc_distance and mjc_gradient.
114pub type MjtSDFType = mjtSDFType;
115
116/*******************************************/
117
118/// A Rust-safe wrapper around mjModel.
119/// Automatically clean after itself on destruction.
120#[derive(Debug)]
121pub struct MjModel(*mut mjModel);
122
123// Allow usage in threaded contexts as the data won't be shared anywhere outside Rust,
124// except in the C++ code.
125unsafe impl Send for MjModel {}
126unsafe impl Sync for MjModel {}
127
128
129impl MjModel {
130    /// Loads the model from an XML file. To load from a virtual file system, use [`MjModel::from_xml_vfs`].
131    pub fn from_xml<T: AsRef<Path>>(path: T) -> Result<Self, Error> {
132        Self::from_xml_file(path, None)
133    }
134
135    /// Loads the model from an XML file, located in a virtual file system (`vfs`).
136    pub fn from_xml_vfs<T: AsRef<Path>>(path: T, vfs: &MjVfs) -> Result<Self, Error> {
137        Self::from_xml_file(path, Some(vfs))
138    }
139
140    fn from_xml_file<T: AsRef<Path>>(path: T, vfs: Option<&MjVfs>) -> Result<Self, Error> {
141        let mut error_buffer = [0i8; 100];
142        unsafe {
143            let path = CString::new(path.as_ref().to_str().expect("invalid utf")).unwrap();
144            let raw_ptr = mj_loadXML(
145                path.as_ptr(), vfs.map_or(ptr::null(), |v| v.ffi()),
146                &mut error_buffer as *mut i8, error_buffer.len() as c_int
147            );
148
149            Self::check_raw_model(raw_ptr, &error_buffer)
150        }
151    }
152
153    /// Loads the model from an XML string.
154    pub fn from_xml_string(data: &str) -> Result<Self, Error> {
155        let mut vfs = MjVfs::new();
156        let filename = "model.xml";
157
158        // Add the file into a virtual file system
159        vfs.add_from_buffer(filename, data.as_bytes())?;
160
161        let mut error_buffer = [0i8; 100];
162        unsafe {
163            let filename_c = CString::new(filename).unwrap();
164            let raw_ptr = mj_loadXML(
165                filename_c.as_ptr(), vfs.ffi(),
166                &mut error_buffer as *mut i8, error_buffer.len() as c_int
167            );
168
169            Self::check_raw_model(raw_ptr, &error_buffer)
170        }
171    }
172
173    /// Loads the model from MJB raw data.
174    pub fn from_buffer(data: &[u8]) -> Result<Self, Error> {
175        unsafe {
176            // Create a virtual FS since we don't have direct access to the load buffer function (or at least it isn't officially exposed).
177            // let raw_ptr = mj_loadModelBuffer(data.as_ptr() as *const c_void, data.len() as i32);
178            let mut vfs = MjVfs::new();
179            let filename = "model.mjb";
180
181            // Add the file into a virtual file system
182            vfs.add_from_buffer(filename, data)?;
183
184            // Load the model from the virtual file system
185            let filename_c = CString::new(filename).unwrap();
186            let raw_model = mj_loadModel(filename_c.as_ptr(), vfs.ffi());
187            Self::check_raw_model(raw_model, &[0])
188        }
189    }
190
191    /// Creates a [`MjModel`] from a raw pointer.
192    pub(crate) fn from_raw(ptr: *mut mjModel) -> Result<Self, Error> {
193        unsafe { Self::check_raw_model(ptr, &[0]) }
194    }
195
196    /// Saves the last XML loaded.
197    pub fn save_last_xml(&self, filename: &str) -> io::Result<()> {
198        let mut error = [0i8; 100];
199        unsafe {
200            let cstring = CString::new(filename)?;
201            match mj_saveLastXML(
202                cstring.as_ptr(), self.ffi(),
203                error.as_mut_ptr(), (error.len() - 1) as i32
204            ) {
205                1 => Ok(()),
206                0 => {
207                    let cstr_error = String::from_utf8_lossy(
208                        // Reinterpret as u8 data. This does not affect the data as it is ASCII
209                        // encoded and thus negative values aren't possible.
210                        std::slice::from_raw_parts(error.as_ptr() as *const u8, error.len())
211                    );
212                    Err(Error::new(ErrorKind::Other, cstr_error))
213                },
214                _ => unreachable!()
215            }
216        }
217    }
218
219    /// Creates a new [`MjData`] instances linked to this model.
220    pub fn make_data<'m>(&'m self) -> MjData<'m> {
221        MjData::new(self)
222    }
223
224    /// Handles the pointer to the model.
225    /// # Safety
226    /// `error_buffer` must have at least on element, where the last element must be 0.
227    unsafe fn check_raw_model(ptr_model: *mut mjModel, error_buffer: &[i8]) -> Result<Self, Error> {
228        if ptr_model.is_null() {
229            Err(Error::new(
230                ErrorKind::UnexpectedEof,
231                unsafe { CStr::from_ptr(error_buffer.as_ptr().cast()).to_string_lossy().into_owned() }
232            ))
233        }
234        else {
235            Ok(Self(ptr_model))
236        }
237    }
238
239    info_method! { Model, ffi(), actuator, [
240        trntype: 1, dyntype: 1, gaintype: 1, biastype: 1, trnid: 2, actadr: 1, actnum: 1, group: 1, ctrllimited: 1,
241        forcelimited: 1, actlimited: 1, dynprm: mjNDYN as usize, gainprm: mjNGAIN as usize, biasprm: mjNBIAS as usize, 
242        actearly: 1, ctrlrange: 2, forcerange: 2, actrange: 2, gear: 6, cranklength: 1, acc0: 1, 
243        length0: 1, lengthrange: 2
244    ], [], []}
245
246    info_method! { Model, ffi(), sensor, [
247        r#type: 1, datatype: 1, needstage: 1,
248        objtype: 1, objid: 1, reftype: 1, refid: 1, intprm: mjNSENS as usize,
249        dim: 1, adr: 1, cutoff: 1, noise: 1
250    ], [], []}
251
252
253    info_method! { Model, ffi(), tendon, [
254        adr: 1, num: 1, matid: 1, group: 1, limited: 1,
255        actfrclimited: 1, width: 1, solref_lim: mjNREF as usize,
256        solimp_lim: mjNIMP as usize, solref_fri: mjNREF as usize, solimp_fri: mjNIMP as usize,
257        range: 2, actfrcrange: 2, margin: 1, stiffness: 1,
258        damping: 1, armature: 1, frictionloss: 1, lengthspring: 2,
259        length0: 1, invweight0: 1, rgba: 4
260    ], [], []}
261
262    info_method! { Model, ffi(), joint, [
263        r#type: 1, qposadr: 1, dofadr: 1, bodyid: 1, group: 1,
264        limited: 1, actfrclimited: 1, actgravcomp: 1, solref: mjNREF as usize,
265        solimp: mjNIMP as usize, pos: 3, axis: 3, stiffness: 1,
266        range: 2, actfrcrange: 2, margin: 1
267    ], [], []}
268
269    info_method! { Model, ffi(), geom, [
270        r#type: 1, contype: 1, conaffinity: 1, condim: 1, bodyid: 1, dataid: 1, matid: 1,
271        group: 1, priority: 1, plugin: 1, sameframe: 1, solmix: 1, solref: mjNREF as usize,
272        solimp: mjNIMP as usize,
273        size: 3, aabb: 6, rbound: 1, pos: 3, quat: 4, friction: 3, margin: 1, gap: 1,
274        fluid: mjNFLUID as usize, rgba: 4
275    ], [], []}
276
277    info_method! { Model, ffi(), body, [
278        parentid: 1, rootid: 1, weldid: 1, mocapid: 1,
279        jntnum: 1, jntadr: 1, dofnum: 1, dofadr: 1,
280        treeid: 1, geomnum: 1, geomadr: 1, simple: 1,
281        sameframe: 1, pos: 3, quat: 4, ipos: 3, iquat: 4,
282        mass: 1, subtreemass: 1, inertia: 3, invweight0: 2,
283        gravcomp: 1, margin: 1, plugin: 1,
284        contype: 1, conaffinity: 1, bvhadr: 1, bvhnum: 1
285    ], [], []}
286
287    info_method! { Model, ffi(), camera, [
288        mode: 1, bodyid: 1, targetbodyid: 1, pos: 3, quat: 4,
289        poscom0: 3, pos0: 3, mat0: 9, orthographic: 1, fovy: 1,
290        ipd: 1, resolution: 2, sensorsize: 2, intrinsic: 4
291    ], [], []}
292
293    info_method! { Model, ffi(), key, [
294        time: 1
295    ], [
296        qpos: nq, qvel: nv, act: na, mpos: nmocap * 3, mquat: nmocap * 4,
297        ctrl: nu
298    ], []}
299
300    info_method! { Model, ffi(), tuple, [
301        size: 1
302    ], [], [
303        objtype: ntupledata, objid: ntupledata, objprm: ntupledata
304    ]}
305
306    info_method! { Model, ffi(), texture, [
307        r#type: 1, colorspace: 1, height: 1, width: 1, nchannel: 1, pathadr: 1
308    ], [], [
309        data: ntexdata
310    ]}
311
312    info_method! { Model, ffi(), site, [
313        r#type: 1, bodyid: 1, group: 1, sameframe: 1, size: 3,
314        pos: 3, quat: 4, rgba: 4, matid: 1
315    ], [user: nuser_site], []}
316
317    info_method! { Model, ffi(), pair, [
318        dim: 1, geom1: 1, geom2: 1, signature: 1, solref: mjNREF as usize,
319        solreffriction: mjNREF as usize, solimp: mjNIMP as usize, margin: 1,
320        gap: 1, friction: 5
321    ], [], []}
322
323    info_method! { Model, ffi(), numeric, [
324        size: 1
325    ], [], [data: nnumericdata]}
326
327
328    info_method! { Model, ffi(), material, [
329        texuniform: 1,
330        texrepeat: 2,
331        emission: 1,
332        specular: 1,
333        shininess: 1,
334        reflectance: 1,
335        metallic: 1,
336        roughness: 1,
337        rgba: 4,
338        texid: MjtTextureRole::mjNTEXROLE as usize
339    ], [], [] }
340
341
342    info_method! { Model, ffi(), light, [
343        mode: 1, bodyid: 1, targetbodyid: 1, r#type: 1, texid: 1, castshadow: 1, bulbradius: 1,
344        intensity: 1, range: 1, active: 1, pos: 3, dir: 3, poscom0: 3, pos0: 3, dir0: 3,
345        attenuation: 3, cutoff: 1, exponent: 1, ambient: 3, diffuse: 3, specular: 3
346    ], [], []}
347
348    info_method! { Model, ffi(), equality, [
349        r#type: 1,          // mjtEq enum
350        obj1id: 1,
351        obj2id: 1,
352        objtype: 1,       // mjtObj enum
353        active0: 1,
354        solref: mjNREF as usize,
355        solimp: mjNIMP as usize,
356        data: mjNEQDATA as usize
357    ], [], []}
358
359    info_method! { Model, ffi(), hfield, [
360        size: 4,
361        nrow: 1,
362        ncol: 1,
363        pathadr: 1
364    ], [], [
365        data: nhfielddata
366    ]}
367
368    /// Deprecated alias for [`MjModel::name_to_id`].
369    #[deprecated]
370    pub fn name2id(&self, type_: MjtObj, name: &str) -> i32 {
371        self.name_to_id(type_, name)
372    }
373
374    /// Translates `name` to the correct id. Wrapper around `mj_name2id`.
375    /// # Panics
376    /// When the `name` contains '\0' characters, a panic occurs.
377    pub fn name_to_id(&self, type_: MjtObj, name: &str) -> i32 {
378        let c_string = CString::new(name).unwrap();
379        unsafe {
380            mj_name2id(self.0, type_ as i32, c_string.as_ptr())
381        }
382    }
383
384    /* Partially auto-generated */
385
386    /// Clones the model.
387    pub fn clone(&self) -> Option<MjModel> {
388        let ptr = unsafe { mj_copyModel(ptr::null_mut(), self.ffi()) };
389        if ptr.is_null() {
390            None
391        }
392        else {
393            Some(MjModel(ptr))
394        }
395    }
396
397    /// Save model to binary MJB file or memory buffer; buffer has precedence when given.
398    /// # Panics
399    /// When the `filename` contains '\0' characters, a panic occurs.
400    pub fn save(&self, filename: Option<&str>, buffer: Option<&mut [u8]>) {
401        let c_filename = filename.map(|f| CString::new(f).unwrap());
402        let (buffer_ptr, buffer_len) = if let Some(b) = buffer {
403            (b.as_mut_ptr(), b.len())
404        }
405        else {
406            (ptr::null_mut(), 0)
407        };
408        let c_filename_ptr = c_filename.as_ref().map_or(ptr::null(), |f| f.as_ptr());
409
410        unsafe { mj_saveModel(
411            self.ffi(), c_filename_ptr,
412            buffer_ptr as *mut std::ffi::c_void, buffer_len as i32
413        ) };
414    }
415
416    /// Return size of buffer needed to hold model.
417    pub fn size(&self) -> std::ffi::c_int {
418        unsafe { mj_sizeModel(self.ffi()) }
419    }
420
421    /// Print mjModel to text file, specifying format.
422    /// float_format must be a valid printf-style format string for a single float value.
423    pub fn print_formatted(&self, filename: &str, float_format: &str) -> Result<(), NulError> {
424        let c_filename = CString::new(filename)?;
425        let c_float_format = CString::new(float_format)?;
426        unsafe { mj_printFormattedModel(self.ffi(), c_filename.as_ptr(), c_float_format.as_ptr()) }
427        Ok(())
428    }
429
430    /// Print model to text file.
431    pub fn print(&self, filename: &str) -> Result<(), NulError> {
432        let c_filename = CString::new(filename)?;
433        unsafe { mj_printModel(self.ffi(), c_filename.as_ptr()) }
434        Ok(())
435    }
436
437    /// Return size of state specification. The bits of the integer spec correspond to element fields of [`MjtState`](crate::wrappers::mj_data::MjtState).
438    pub fn state_size(&self, spec: std::ffi::c_uint) -> std::ffi::c_int {
439        unsafe { mj_stateSize(self.ffi(), spec) }
440    }
441
442    /// Determine type of friction cone.
443    pub fn is_pyramidal(&self) -> bool {
444        unsafe { mj_isPyramidal(self.ffi()) == 1 }
445    }
446
447    /// Determine type of constraint Jacobian.
448    pub fn is_sparse(&self) -> bool {
449        unsafe { mj_isSparse(self.ffi()) == 1 }
450    }
451
452    /// Determine type of solver (PGS is dual, CG and Newton are primal).
453    pub fn is_dual(&self) -> bool {
454        unsafe { mj_isDual(self.ffi()) == 1 }
455    }
456
457    /// Get name of object with the specified [`MjtObj`] type and id, returns NULL if name not found.
458    /// Wraps ``mj_id2name``.
459    pub fn id_to_name(&self, type_: MjtObj, id: std::ffi::c_int) -> Option<&str> {
460        let ptr = unsafe { mj_id2name(self.ffi(), type_ as i32, id) };
461        if ptr.is_null() {
462            None
463        }
464        else {
465            let cstr = unsafe { CStr::from_ptr(ptr).to_str().unwrap() };
466            Some(cstr)
467        }
468    }
469
470    /// Sum all body masses.
471    pub fn get_totalmass(&self) -> MjtNum {
472        unsafe { mj_getTotalmass(self.ffi()) }
473    }
474
475    /// Scale body masses and inertias to achieve specified total mass.
476    pub fn set_totalmass(&mut self, newmass: MjtNum) {
477        unsafe { mj_setTotalmass(self.ffi_mut(), newmass) }
478    }
479
480    /* FFI */
481    /// Returns a reference to the wrapped FFI struct.
482    pub fn ffi(&self) -> &mjModel {
483        unsafe { self.0.as_ref().unwrap() }
484    }
485
486    /// Returns a mutable reference to the wrapped FFI struct.
487    pub unsafe fn ffi_mut(&mut self) -> &mut mjModel {
488        unsafe { self.0.as_mut().unwrap() }
489    }
490
491    /// Returns a direct pointer to the underlying model.
492    /// THIS IS NOT TO BE USED.
493    /// It is only meant for the viewer code, which currently still depends
494    /// on mutable pointers to model and data. This will be removed in the future.
495    pub(crate) unsafe fn __raw(&self) -> *mut mjModel {
496        self.0
497    }
498}
499
500
501/// Public attribute methods.
502impl MjModel {
503    /// Compilation signature.
504    pub fn signature(&self) -> u64 {
505        self.ffi().signature
506    }
507
508    /// An immutable reference to physics options.
509    pub fn opt(&self) -> &MjOption {
510        &self.ffi().opt
511    }
512
513    /// A mutable reference to physics options.
514    pub fn opt_mut(&mut self) -> &mut MjOption {
515        // SAFETY: changing options can't break anything in terms of memory or UB.
516        &mut unsafe { self.ffi_mut() }.opt
517    }
518
519    /// An immutable reference to visualization options.
520    pub fn vis(&self) -> &MjVisual {
521        &self.ffi().vis
522    }
523
524    /// A mutable reference to visualization options.
525    pub fn vis_mut(&mut self) -> &mut MjVisual {
526        // SAFETY: changing visualization options can't break anything in terms of memory or UB.
527        &mut unsafe { self.ffi_mut() }.vis
528    }
529
530    /// An immmutable reference to model statistics.
531    pub fn stat(&self) -> &MjStatistic {
532        &self.ffi().stat
533    }
534
535    /// A mutable reference to model statistics.
536    pub fn stat_mut(&mut self) -> &mut MjStatistic {
537        // SAFETY: changing model statistics can't break anything in terms of memory or UB.
538        &mut unsafe { self.ffi_mut() }.stat
539    }
540}
541
542
543impl Drop for MjModel {
544    fn drop(&mut self) {
545        unsafe {
546            mj_deleteModel(self.0);
547        }
548    }
549}
550
551
552/**************************************************************************************************/
553// Actuator view
554/**************************************************************************************************/
555info_with_view!(Model, actuator, actuator_,
556    [
557        trntype: MjtTrn, dyntype: MjtDyn, gaintype: MjtGain, biastype: MjtBias, trnid: i32,
558        actadr: i32, actnum: i32, group: i32, ctrllimited: bool,
559        forcelimited: bool, actlimited: bool, dynprm: MjtNum, gainprm: MjtNum, biasprm: MjtNum,
560        actearly: bool, ctrlrange: MjtNum, forcerange: MjtNum, actrange: MjtNum,
561        gear: MjtNum, cranklength: MjtNum, acc0: MjtNum, length0: MjtNum, lengthrange: MjtNum
562    ], []
563);
564
565
566/**************************************************************************************************/
567// Sensor view
568/**************************************************************************************************/
569info_with_view!(Model, sensor, sensor_,
570    [
571        r#type: MjtSensor, datatype: MjtDataType, needstage: MjtStage,
572        objtype: MjtObj, objid: i32, reftype: MjtObj, refid: i32, intprm: i32,
573        dim: i32, adr: i32, cutoff: MjtNum, noise: MjtNum
574    ], []
575);
576
577
578/**************************************************************************************************/
579// Tendon view
580/**************************************************************************************************/
581info_with_view!(Model, tendon, tendon_,
582    [
583        adr: i32, num: i32, matid: i32, group: i32, limited: bool,
584        actfrclimited: bool, width: MjtNum, solref_lim: MjtNum,
585        solimp_lim: MjtNum, solref_fri: MjtNum, solimp_fri: MjtNum,
586        range: MjtNum, actfrcrange: MjtNum, margin: MjtNum, stiffness: MjtNum,
587        damping: MjtNum, armature: MjtNum, frictionloss: MjtNum, lengthspring: MjtNum,
588        length0: MjtNum, invweight0: MjtNum, rgba: f32
589    ], []
590);
591
592
593/**************************************************************************************************/
594// Joint view
595/**************************************************************************************************/
596info_with_view!(Model, joint, jnt_,
597    [
598        r#type: MjtJoint, qposadr: i32, dofadr: i32, bodyid: i32, group: i32,
599        limited: bool, actfrclimited: bool, actgravcomp: bool, solref: MjtNum,
600        solimp: MjtNum, pos: MjtNum, axis: MjtNum, stiffness: MjtNum,
601        range: MjtNum, actfrcrange: MjtNum, margin: MjtNum
602    ], []
603);
604
605/**************************************************************************************************/
606// Geom view
607/**************************************************************************************************/
608info_with_view!(Model, geom, geom_,
609    [
610        r#type: MjtGeom, contype: i32, conaffinity: i32, condim: i32, bodyid: i32, dataid: i32, matid: i32,
611        group: i32, priority: i32, plugin: i32, sameframe: MjtSameFrame, solmix: MjtNum, solref: MjtNum, solimp: MjtNum,
612        size: MjtNum, aabb: MjtNum, rbound: MjtNum, pos: MjtNum, quat: MjtNum, friction: MjtNum, margin: MjtNum, gap: MjtNum,
613        fluid: MjtNum, rgba: f32
614    ], []
615);
616
617/**************************************************************************************************/
618// Body view
619/**************************************************************************************************/
620info_with_view!(Model, body, body_,
621    [
622        parentid: i32, rootid: i32, weldid: i32, mocapid: i32,
623        jntnum: i32, jntadr: i32, dofnum: i32, dofadr: i32,
624        treeid: i32, geomnum: i32, geomadr: i32, simple: MjtByte,
625        sameframe: MjtSameFrame, pos: MjtNum, quat: MjtNum, ipos: MjtNum, iquat: MjtNum,
626        mass: MjtNum, subtreemass: MjtNum, inertia: MjtNum, invweight0: MjtNum,
627        gravcomp: MjtNum, margin: MjtNum, plugin: i32,
628        contype: i32, conaffinity: i32, bvhadr: i32, bvhnum: i32
629    ], []
630);
631
632
633/**************************************************************************************************/
634// Camera view
635/**************************************************************************************************/
636info_with_view!(Model, camera, cam_,
637    [
638        mode: MjtCamLight, bodyid: i32, targetbodyid: i32, pos: MjtNum, quat: MjtNum,
639        poscom0: MjtNum, pos0: MjtNum, mat0: MjtNum, orthographic: bool, fovy: MjtNum,
640        ipd: MjtNum, resolution: i32, sensorsize: f32, intrinsic: f32
641    ], []
642);
643
644/**************************************************************************************************/
645// KeyFrame view
646/**************************************************************************************************/
647info_with_view!(Model, key, key_,
648    [
649        time: MjtNum, qpos: MjtNum, qvel: MjtNum, act: MjtNum, mpos: MjtNum,
650        mquat: MjtNum, ctrl: MjtNum
651    ], []
652);
653
654/**************************************************************************************************/
655// Tuple view
656/**************************************************************************************************/
657info_with_view!(Model, tuple, tuple_,
658    [
659        size: i32, objtype: MjtObj, objid: i32, objprm: MjtNum
660    ], []
661);
662
663
664/**************************************************************************************************/
665// Texture view
666/**************************************************************************************************/
667info_with_view!(Model, texture, tex_,
668    [
669        r#type: MjtTexture, colorspace: MjtColorSpace, height: i32, width: i32, nchannel: i32,
670        data: MjtByte
671    ], [pathadr: i32]
672);
673
674/**************************************************************************************************/
675// Site view
676/**************************************************************************************************/
677info_with_view!(Model, site, site_,
678    [
679        r#type: MjtGeom, bodyid: i32, group: i32, sameframe: MjtSameFrame, size: MjtNum,
680        pos: MjtNum, quat: MjtNum, user: MjtNum, rgba: f32
681    ], [matid: i32]
682);
683
684/**************************************************************************************************/
685// Pair view
686/**************************************************************************************************/
687info_with_view!(Model, pair, pair_,
688    [
689        dim: i32, geom1: i32, geom2: i32, signature: i32, solref: MjtNum, solreffriction: MjtNum,
690        solimp: MjtNum, margin: MjtNum, gap: MjtNum, friction: MjtNum
691    ], []
692);
693
694
695/**************************************************************************************************/
696// Numeric view
697/**************************************************************************************************/
698info_with_view!(Model, numeric, numeric_,
699    [
700        size: i32, data: MjtNum
701    ], []
702);
703
704/**************************************************************************************************/
705// Material view
706/**************************************************************************************************/
707info_with_view!(Model, material, mat_,
708    [
709        texuniform: bool,
710        texrepeat: f32,
711        emission: f32,
712        specular: f32,
713        shininess: f32,
714        reflectance: f32,
715        metallic: f32,
716        roughness: f32,
717        rgba: f32,
718        texid: i32
719    ], []
720);
721
722/**************************************************************************************************/
723// Light view
724/**************************************************************************************************/
725info_with_view!(Model, light, light_,
726    [
727        mode: MjtCamLight, bodyid: i32, targetbodyid: i32, r#type: MjtLightType, texid: i32, castshadow: bool,
728        bulbradius: f32, intensity: f32, range: f32, active: bool, pos: MjtNum, dir: MjtNum,
729        poscom0: MjtNum, pos0: MjtNum, dir0: MjtNum, attenuation: f32, cutoff: f32, exponent: f32,
730        ambient: f32, diffuse: f32, specular: f32
731    ], []
732);
733
734/**************************************************************************************************/
735// Equality view
736/**************************************************************************************************/
737info_with_view!(Model, equality, eq_,
738    [
739        r#type: MjtEq,
740        obj1id: i32,
741        obj2id: i32,
742        objtype: MjtObj,
743        active0: bool,
744        solref: MjtNum,
745        solimp: MjtNum,
746        data: MjtNum
747    ], []
748);
749
750
751/**************************************************************************************************/
752// Height field view
753/**************************************************************************************************/
754info_with_view!(Model, hfield, hfield_,
755    [
756        size: MjtNum,
757        nrow: i32,
758        ncol: i32,
759        data: f32,
760        pathadr: i32
761    ], []
762);
763
764#[cfg(test)]
765mod tests {
766    use crate::assert_relative_eq;
767
768    use super::*;
769    use std::fs;
770
771    const EXAMPLE_MODEL: &str = stringify!(
772    <mujoco>
773        <worldbody>
774            <light name="lamp_light1"
775                mode="fixed" type="directional" castshadow="false" bulbradius="0.5" intensity="250"
776                range="10" active="true" pos="0 0 0" dir="0 0 -1" attenuation="0.1 0.05 0.01"
777                cutoff="60" exponent="2" ambient="0.1 0.1 0.25" diffuse="0.5 1 1" specular="1 1.5 1"/>
778
779            <light name="lamp_light2"
780                mode="fixed" type="spot" castshadow="true" bulbradius="0.2" intensity="500"
781                range="10" active="true" pos="0 0 0" dir="0 0 -1" attenuation="0.1 0.05 0.01"
782                cutoff="45" exponent="2" ambient="0.1 0.1 0.1" diffuse="1 1 1" specular="1 1 1"/>
783
784            <camera name="cam1" fovy="50" resolution="100 200"/>
785
786            <light ambient="0.2 0.2 0.2"/>
787            <body name="ball">
788                <geom name="green_sphere" pos=".2 .2 .2" size=".1" rgba="0 1 0 1"/>
789                <joint name="ball" type="free" axis="1 1 1"/>
790                <site name="touch" size="1" type="box"/>
791            </body>
792
793            <body name="ball1" pos="-.5 0 0">
794                <geom size=".1" rgba="0 1 0 1" mass="1"/>
795                <joint type="free"/>
796                <site name="ball1" size=".1 .1 .1" pos="0 0 0" rgba="0 1 0 0.2" type="box"/>
797                <site name="ball12" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
798                <site name="ball13" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
799            </body>
800
801            <body name="ball2"  pos=".5 0 0">
802                <geom name="ball2" size=".5" rgba="0 1 1 1" mass="1"/>
803                <joint type="free"/>
804                <site name="ball2" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
805                <site name="ball22" size="0.5 0.25 0.5" pos="5 1 3" rgba="1 2 3 1" type="box"/>
806                <site name="ball23" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
807            </body>
808
809            <geom name="floor" type="plane" size="10 10 1" euler="5 0 0"/>
810
811            <body name="slider">
812                <geom name="rod" type="cylinder" size="1 10 0" euler="90 0 0" pos="0 0 10"/>
813                <joint name="rod" type="slide" axis="0 1 0" range="0 1"/>
814            </body>
815
816            <body name="ball3"  pos="0 0 5">
817                <geom name="ball31" size=".5" rgba="0 1 1 1" mass="1"/>
818                <joint type="slide"/>
819            </body>
820
821            <body name="ball32"  pos="0 0 -5">
822                <geom name="ball32" size=".5" rgba="0 1 1 1" mass="1"/>
823                <joint type="slide"/>
824            </body>
825
826            <body name="eq_body1" pos="0 0 0">
827                <geom size="0.1"/>
828            </body>
829            <body name="eq_body2" pos="1 0 0">
830                <geom size="0.1"/>
831            </body>
832            <body name="eq_body3" pos="0 0 0">
833                <geom size="0.1"/>
834            </body>
835            <body name="eq_body4" pos="1 0 0">
836                <geom size="0.1"/>
837            </body>
838        </worldbody>
839
840        
841        <equality>
842            <connect name="eq1" body1="eq_body1" body2="eq_body2" anchor="15 0 10"/>
843            <connect name="eq2" body1="eq_body2" body2="eq_body1" anchor="-5 0 10"/>
844            <connect name="eq3" body1="eq_body3" body2="eq_body4" anchor="0 5 0"/>
845            <connect name="eq4" body1="eq_body4" body2="eq_body3" anchor="5 5 10"/>
846        </equality>
847
848
849        <actuator>
850            <general name="slider" joint="rod" biastype="affine" ctrlrange="0 1" gaintype="fixed"/>
851        </actuator>
852
853        <sensor>
854            <touch name="touch" site="touch"/>
855        </sensor>
856
857        <tendon>
858            <spatial name="tendon" limited="true" range="0 1" rgba="0 .1 1 1" width=".005">
859            <site site="ball1"/>
860            <site site="ball2"/>
861        </spatial>
862    </tendon>
863
864
865    <!-- Contact pair between the two geoms -->
866    <contact>
867        <pair name="geom_pair" geom1="ball31" geom2="ball32" condim="3" solref="0.02 1"
868            solreffriction="0.01 0.5" solimp="0.0 0.95 0.001 0.5 2" margin="0.001" gap="0"
869            friction="1.0 0.8 0.6 0.0 0.0">
870        </pair>
871    </contact>
872
873      <!-- A keyframe with qpos/qvel/ctrl etc. -->
874    <keyframe>
875        <!-- adjust nq/nv/nu in <default> or body definitions to match
876            lengths in your test constants -->
877        <key name="pose1"
878            time="1.5"
879            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"
880            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"
881            ctrl="0.5"/>
882    </keyframe>
883
884    <custom>
885        <tuple name="tuple_example">
886            <!-- First entry: a body -->
887            <element objtype="body" objname="ball2" prm="0.5"/>
888            <!-- Second entry: a site -->
889            <element objtype="site" objname="ball1" prm="1.0"/>
890        </tuple>
891
892        <!-- Numeric element with a single value -->
893        <numeric name="gain_factor1" size="5" data="3.14159 0 0 0 3.14159"/>
894        <numeric name="gain_factor2" size="3" data="1.25 5.5 10.0"/>
895    </custom>
896
897    <!-- Texture definition -->
898    <asset>
899        <texture name="wall_tex"
900            type="2d"
901            colorspace="sRGB"
902            width="128"
903            height="128"
904            nchannel="3"
905            builtin="flat"
906            rgb1="0.6 0.6 0.6"
907            rgb2="0.6 0.6 0.6"
908            mark="none"/>
909
910        <!-- Material definition -->
911        <material name="wood_material"
912            rgba="0.8 0.5 0.3 1"
913            emission="0.1"
914            specular="0.5"
915            shininess="0.7"
916            reflectance="0.2"
917            metallic="0.3"
918            roughness="0.4"
919            texuniform="true"
920            texrepeat="2 2"/>
921
922        <!-- Material definition -->
923        <material name="also_wood_material"
924            rgba="0.8 0.5 0.3 1"
925            emission="0.1"
926            specular="0.5"
927            shininess="0.7"
928            reflectance="0.2"
929            metallic="0.3"
930            roughness="0.5"
931            texuniform="false"
932            texrepeat="2 2"/>
933
934        <hfield name="hf1" nrow="2" ncol="3" size="1 1 1 0.1"/>
935        <hfield name="hf2" nrow="5" ncol="3" size="1 1 1 5.25"/>
936        <hfield name="hf3" nrow="2" ncol="3" size="1 1 1 0.1"/>
937    </asset>
938    </mujoco>
939);
940
941    /// Tests if the model can be loaded and then saved.
942    #[test]
943    fn test_model_load_save() {
944        const MODEL_SAVE_XML_PATH: &str = "./__TMP_MODEL1.xml";
945        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
946        model.save_last_xml(MODEL_SAVE_XML_PATH).expect("could not save the model XML.");      
947        fs::remove_file(MODEL_SAVE_XML_PATH).unwrap();
948    }
949
950    #[test]
951    fn test_actuator_model_view() {
952        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
953        let actuator_model_info = model.actuator("slider").unwrap();
954        let view = actuator_model_info.view(&model);
955
956        /* Test read */
957        assert_eq!(view.biastype[0], MjtBias::mjBIAS_AFFINE);
958        assert_eq!(&view.ctrlrange[..], [0.0, 1.0]);
959        assert_eq!(view.ctrllimited[0], true);
960        assert_eq!(view.forcelimited[0], false);
961        assert_eq!(view.trntype[0], MjtTrn::mjTRN_JOINT);
962        assert_eq!(view.gaintype[0], MjtGain::mjGAIN_FIXED);
963
964        /* Test write */
965        let mut view_mut = actuator_model_info.view_mut(&mut model);
966        view_mut.gaintype[0] = MjtGain::mjGAIN_AFFINE;
967        assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_AFFINE);
968        view_mut.zero();
969        assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_FIXED);
970    }
971
972    #[test]
973    fn test_sensor_model_view() {
974        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
975        let sensor_model_info = model.sensor("touch").unwrap();
976        let view = sensor_model_info.view(&model);
977        
978        /* Test read */
979        assert_eq!(view.dim[0], 1);
980        assert_eq!(view.objtype[0], MjtObj::mjOBJ_SITE);
981        assert_eq!(view.noise[0], 0.0);
982        assert_eq!(view.r#type[0], MjtSensor::mjSENS_TOUCH);
983
984        /* Test write */
985        let mut view_mut = sensor_model_info.view_mut(&mut model);
986        view_mut.noise[0] = 1.0;
987        assert_eq!(view_mut.noise[0], 1.0);
988    }
989
990    #[test]
991    fn test_tendon_model_view() {
992        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
993        let tendon_model_info = model.tendon("tendon").unwrap();
994        let view = tendon_model_info.view(&model);
995        
996        /* Test read */
997        assert_eq!(&view.range[..], [0.0, 1.0]);
998        assert_eq!(view.limited[0], true);
999        assert_eq!(view.width[0], 0.005);
1000
1001        /* Test write */
1002        let mut view_mut = tendon_model_info.view_mut(&mut model);
1003        view_mut.frictionloss[0] = 5e-2;
1004        assert_eq!(view_mut.frictionloss[0], 5e-2);
1005    }
1006
1007    #[test]
1008    fn test_joint_model_view() {
1009        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1010        let model_info = model.joint("rod").unwrap();
1011        let view = model_info.view(&model);
1012        
1013        /* Test read */
1014        assert_eq!(view.r#type[0], MjtJoint::mjJNT_SLIDE);
1015        assert_eq!(view.limited[0], true);
1016        assert_eq!(&view.axis[..], [0.0, 1.0 , 0.0]);
1017
1018        /* Test write */
1019        let mut view_mut = model_info.view_mut(&mut model);
1020        view_mut.axis.copy_from_slice(&[1.0, 0.0, 0.0]);
1021        assert_eq!(&view_mut.axis[..], [1.0, 0.0 , 0.0]);
1022    }
1023
1024    #[test]
1025    fn test_geom_model_view() {
1026        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1027        let model_info = model.geom("ball2").unwrap();
1028        let view = model_info.view(&model);
1029        
1030        /* Test read */
1031        assert_eq!(view.r#type[0], MjtGeom::mjGEOM_SPHERE);
1032        assert_eq!(view.size[0], 0.5);
1033
1034        /* Test write */
1035        let mut view_mut = model_info.view_mut(&mut model);
1036        view_mut.size[0] = 1.0;
1037        assert_eq!(view_mut.size[0], 1.0);
1038    }
1039
1040    #[test]
1041    fn test_body_model_view() {
1042        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1043        let model_info = model.body("ball2").unwrap();
1044        let view = model_info.view(&model);
1045        
1046        /* Test read */
1047        assert_eq!(view.pos[0], 0.5);
1048
1049        /* Test write */
1050        let mut view_mut = model_info.view_mut(&mut model);
1051        view_mut.pos[0] = 1.0;
1052        assert_eq!(view_mut.pos[0], 1.0);
1053    }
1054
1055
1056    #[test]
1057    fn test_camera_model_view() {
1058        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1059        let model_info = model.camera("cam1").unwrap();
1060        let view = model_info.view(&model);
1061
1062        /* Test read */
1063        assert_eq!(&view.resolution[..], [100, 200]);
1064        assert_eq!(view.fovy[0], 50.0);
1065
1066        /* Test write */
1067        let mut view_mut = model_info.view_mut(&mut model);
1068        view_mut.fovy[0] = 60.0;
1069        assert_eq!(view_mut.fovy[0], 60.0);
1070    }
1071
1072    #[test]
1073    fn test_id_2name_valid() {
1074        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1075
1076        // Body with id=1 should exist ("box")
1077        let name = model.id_to_name(MjtObj::mjOBJ_BODY, 1);
1078        assert_eq!(name, Some("ball"));
1079    }
1080
1081    #[test]
1082    fn test_model_prints() {
1083        const TMP_FILE: &str = "tmpprint.txt";
1084        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1085        assert!(model.print(TMP_FILE).is_ok());
1086        fs::remove_file(TMP_FILE).unwrap();
1087
1088        assert!(model.print_formatted(TMP_FILE, "%.2f").is_ok());
1089        fs::remove_file(TMP_FILE).unwrap();
1090    }
1091
1092    #[test]
1093    fn test_id_2name_invalid() {
1094        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1095
1096        // Invalid id should return None
1097        let name = model.id_to_name(MjtObj::mjOBJ_BODY, 9999);
1098        assert_eq!(name, None);
1099    }
1100
1101    #[test]
1102    fn test_totalmass_set_and_get() {
1103        let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1104
1105        let mass_before = model.get_totalmass();
1106        model.set_totalmass(5.0);
1107        let mass_after = model.get_totalmass();
1108
1109        assert_relative_eq!(mass_after, 5.0, epsilon = 1e-9);
1110        assert_ne!(mass_before, mass_after);
1111    }
1112
1113    /// Tests if copying the model works without any memory problems.
1114    #[test]
1115    fn test_copy_model() {
1116        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1117        assert!(model.clone().is_some());
1118    }
1119
1120    #[test]
1121    fn test_model_save() {
1122        const MODEL_SAVE_PATH: &str = "./__TMP_MODEL2.mjb";
1123        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1124        model.save(Some(MODEL_SAVE_PATH), None);
1125
1126        let saved_data = fs::read(MODEL_SAVE_PATH).unwrap();
1127        let mut data = vec![0; saved_data.len()];
1128        model.save(None, Some(&mut data));
1129
1130        assert_eq!(saved_data, data);
1131        fs::remove_file(MODEL_SAVE_PATH).unwrap();
1132
1133        /* Test virtual file system load */
1134        assert!(MjModel::from_buffer(&saved_data).is_ok());
1135    }
1136
1137    #[test]
1138    fn test_site_view() {
1139        // <site name="ball22" size="0 0.25 0" pos="5 1 3" rgba="1 2 3 1" type="box"/>
1140        const BODY_NAME: &str = "ball2";
1141        const SITE_NAME: &str = "ball22";
1142        const SITE_SIZE: [f64; 3] = [0.5, 0.25, 0.5];
1143        const SITE_POS: [f64; 3] = [5.0, 1.0, 3.0];
1144        const SITE_RGBA: [f32; 4] = [1.0, 2.0, 3.0, 1.0];
1145        const SITE_TYPE: MjtGeom = MjtGeom::mjGEOM_BOX;
1146
1147        let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1148        let info_ball = model.body(BODY_NAME).unwrap();
1149        let info_site = model.site(SITE_NAME).unwrap();
1150        let view_site = info_site.view(&model);
1151
1152        /* Check if all the attributes given match */
1153        assert_eq!(info_site.name, SITE_NAME);
1154        assert_eq!(view_site.size[..], SITE_SIZE);
1155        assert_eq!(view_site.pos[..], SITE_POS);
1156        assert_eq!(view_site.rgba[..], SITE_RGBA);
1157        assert_eq!(view_site.r#type[0], SITE_TYPE);
1158
1159        assert_eq!(view_site.bodyid[0] as usize, info_ball.id)
1160    }
1161
1162    #[test]
1163    fn test_pair_view() {
1164        const PAIR_NAME: &str = "geom_pair";
1165        const DIM: i32 = 3;
1166        const GEOM1_NAME: &str = "ball31";
1167        const GEOM2_NAME: &str = "ball32";
1168        const SOLREF: [f64; mjNREF as usize] = [0.02, 1.0];
1169        const SOLREFFRICTION: [f64; mjNREF as usize] = [0.01, 0.5];
1170        const SOLIMP: [f64; mjNIMP as usize] = [0., 0.95, 0.001, 0.5, 2.0];
1171        const MARGIN: f64 = 0.001;
1172        const GAP: f64 = 0.0;
1173        const FRICTION: [f64; 5] = [1.0, 0.8, 0.6, 0.0, 0.0];
1174
1175        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1176        let info_pair = model.pair(PAIR_NAME).unwrap();
1177        let view_pair = info_pair.view(&model);
1178
1179        let geom1_info = model.geom(GEOM1_NAME).unwrap();
1180        let geom2_info = model.geom(GEOM2_NAME).unwrap();
1181
1182        // signature =  body1 << 16 + body2 according to MuJoCo's documentation.
1183        let signature = ((geom1_info.view(&model).bodyid[0] as u32) << 16) + geom2_info.view(&model).bodyid[0] as u32;
1184
1185        assert_eq!(view_pair.dim[0], DIM);
1186        assert_eq!(view_pair.geom1[0] as usize, geom1_info.id);
1187        assert_eq!(view_pair.geom2[0] as usize, geom2_info.id);
1188        assert_eq!(view_pair.signature[0] as u32, signature);
1189        assert_eq!(view_pair.solref[..], SOLREF);
1190        assert_eq!(view_pair.solreffriction[..], SOLREFFRICTION);
1191        assert_eq!(view_pair.solimp[..], SOLIMP);
1192        assert_eq!(view_pair.margin[0], MARGIN);
1193        assert_eq!(view_pair.gap[0], GAP);
1194        assert_eq!(view_pair.friction[..], FRICTION);
1195    }
1196
1197    #[test]
1198    fn test_key_view() {
1199        const KEY_NAME: &str = "pose1";
1200        const TIME: f64 = 1.5;
1201        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];
1202        const ACT: &[f64]  = &[];
1203        const CTRL: &[f64] = &[0.5];
1204
1205        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1206        let info_key = model.key(KEY_NAME).unwrap();
1207        let view_key = info_key.view(&model);
1208
1209        assert_eq!(view_key.time[0], TIME);
1210        // Don't test qpos, as it does some magic angle conversions, making the tests fail.
1211        // If all the other succeed, assume qpos works too (as its the exact same logic).
1212        assert_eq!(&view_key.qvel[..model.ffi().nv as usize], QVEL);
1213        assert_eq!(&view_key.act[..model.ffi().na as usize], ACT);
1214        assert_eq!(&view_key.ctrl[..model.ffi().nu as usize], CTRL);
1215    }
1216
1217    #[test]
1218    fn test_tuple_view() {
1219        const TUPLE_NAME: &str = "tuple_example";
1220        const SIZE: i32 = 2;
1221        const OBJTYPE: &[MjtObj] = &[MjtObj::mjOBJ_BODY, MjtObj::mjOBJ_SITE];
1222        const OBJPRM: &[f64]  = &[0.5, 1.0];
1223
1224        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1225        let info_tuple = model.tuple(TUPLE_NAME).unwrap();
1226        let view_tuple = info_tuple.view(&model);
1227
1228        let objid = &[
1229            model.body("ball2").unwrap().id as i32,
1230            model.site("ball1").unwrap().id as i32,
1231        ];
1232
1233        assert_eq!(view_tuple.size[0], SIZE);
1234        assert_eq!(&view_tuple.objtype[..SIZE as usize], OBJTYPE);
1235        assert_eq!(&view_tuple.objid[..SIZE as usize], objid);
1236        assert_eq!(&view_tuple.objprm[..SIZE as usize], OBJPRM);
1237    }
1238
1239    #[test]
1240    fn test_texture_view() {
1241        const TEX_NAME: &str = "wall_tex";
1242        const TYPE: MjtTexture = MjtTexture::mjTEXTURE_2D;          // for example, 2 = 2D texture
1243        const COLORSPACE: MjtColorSpace = MjtColorSpace::mjCOLORSPACE_SRGB;    // e.g. RGB
1244        const HEIGHT: i32 = 128;
1245        const WIDTH: i32 = 128;
1246        const NCHANNEL: i32 = 3;
1247
1248        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1249        let info_tex = model.texture(TEX_NAME).unwrap();
1250        let view_tex = info_tex.view(&model);
1251
1252        assert_eq!(view_tex.r#type[0], TYPE);
1253        assert_eq!(view_tex.colorspace[0], COLORSPACE);
1254        assert_eq!(view_tex.height[0], HEIGHT);
1255        assert_eq!(view_tex.width[0], WIDTH);
1256        assert_eq!(view_tex.nchannel[0], NCHANNEL);
1257
1258        assert_eq!(view_tex.data.len(), (WIDTH * HEIGHT * NCHANNEL) as usize);
1259    }
1260
1261    #[test]
1262    fn test_numeric_view() {
1263        const NUMERIC_NAME: &str = "gain_factor2";
1264        const SIZE: i32 = 3;
1265        const DATA: [f64; 3] = [1.25, 5.5, 10.0];
1266
1267        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1268        let info_numeric = model.numeric(NUMERIC_NAME).unwrap();
1269        let view_numeric = info_numeric.view(&model);
1270
1271        assert_eq!(view_numeric.size[0], SIZE);
1272        assert_eq!(view_numeric.data[..SIZE as usize], DATA);
1273    }
1274
1275    #[test]
1276    fn test_material_view() {
1277        const MATERIAL_NAME: &str = "also_wood_material";
1278
1279        const TEXUNIFORM: bool = false;
1280        const TEXREPEAT: [f32; 2] = [2.0, 2.0];
1281        const EMISSION: f32 = 0.1;
1282        const SPECULAR: f32 = 0.5;
1283        const SHININESS: f32 = 0.7;
1284        const REFLECTANCE: f32 = 0.2;
1285        const METALLIC: f32 = 0.3;
1286        const ROUGHNESS: f32 = 0.5;
1287        const RGBA: [f32; 4] = [0.8, 0.5, 0.3, 1.0];
1288        const TEXID: i32 = -1;
1289
1290        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1291        let info_material = model.material(MATERIAL_NAME).unwrap();
1292        let view_material = info_material.view(&model);
1293
1294        assert_eq!(view_material.texuniform[0], TEXUNIFORM);
1295        assert_eq!(view_material.texrepeat[..], TEXREPEAT);
1296        assert_eq!(view_material.emission[0], EMISSION);
1297        assert_eq!(view_material.specular[0], SPECULAR);
1298        assert_eq!(view_material.shininess[0], SHININESS);
1299        assert_eq!(view_material.reflectance[0], REFLECTANCE);
1300        assert_eq!(view_material.metallic[0], METALLIC);
1301        assert_eq!(view_material.roughness[0], ROUGHNESS);
1302        assert_eq!(view_material.rgba[..], RGBA);
1303        assert_eq!(view_material.texid[0], TEXID);
1304    }
1305
1306    #[test]
1307    fn test_light_view() {
1308        const LIGHT_NAME: &str = "lamp_light2";
1309        const MODE: MjtCamLight = MjtCamLight::mjCAMLIGHT_FIXED;
1310        const BODYID: usize = 0;       // lamp body id
1311        const TYPE: MjtLightType = MjtLightType::mjLIGHT_SPOT;           // spot light, adjust if mjLightType differs
1312        const TEXID: i32 = -1;
1313        const CASTSHADOW: bool = true;
1314        const BULBRADIUS: f32 = 0.2;
1315        const INTENSITY: f32 = 500.0;
1316        const RANGE: f32 = 10.0;
1317        const ACTIVE: bool = true;
1318
1319        const POS: [MjtNum; 3] = [0.0, 0.0, 0.0];
1320        const DIR: [MjtNum; 3] = [0.0, 0.0, -1.0];
1321        const POS0: [MjtNum; 3] = [0.0, 0.0, 0.0];
1322        const DIR0: [MjtNum; 3] = [0.0, 0.0, -1.0];
1323        const ATTENUATION: [f32; 3] = [0.1, 0.05, 0.01];
1324        const CUTOFF: f32 = 45.0;
1325        const EXPONENT: f32 = 2.0;
1326        const AMBIENT: [f32; 3] = [0.1, 0.1, 0.1];
1327        const DIFFUSE: [f32; 3] = [1.0, 1.0, 1.0];
1328        const SPECULAR: [f32; 3] = [1.0, 1.0, 1.0];
1329
1330        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1331        let info_light = model.light(LIGHT_NAME).unwrap();
1332        let view_light = info_light.view(&model);
1333
1334        assert_eq!(view_light.mode[0], MODE);
1335        assert_eq!(view_light.bodyid[0] as usize, BODYID);
1336        assert_eq!(view_light.targetbodyid[0], -1);
1337        assert_eq!(view_light.r#type[0], TYPE);
1338        assert_eq!(view_light.texid[0], TEXID);
1339        assert_eq!(view_light.castshadow[0], CASTSHADOW);
1340        assert_eq!(view_light.bulbradius[0], BULBRADIUS);
1341        assert_eq!(view_light.intensity[0], INTENSITY);
1342        assert_eq!(view_light.range[0], RANGE);
1343        assert_eq!(view_light.active[0], ACTIVE);
1344
1345        assert_eq!(view_light.pos[..], POS);
1346        assert_eq!(view_light.dir[..], DIR);
1347        assert_eq!(view_light.pos0[..], POS0);
1348        assert_eq!(view_light.dir0[..], DIR0);
1349        assert_eq!(view_light.attenuation[..], ATTENUATION);
1350        assert_eq!(view_light.cutoff[0], CUTOFF);
1351        assert_eq!(view_light.exponent[0], EXPONENT);
1352        assert_eq!(view_light.ambient[..], AMBIENT);
1353        assert_eq!(view_light.diffuse[..], DIFFUSE);
1354        assert_eq!(view_light.specular[..], SPECULAR);
1355    }
1356
1357    #[test]
1358    fn test_connect_eq_view() {
1359        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1360
1361        // Take the third equality constraint
1362        let info_eq = model.equality("eq3").unwrap();
1363        let view_eq = info_eq.view(&model);
1364
1365        // Check type
1366        assert_eq!(view_eq.r#type[0], MjtEq::mjEQ_CONNECT);
1367
1368        // Check connected bodies
1369        assert_eq!(view_eq.obj1id[0], model.name_to_id(MjtObj::mjOBJ_BODY, "eq_body3"));
1370        assert_eq!(view_eq.obj2id[0], model.name_to_id(MjtObj::mjOBJ_BODY, "eq_body4"));
1371        assert_eq!(view_eq.objtype[0], MjtObj::mjOBJ_BODY);
1372
1373        // Check active
1374        assert_eq!(view_eq.active0[0], true);
1375
1376        // Check anchor position stored in eq_data
1377        let anchor = &view_eq.data[0..3];
1378        assert_eq!(anchor[0], 0.0);
1379        assert_eq!(anchor[1], 5.0);
1380        assert_eq!(anchor[2], 0.0);
1381    }
1382
1383    #[test]
1384    fn test_hfield_view() {
1385        let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
1386
1387        // Access first height field
1388        let info_hf = model.hfield("hf2").unwrap();
1389        let view_hf = info_hf.view(&model);
1390
1391        // Expected values
1392        let expected_size: [f64; 4] = [1.0, 1.0, 1.0, 5.25]; // radius_x, radius_y, elevation_z, base_z
1393        let expected_nrow = 5;
1394        let expected_ncol = 3;
1395        let expected_data: [f32; 15] = [0.0; 15];
1396
1397        // Assertions
1398        assert_eq!(view_hf.size[..], expected_size);
1399        assert_eq!(view_hf.nrow[0], expected_nrow);
1400        assert_eq!(view_hf.ncol[0], expected_ncol);
1401
1402        // hfield_data length should match nrow * ncol
1403        assert_eq!(view_hf.data.len(), (expected_nrow * expected_ncol) as usize);
1404        assert_eq!(view_hf.data[..], expected_data[..]);
1405
1406        // Pathadr is -1 (no external file)
1407        assert_eq!(view_hf.pathadr[0], -1);
1408    }
1409}