1use crate::{
3 view_creator, info_method, info_with_view,
4 array_slice_dyn, getter_setter
5};
6use crate::util::{assert_mujoco_version, ERROR_BUF_LEN};
7use crate::error::{MjDataError, MjModelError};
8use crate::wrappers::mj_option::MjOption;
9use crate::wrappers::mj_data::MjData;
10use crate::mujoco_c::*;
11
12use super::mj_auxiliary::{MjVfs, MjVisual, MjStatistic};
13use super::mj_primitive::*;
14
15use std::ffi::{c_char, CStr, CString, c_int, c_void};
16use std::ptr::{self, NonNull};
17use std::path::Path;
18
19
20pub type MjtDisableBit = mjtDisableBit;
26
27pub type MjtEnableBit = mjtEnableBit;
31
32pub type MjtJoint = mjtJoint;
36
37pub type MjtGeom = mjtGeom;
41
42pub type MjtProjection = mjtProjection;
44
45pub type MjtCamLight = mjtCamLight;
48
49pub type MjtLightType = mjtLightType;
52
53pub type MjtTexture = mjtTexture;
55
56pub type MjtTextureRole = mjtTextureRole;
59
60pub type MjtColorSpace = mjtColorSpace;
62
63pub type MjtLRMode = mjtLRMode;
65
66#[derive(Debug, Clone, Copy, PartialEq, Eq, Hash)]
74#[repr(i32)]
75pub enum MjtCubeFace {
76 Right = 0,
78 Left = 1,
80 Up = 2,
82 Down = 3,
84 Front = 4,
86 Back = 5,
88}
89
90pub type MjtIntegrator = mjtIntegrator;
92
93pub type MjtCone = mjtCone;
95
96pub type MjtJacobian = mjtJacobian;
98
99pub type MjtSolver = mjtSolver;
101
102pub type MjtEq = mjtEq;
104
105pub type MjtWrap = mjtWrap;
107
108pub type MjtTrn = mjtTrn;
110
111pub type MjtDyn = mjtDyn;
113
114pub type MjtGain = mjtGain;
116
117pub type MjtBias = mjtBias;
119
120pub type MjtObj = mjtObj;
123
124pub type MjtSensor = mjtSensor;
126
127pub type MjtStage = mjtStage;
130
131pub type MjtDataType = mjtDataType;
133
134pub type MjtConDataField = mjtConDataField;
136
137pub type MjtSameFrame = mjtSameFrame;
140
141pub type MjtSleepPolicy = mjtSleepPolicy;
144
145pub type MjtFlexSelf = mjtFlexSelf;
147
148pub type MjtSDFType = mjtSDFType;
150
151pub type MjtRayDataField = mjtRayDataField;
153
154pub type MjtCamOutBit = mjtCamOutBit;
156
157unsafe impl bytemuck::Zeroable for mjtTrn_ {}
163unsafe impl bytemuck::Zeroable for mjtDyn_ {}
164unsafe impl bytemuck::Zeroable for mjtGain_ {}
165unsafe impl bytemuck::Zeroable for mjtBias_ {}
166unsafe impl bytemuck::Zeroable for mjtObj_ {}
167unsafe impl bytemuck::Zeroable for mjtSameFrame_ {}
168unsafe impl bytemuck::Zeroable for mjtCamLight_ {}
169unsafe impl bytemuck::Zeroable for mjtProjection_ {}
170unsafe impl bytemuck::Zeroable for mjtEq_ {}
171unsafe impl bytemuck::Zeroable for mjtGeom_ {}
172unsafe impl bytemuck::Zeroable for mjtJoint_ {}
173unsafe impl bytemuck::Zeroable for mjtLightType_ {}
174unsafe impl bytemuck::Zeroable for mjtSensor_ {}
175unsafe impl bytemuck::Zeroable for mjtDataType_ {}
176unsafe impl bytemuck::Zeroable for mjtStage_ {}
177unsafe impl bytemuck::Zeroable for mjtTexture_ {}
178unsafe impl bytemuck::Zeroable for mjtColorSpace_ {}
179
180#[derive(Debug)]
185pub struct MjModel(NonNull<mjModel>);
186
187unsafe impl Send for MjModel {}
190unsafe impl Sync for MjModel {}
191
192
193impl MjModel {
194 pub fn from_xml<T: AsRef<Path>>(path: T) -> Result<Self, MjModelError> {
204 Self::from_xml_file(path, None)
205 }
206
207 pub fn from_xml_vfs<T: AsRef<Path>>(path: T, vfs: &MjVfs) -> Result<Self, MjModelError> {
217 Self::from_xml_file(path, Some(vfs))
218 }
219
220 fn from_xml_file<T: AsRef<Path>>(path: T, vfs: Option<&MjVfs>) -> Result<Self, MjModelError> {
221 assert_mujoco_version();
222
223 let mut error_buffer = [0; ERROR_BUF_LEN];
224 let path_str = path.as_ref().to_str()
225 .ok_or(MjModelError::InvalidUtf8Path)?;
226 let path = CString::new(path_str).unwrap();
227 let raw_ptr = unsafe { mj_loadXML(
228 path.as_ptr(), vfs.map_or(ptr::null(), |v| v.ffi()),
229 error_buffer.as_mut_ptr(), error_buffer.len() as c_int
230 ) };
231
232 Self::check_raw_model(raw_ptr, &error_buffer)
233 }
234
235 pub fn from_xml_string(data: &str) -> Result<Self, MjModelError> {
244 assert_mujoco_version();
245
246 let mut vfs = MjVfs::new();
247 let filename = "model.xml";
248
249 vfs.add_from_buffer(filename, data.as_bytes())?;
251
252 let mut error_buffer = [0; ERROR_BUF_LEN];
253 let filename_c = CString::new(filename).unwrap();
254 let raw_ptr = unsafe { mj_loadXML(
255 filename_c.as_ptr(), vfs.ffi(),
256 error_buffer.as_mut_ptr(), error_buffer.len() as c_int
257 ) };
258
259 Self::check_raw_model(raw_ptr, &error_buffer)
260 }
261
262 pub fn from_buffer(data: &[u8]) -> Result<Self, MjModelError> {
270 assert_mujoco_version();
271 unsafe {
272 Self::from_raw(mj_loadModelBuffer(data.as_ptr() as *const c_void, data.len() as i32))
273 }
274 }
275
276 pub(crate) fn from_raw(ptr: *mut mjModel) -> Result<Self, MjModelError> {
278 Self::check_raw_model(ptr, &[0])
279 }
280
281 pub fn save_last_xml<T: AsRef<Path>>(&self, filename: T) -> Result<(), MjModelError> {
290 let path_str = filename.as_ref().to_str()
291 .ok_or(MjModelError::InvalidUtf8Path)?;
292 let mut error = [0; ERROR_BUF_LEN];
293 let cstring = CString::new(path_str).unwrap();
294 let result = unsafe { mj_saveLastXML(
295 cstring.as_ptr(), self.ffi(),
296 error.as_mut_ptr(), error.len() as i32
297 ) };
298 match result {
299 1 => Ok(()),
300 _ => {
301 let cstr_error = unsafe { CStr::from_ptr(error.as_ptr()) }
305 .to_string_lossy()
306 .into_owned();
307 Err(MjModelError::SaveFailed(cstr_error))
308 },
309 }
310 }
311
312 pub fn make_data(&self) -> MjData<&Self> {
318 MjData::new(self)
319 }
320
321 pub fn try_make_data(&self) -> Result<MjData<&Self>, MjDataError> {
327 MjData::try_new(self)
328 }
329
330 fn check_raw_model(ptr_model: *mut mjModel, error_buffer: &[c_char]) -> Result<Self, MjModelError> {
333 match NonNull::new(ptr_model) {
334 Some(nn) => Ok(Self(nn)),
335 None => {
336 let message = unsafe { CStr::from_ptr(error_buffer.as_ptr()) }
339 .to_string_lossy()
340 .into_owned();
341 Err(MjModelError::LoadFailed(message))
342 }
343 }
344 }
345
346 info_method! { Model, actuator,
347 [trntype: 1, dyntype: 1, gaintype: 1, biastype: 1, trnid: 2, actadr: 1, actnum: 1,
348 group: 1, history: 2, historyadr: 1, delay: 1, ctrllimited: 1, forcelimited: 1, actlimited: 1, dynprm: mjNDYN as usize, gainprm: mjNGAIN as usize, biasprm: mjNBIAS as usize,
349 actearly: 1, ctrlrange: 2, forcerange: 2, actrange: 2, damping: 1,
350 dampingpoly: mjNPOLY as usize, armature: 1, gear: 6, cranklength: 1, acc0: 1, length0: 1,
351 lengthrange: 2, plugin: 1],
352 [user: nuser_actuator],
353 []
354 }
355
356 info_method! { Model, body,
357 [parentid: 1, rootid: 1, weldid: 1, mocapid: 1, jntnum: 1, jntadr: 1,
358 dofnum: 1, dofadr: 1, treeid: 1, geomnum: 1, geomadr: 1, simple: 1,
359 sameframe: 1, pos: 3, quat: 4, ipos: 3, iquat: 4, mass: 1, subtreemass: 1,
360 inertia: 3, invweight0: 2, gravcomp: 1, margin: 1, plugin: 1,
361 contype: 1, conaffinity: 1, bvhadr: 1, bvhnum: 1],
362 [user: nuser_body],
363 []
364 }
365
366 info_method! { Model, camera,
367 [mode: 1, bodyid: 1, targetbodyid: 1,
368 pos: 3, quat: 4, poscom0: 3,
369 pos0: 3, mat0: 9, projection: 1, fovy: 1,
370 ipd: 1, resolution: 2, output: 1, sensorsize: 2, intrinsic: 4],
371 [user: nuser_cam],
372 []
373 }
374
375 info_method! { Model, joint,
376 [r#type: 1, qposadr: 1, dofadr: 1, group: 1,
377 limited: 1, actfrclimited: 1, actgravcomp: 1, solref: mjNREF as usize, solimp: mjNIMP as usize,
378 pos: 3, axis: 3, stiffness: 1, stiffnesspoly: mjNPOLY as usize,
379 range: 2, actfrcrange: 2, margin: 1, bodyid: 1, actuatorid: 1],
380 [user: nuser_jnt],
381 [qpos0: nq, qpos_spring: nq, jntid: nv,
382 dof_bodyid: nv, parentid: nv, dof_treeid: nv, Madr: nv, simplenum: nv, frictionloss: nv,
383 armature: nv, damping: nv, dampingpoly: nv * mjNPOLY as usize, invweight0: nv, M0: nv]
384 }
385
386
387 info_method! { Model, equality,
388 [r#type: 1, obj1id: 1,
389 obj2id: 1, active0: 1,
390 solref: mjNREF as usize, solimp: mjNIMP as usize,
391 data: mjNEQDATA as usize, objtype: 1],
392 [],
393 []
394 }
395
396 info_method! { Model, exclude,
397 [signature: 1],
398 [],
399 []
400 }
401
402 info_method! { Model, geom,
403 [r#type: 1, contype: 1, conaffinity: 1, condim: 1, bodyid: 1, dataid: 1, matid: 1,
404 group: 1, priority: 1, plugin: 1, sameframe: 1, solmix: 1, solref: mjNREF as usize, solimp: mjNIMP as usize, size: 3,
405 aabb: 6, rbound: 1, pos: 3, quat: 4, friction: 3, margin: 1, gap: 1, fluid: mjNFLUID as usize, rgba: 4],
406 [user: nuser_geom],
407 []
408 }
409
410 info_method! { Model, hfield,
411 [size: 4,
412 nrow: 1,
413 ncol: 1,
414 adr: 1,
415 pathadr: 1],
416 [],
417 [data: nhfielddata]
418 }
419
420 info_method! { Model, light,
421 [mode: 1, bodyid: 1, targetbodyid: 1, r#type: 1, texid: 1, castshadow: 1,
422 bulbradius: 1, intensity: 1, range: 1,
423 active: 1, pos: 3, dir: 3, poscom0: 3, pos0: 3,
424 dir0: 3, attenuation: 3, cutoff: 1, exponent: 1, ambient: 3,
425 diffuse: 3, specular: 3],
426 [],
427 []
428 }
429
430 info_method! { Model, material,
431 [texid: MjtTextureRole::mjNTEXROLE as usize, texuniform: 1,
432 texrepeat: 2, emission: 1,
433 specular: 1, shininess: 1,
434 reflectance: 1, rgba: 4, metallic: 1, roughness: 1],
435 [],
436 []
437 }
438
439 info_method! { Model, mesh,
440 [vertadr: 1, vertnum: 1,
441 texcoordadr: 1, faceadr: 1,
442 facenum: 1, graphadr: 1,
443 normaladr: 1, normalnum: 1, texcoordnum: 1,
444 bvhadr: 1, bvhnum: 1, octadr: 1, octnum: 1,
445 pathadr: 1, polynum: 1, polyadr: 1,
446 scale: 3, pos: 3, quat: 4],
447 [],
448 []
449 }
450
451 info_method! { Model, numeric,
452 [adr: 1,
453 size: 1],
454 [],
455 [data: nnumericdata]
456 }
457
458 info_method! { Model, pair,
459 [dim: 1, geom1: 1, geom2: 1,
460 signature: 1, solref: mjNREF as usize, solimp: mjNIMP as usize,
461 margin: 1, gap: 1, friction: 5, solreffriction: mjNREF as usize],
462 [],
463 []
464 }
465
466 info_method! { Model, sensor,
467 [r#type: 1, datatype: 1, needstage: 1,
468 objtype: 1, objid: 1, reftype: 1,
469 refid: 1, intprm: mjNSENS as usize, dim: 1, adr: 1,
470 cutoff: 1, noise: 1, history: 2, historyadr: 1, delay: 1, interval: 2, plugin: 1],
471 [user: nuser_sensor],
472 []
473 }
474
475 info_method! { Model, site,
476 [r#type: 1, bodyid: 1, matid: 1,
477 group: 1, sameframe: 1, size: 3,
478 pos: 3, quat: 4, rgba: 4],
479 [user: nuser_site],
480 []
481 }
482
483 info_method! { Model, skin,
484 [matid: 1, group: 1, rgba: 4, inflate: 1,
485 vertadr: 1, vertnum: 1, texcoordadr: 1,
486 faceadr: 1, facenum: 1, boneadr: 1,
487 bonenum: 1, pathadr: 1],
488 [],
489 []
490 }
491
492 info_method! { Model, tendon,
493 [adr: 1, num: 1, matid: 1, actuatorid: 1, group: 1, treenum: 1, treeid: 2,
494 limited: 1, actfrclimited: 1, width: 1,
495 solref_lim: mjNREF as usize, solimp_lim: mjNIMP as usize, solref_fri: mjNREF as usize, solimp_fri: mjNIMP as usize, range: 2, actfrcrange: 2, margin: 1,
496 stiffness: 1, stiffnesspoly: mjNPOLY as usize, damping: 1, dampingpoly: mjNPOLY as usize, armature: 1,
497 frictionloss: 1, lengthspring: 2, length0: 1, invweight0: 1, J_rownnz: 1, J_rowadr: 1, rgba: 4],
498 [user: nuser_tendon],
499 [J_colind: nJten]
500 }
501
502 info_method! { Model, texture,
503 [r#type: 1, colorspace: 1, height: 1,
504 width: 1, nchannel: 1,
505 adr: 1, pathadr: 1],
506 [],
507 [data: ntexdata]
508 }
509
510 info_method! { Model, tuple,
511 [adr: 1,
512 size: 1],
513 [],
514 [objtype: ntupledata,
515 objid: ntupledata,
516 objprm: ntupledata]
517 }
518
519 info_method! { Model, key,
520 [time: 1],
521 [qpos: nq, qvel: nv,
522 act: na, mpos: nmocap*3,
523 mquat: nmocap*4, ctrl: nu],
524 []
525 }
526
527 pub fn name_to_id(&self, type_: MjtObj, name: &str) -> Option<usize> {
532 let c_string = CString::new(name).unwrap();
533 let id = unsafe {
534 mj_name2id(self.ffi(), type_ as i32, c_string.as_ptr())
535 };
536 if id == -1 { None } else { Some(id as usize) }
537 }
538
539 pub fn try_clone(&self) -> Result<MjModel, MjModelError> {
547 let ptr = unsafe { mj_copyModel(ptr::null_mut(), self.ffi()) };
548 NonNull::new(ptr)
549 .map(MjModel)
550 .ok_or(MjModelError::AllocationFailed)
551 }
552
553 pub fn save_to_file<T: AsRef<Path>>(&self, filename: T) -> Result<(), MjModelError> {
565 let path_str = filename.as_ref().to_str()
566 .ok_or(MjModelError::InvalidUtf8Path)?;
567 let c_filename = CString::new(path_str).unwrap();
568 unsafe { mj_saveModel(
569 self.ffi(), c_filename.as_ptr(),
570 ptr::null_mut(), 0
571 ) };
572 Ok(())
573 }
574
575 pub fn save_to_buffer(&self, buffer: &mut [u8]) -> Result<(), MjModelError> {
581 let needed = self.size();
582 if buffer.len() < needed {
583 return Err(MjModelError::BufferTooSmall {
584 needed,
585 available: buffer.len(),
586 });
587 }
588 unsafe { mj_saveModel(
589 self.ffi(), ptr::null(),
590 buffer.as_mut_ptr() as *mut c_void, buffer.len() as i32
591 ) };
592 Ok(())
593 }
594
595 pub fn size(&self) -> usize {
597 unsafe { mj_sizeModel(self.ffi()) as usize }
598 }
599
600 pub fn print_formatted<T: AsRef<Path>>(&self, filename: T, float_format: &str) -> Result<(), MjModelError> {
612 let path_str = filename.as_ref().to_str()
613 .ok_or(MjModelError::InvalidUtf8Path)?;
614 let c_filename = CString::new(path_str).unwrap();
615 let c_float_format = CString::new(float_format).unwrap();
616 unsafe { mj_printFormattedModel(self.ffi(), c_filename.as_ptr(), c_float_format.as_ptr()) }
617 Ok(())
618 }
619
620 pub fn print<T: AsRef<Path>>(&self, filename: T) -> Result<(), MjModelError> {
631 let path_str = filename.as_ref().to_str()
632 .ok_or(MjModelError::InvalidUtf8Path)?;
633 let c_filename = CString::new(path_str).unwrap();
634 unsafe { mj_printModel(self.ffi(), c_filename.as_ptr()) }
635 Ok(())
636 }
637
638 pub fn state_size(&self, spec: u32) -> usize {
640 unsafe { mj_stateSize(self.ffi(), spec as i32) as usize }
641 }
642
643 pub fn extract_state(&self, src: &[MjtNum], src_spec: u32, dst_spec: u32) -> Box<[MjtNum]> {
653 self.try_extract_state(src, src_spec, dst_spec).unwrap()
654 }
655
656 pub fn try_extract_state(&self, src: &[MjtNum], src_spec: u32, dst_spec: u32) -> Result<Box<[MjtNum]>, MjModelError> {
663 let expected = self.state_size(src_spec);
664 if src.len() != expected {
665 return Err(MjModelError::StateSliceLengthMismatch { expected, got: src.len() });
666 }
667
668 if (dst_spec & src_spec) != dst_spec {
669 return Err(MjModelError::SpecNotSubset);
670 }
671
672 let required_size = self.state_size(dst_spec);
673 let mut dst = Vec::with_capacity(required_size);
674
675 unsafe {
679 mj_extractState(
680 self.ffi(),
681 src.as_ptr(), src_spec as i32,
682 dst.as_mut_ptr(), dst_spec as i32
683 );
684
685 dst.set_len(required_size);
686 Ok(dst.into_boxed_slice())
687 }
688 }
689
690 pub fn extract_state_into(&self, src: &[MjtNum], src_spec: u32, dst: &mut [MjtNum], dst_spec: u32) -> usize {
701 self.try_extract_state_into(src, src_spec, dst, dst_spec).unwrap()
702 }
703
704 pub fn try_extract_state_into(&self, src: &[MjtNum], src_spec: u32, dst: &mut [MjtNum], dst_spec: u32) -> Result<usize, MjModelError> {
712 let expected = self.state_size(src_spec);
713 if src.len() != expected {
714 return Err(MjModelError::StateSliceLengthMismatch { expected, got: src.len() });
715 }
716
717 if (dst_spec & src_spec) != dst_spec {
718 return Err(MjModelError::SpecNotSubset);
719 }
720
721 let required_size = self.state_size(dst_spec);
722 let available_size = dst.len();
723
724 if available_size < required_size {
725 return Err(MjModelError::BufferTooSmall { needed: required_size, available: available_size });
726 }
727
728 unsafe {
729 mj_extractState(
730 self.ffi(),
731 src.as_ptr(), src_spec as i32,
732 dst.as_mut_ptr(), dst_spec as i32
733 );
734 }
735
736 Ok(required_size)
737 }
738
739 pub fn is_pyramidal(&self) -> bool {
741 unsafe { mj_isPyramidal(self.ffi()) == 1 }
742 }
743
744 pub fn is_sparse(&self) -> bool {
746 unsafe { mj_isSparse(self.ffi()) == 1 }
747 }
748
749 pub fn is_dual(&self) -> bool {
751 unsafe { mj_isDual(self.ffi()) == 1 }
752 }
753
754 pub fn id_to_name(&self, type_: MjtObj, id: usize) -> Option<&str> {
760 let ptr = unsafe { mj_id2name(self.ffi(), type_ as i32, id as i32) };
761 if ptr.is_null() {
762 None
763 }
764 else {
765 let cstr = unsafe { CStr::from_ptr(ptr).to_str().unwrap() };
768 Some(cstr)
769 }
770 }
771
772 pub fn totalmass(&self) -> MjtNum {
774 unsafe { mj_getTotalmass(self.ffi()) }
775 }
776
777 pub fn set_totalmass(&mut self, newmass: MjtNum) {
779 unsafe { mj_setTotalmass(self.ffi_mut(), newmass) }
780 }
781
782 pub fn max_contacts(&self, geom1: usize, geom2: usize, has_margin: Option<bool>) -> u32 {
791 self.try_max_contacts(geom1, geom2, has_margin).unwrap()
792 }
793
794 pub fn try_max_contacts(&self, geom1: usize, geom2: usize, has_margin: Option<bool>) -> Result<u32, MjModelError> {
799 let ngeom = self.ngeom() as usize;
800
801 if geom1 >= ngeom {
802 return Err(MjModelError::IndexOutOfBounds { id: geom1, len: ngeom });
803 }
804
805 if geom2 >= ngeom {
806 return Err(MjModelError::IndexOutOfBounds { id: geom2, len: ngeom });
807 }
808
809 Ok(unsafe { mj_maxContact(
810 self.ffi(),
811 geom1 as i32, geom2 as i32,
812 has_margin.map(|m| m as i32).unwrap_or(-1)
814 ) as u32 })
815 }
816
817 pub fn ffi(&self) -> &mjModel {
820 unsafe { self.0.as_ref() }
823 }
824
825 pub unsafe fn ffi_mut(&mut self) -> &mut mjModel {
832 unsafe { self.0.as_mut() }
833 }
834
835 #[cfg(feature = "cpp-viewer")]
838 pub(crate) fn as_raw_ptr(&self) -> *mut mjModel {
839 self.0.as_ptr()
840 }
841}
842
843
844impl MjModel {
846 pub fn signature(&self) -> u64 {
848 self.ffi().signature
849 }
850
851 getter_setter! {get, [
852 [ffi] nq: MjtSize; "number of generalized coordinates = dim(qpos).";
853 [ffi] nv: MjtSize; "number of degrees of freedom = dim(qvel).";
854 [ffi] nu: MjtSize; "number of actuators/controls = dim(ctrl).";
855 [ffi] na: MjtSize; "number of activation states = dim(act).";
856 [ffi] nbody: MjtSize; "number of bodies.";
857 [ffi] nbvh: MjtSize; "number of total bounding volumes in all bodies.";
858 [ffi] nbvhstatic: MjtSize; "number of static bounding volumes (aabb stored in mjModel).";
859 [ffi] nbvhdynamic: MjtSize; "number of dynamic bounding volumes (aabb stored in mjData).";
860 [ffi] noct: MjtSize; "number of total octree cells in all meshes.";
861 [ffi] njnt: MjtSize; "number of joints.";
862 [ffi] ntree: MjtSize; "number of kinematic trees under world body.";
863 [ffi] nM: MjtSize; "number of non-zeros in sparse inertia matrix.";
864 [ffi] nB: MjtSize; "number of non-zeros in sparse body-dof matrix.";
865 [ffi] nC: MjtSize; "number of non-zeros in sparse reduced dof-dof matrix.";
866 [ffi] nD: MjtSize; "number of non-zeros in sparse dof-dof matrix.";
867 [ffi] ngeom: MjtSize; "number of geoms.";
868 [ffi] nsite: MjtSize; "number of sites.";
869 [ffi] ncam: MjtSize; "number of cameras.";
870 [ffi] nlight: MjtSize; "number of lights.";
871 [ffi] nflex: MjtSize; "number of flexes.";
872 [ffi] nflexnode: MjtSize; "number of dofs in all flexes.";
873 [ffi] nflexvert: MjtSize; "number of vertices in all flexes.";
874 [ffi] nflexedge: MjtSize; "number of edges in all flexes.";
875 [ffi] nflexelem: MjtSize; "number of elements in all flexes.";
876 [ffi] nflexelemdata: MjtSize; "number of element vertex ids in all flexes.";
877 [ffi] nflexstiffness: MjtSize; "number of stiffness parameters in all flexes.";
878 [ffi] nflexbending: MjtSize; "number of bending parameters in all flexes";
879 [ffi] nflexelemedge: MjtSize; "number of element edge ids in all flexes.";
880 [ffi] nflexshelldata: MjtSize; "number of shell fragment vertex ids in all flexes.";
881 [ffi] nflexevpair: MjtSize; "number of element-vertex pairs in all flexes.";
882 [ffi] nflextexcoord: MjtSize; "number of vertices with texture coordinates.";
883 [ffi] nJfe: MjtSize; "number of non-zeros in sparse flexedge Jacobian matrix.";
884 [ffi] nJfv: MjtSize; "number of non-zeros in sparse flexvert Jacobian matrix.";
885 [ffi] nmesh: MjtSize; "number of meshes.";
886 [ffi] nmeshvert: MjtSize; "number of vertices in all meshes.";
887 [ffi] nmeshnormal: MjtSize; "number of normals in all meshes.";
888 [ffi] nmeshtexcoord: MjtSize; "number of texcoords in all meshes.";
889 [ffi] nmeshface: MjtSize; "number of triangular faces in all meshes.";
890 [ffi] nmeshgraph: MjtSize; "number of ints in mesh auxiliary data.";
891 [ffi] nmeshpoly: MjtSize; "number of polygons in all meshes.";
892 [ffi] nmeshpolyvert: MjtSize; "number of vertices in all polygons.";
893 [ffi] nmeshpolymap: MjtSize; "number of polygons in vertex map.";
894 [ffi] nskin: MjtSize; "number of skins.";
895 [ffi] nskinvert: MjtSize; "number of vertices in all skins.";
896 [ffi] nskintexvert: MjtSize; "number of vertices with texcoords in all skins.";
897 [ffi] nskinface: MjtSize; "number of triangular faces in all skins.";
898 [ffi] nskinbone: MjtSize; "number of bones in all skins.";
899 [ffi] nskinbonevert: MjtSize; "number of vertices in all skin bones.";
900 [ffi] nhfield: MjtSize; "number of heightfields.";
901 [ffi] nhfielddata: MjtSize; "number of data points in all heightfields.";
902 [ffi] ntex: MjtSize; "number of textures.";
903 [ffi] ntexdata: MjtSize; "number of bytes in texture rgb data.";
904 [ffi] nmat: MjtSize; "number of materials.";
905 [ffi] npair: MjtSize; "number of predefined geom pairs.";
906 [ffi] nexclude: MjtSize; "number of excluded geom pairs.";
907 [ffi] neq: MjtSize; "number of equality constraints.";
908 [ffi] ntendon: MjtSize; "number of tendons.";
909 [ffi] nJten: MjtSize; "number of non-zeros in sparse tendon Jacobian matrix.";
910 [ffi] nwrap: MjtSize; "number of wrap objects in all tendon paths.";
911 [ffi] nsensor: MjtSize; "number of sensors.";
912 [ffi] nnumeric: MjtSize; "number of numeric custom fields.";
913 [ffi] nnumericdata: MjtSize; "number of mjtNums in all numeric fields.";
914 [ffi] ntext: MjtSize; "number of text custom fields.";
915 [ffi] ntextdata: MjtSize; "number of mjtBytes in all text fields.";
916 [ffi] ntuple: MjtSize; "number of tuple custom fields.";
917 [ffi] ntupledata: MjtSize; "number of objects in all tuple fields.";
918 [ffi] nkey: MjtSize; "number of keyframes.";
919 [ffi] nmocap: MjtSize; "number of mocap bodies.";
920 [ffi] nplugin: MjtSize; "number of plugin instances.";
921 [ffi] npluginattr: MjtSize; "number of chars in all plugin config attributes.";
922 [ffi] nuser_body: MjtSize; "number of mjtNums in body_user.";
923 [ffi] nuser_jnt: MjtSize; "number of mjtNums in jnt_user.";
924 [ffi] nuser_geom: MjtSize; "number of mjtNums in geom_user.";
925 [ffi] nuser_site: MjtSize; "number of mjtNums in site_user.";
926 [ffi] nuser_cam: MjtSize; "number of mjtNums in cam_user.";
927 [ffi] nuser_tendon: MjtSize; "number of mjtNums in tendon_user.";
928 [ffi] nuser_actuator: MjtSize; "number of mjtNums in actuator_user.";
929 [ffi] nuser_sensor: MjtSize; "number of mjtNums in sensor_user.";
930 [ffi] nnames: MjtSize; "number of chars in all names.";
931 [ffi] npaths: MjtSize; "number of chars in all paths.";
932 [ffi] nnames_map: MjtSize; "number of slots in the names hash map.";
933 [ffi] nJmom: MjtSize; "number of non-zeros in sparse actuator_moment matrix.";
934 [ffi] ngravcomp: MjtSize; "number of bodies with nonzero gravcomp.";
935 [ffi] nemax: MjtSize; "number of potential equality-constraint rows.";
936 [ffi] njmax: MjtSize; "number of available rows in constraint Jacobian (legacy).";
937 [ffi] nconmax: MjtSize; "number of potential contacts in contact list (legacy).";
938 [ffi] nuserdata: MjtSize; "number of mjtNums reserved for the user.";
939 [ffi] nsensordata: MjtSize; "number of mjtNums in sensor data vector.";
940 [ffi] npluginstate: MjtSize; "number of mjtNums in plugin state vector.";
941 [ffi] nhistory: MjtSize; "number of mjtNums in history buffer.";
942 [ffi] narena: MjtSize; "number of bytes in the mjData arena (inclusive of stack).";
943 [ffi] nbuffer: MjtSize; "number of bytes in buffer.";
944 ]}
945
946 getter_setter! {get, [
947 [ffi, ffi_mut] opt: &MjOption; "physics options.";
948 [ffi, ffi_mut] vis: &MjVisual; "visualization options.";
949 [ffi, ffi_mut] stat: &MjStatistic; "model statistics.";
950 ]}
951}
952
953impl MjModel {
955 array_slice_dyn! {
956 qpos0: &[MjtNum; "qpos values at default pose"; ffi().nq],
957 qpos_spring: &[MjtNum; "reference pose for springs"; ffi().nq],
958 (mut = unsafe) body_parentid: &[i32; "id of body's parent"; ffi().nbody],
959 (mut = unsafe) body_rootid: &[i32; "ancestor that is direct child of world"; ffi().nbody],
960 (mut = unsafe) body_weldid: &[i32; "top ancestor with no dofs to this body"; ffi().nbody],
961 (mut = unsafe) body_mocapid: &[i32; "id of mocap data; -1: none"; ffi().nbody],
962 (mut = unsafe) body_jntnum: &[i32; "number of joints for this body"; ffi().nbody],
963 (mut = unsafe) body_jntadr: &[i32; "start addr of joints; -1: no joints"; ffi().nbody],
964 (mut = unsafe) body_dofnum: &[i32; "number of motion degrees of freedom"; ffi().nbody],
965 (mut = unsafe) body_dofadr: &[i32; "start addr of dofs; -1: no dofs"; ffi().nbody],
966 (mut = unsafe) body_treeid: &[i32; "id of body's kinematic tree; -1: static"; ffi().nbody],
967 (mut = unsafe) body_geomnum: &[i32; "number of geoms"; ffi().nbody],
968 (mut = unsafe) body_geomadr: &[i32; "start addr of geoms; -1: no geoms"; ffi().nbody],
969 body_simple: &[MjtByte; "1: diag M; 2: diag M, sliders only"; ffi().nbody],
970 body_sameframe: &[MjtSameFrame [force]; "same frame as inertia"; ffi().nbody],
971 body_pos: &[[MjtNum; 3] [force]; "position offset rel. to parent body"; ffi().nbody],
972 body_quat: &[[MjtNum; 4] [force]; "orientation offset rel. to parent body"; ffi().nbody],
973 body_ipos: &[[MjtNum; 3] [force]; "local position of center of mass"; ffi().nbody],
974 body_iquat: &[[MjtNum; 4] [force]; "local orientation of inertia ellipsoid"; ffi().nbody],
975 body_mass: &[MjtNum; "mass"; ffi().nbody],
976 body_subtreemass: &[MjtNum; "mass of subtree starting at this body"; ffi().nbody],
977 body_inertia: &[[MjtNum; 3] [force]; "diagonal inertia in ipos/iquat frame"; ffi().nbody],
978 body_invweight0: &[[MjtNum; 2] [force]; "mean inv inert in qpos0 (trn, rot)"; ffi().nbody],
979 body_gravcomp: &[MjtNum; "antigravity force, units of body weight"; ffi().nbody],
980 body_margin: &[MjtNum; "MAX over all geom margins"; ffi().nbody],
981 (mut = unsafe) body_plugin: &[i32; "plugin instance id; -1: not in use"; ffi().nbody],
982 body_contype: &[i32; "OR over all geom contypes"; ffi().nbody],
983 body_conaffinity: &[i32; "OR over all geom conaffinities"; ffi().nbody],
984 (mut = unsafe) body_bvhadr: &[i32; "address of bvh root"; ffi().nbody],
985 (mut = unsafe) body_bvhnum: &[i32; "number of bounding volumes"; ffi().nbody],
986 bvh_depth: &[i32; "depth in the bounding volume hierarchy"; ffi().nbvh],
987 (mut = unsafe) bvh_child: &[[i32; 2] [force]; "left and right children in tree"; ffi().nbvh],
988 (mut = unsafe) bvh_nodeid: &[i32; "geom or elem id of node; -1: non-leaf"; ffi().nbvh],
989 bvh_aabb: &[[MjtNum; 6] [force]; "local bounding box (center, size)"; ffi().nbvhstatic],
990 oct_depth: &[i32; "depth in the octree"; ffi().noct],
991 (mut = unsafe) oct_child: &[[i32; 8] [force]; "children of octree node"; ffi().noct],
992 oct_aabb: &[[MjtNum; 6] [force]; "octree node bounding box (center, size)"; ffi().noct],
993 oct_coeff: &[[MjtNum; 8] [force]; "octree interpolation coefficients"; ffi().noct],
994 (mut = unsafe) jnt_type: &[MjtJoint [force]; "type of joint"; ffi().njnt],
995 (mut = unsafe) jnt_qposadr: &[i32; "start addr in 'qpos' for joint's data"; ffi().njnt],
996 (mut = unsafe) jnt_dofadr: &[i32; "start addr in 'qvel' for joint's data"; ffi().njnt],
997 (mut = unsafe) jnt_bodyid: &[i32; "id of joint's body"; ffi().njnt],
998 (mut = unsafe) jnt_actuatorid: &[i32; "actuator contributing damping / armature"; ffi().njnt],
999 jnt_group: &[i32; "group for visibility"; ffi().njnt],
1000 jnt_limited: &[MjtBool; "does joint have limits"; ffi().njnt],
1001 jnt_actfrclimited: &[MjtBool; "does joint have actuator force limits"; ffi().njnt],
1002 jnt_actgravcomp: &[MjtBool; "is gravcomp force applied via actuators"; ffi().njnt],
1003 jnt_solref: &[[MjtNum; mjNREF as usize] [force]; "constraint solver reference: limit"; ffi().njnt],
1004 jnt_solimp: &[[MjtNum; mjNIMP as usize] [force]; "constraint solver impedance: limit"; ffi().njnt],
1005 jnt_pos: &[[MjtNum; 3] [force]; "local anchor position"; ffi().njnt],
1006 jnt_axis: &[[MjtNum; 3] [force]; "local joint axis"; ffi().njnt],
1007 jnt_stiffness: &[MjtNum; "stiffness coefficient"; ffi().njnt],
1008 jnt_stiffnesspoly: &[[MjtNum; mjNPOLY as usize] [force]; "high-order stiffness coefficients"; ffi().njnt],
1009 jnt_range: &[[MjtNum; 2] [force]; "joint limits"; ffi().njnt],
1010 jnt_actfrcrange: &[[MjtNum; 2] [force]; "range of total actuator force"; ffi().njnt],
1011 jnt_margin: &[MjtNum; "min distance for limit detection"; ffi().njnt],
1012 (mut = unsafe) dof_bodyid: &[i32; "id of dof's body"; ffi().nv],
1013 (mut = unsafe) dof_jntid: &[i32; "id of dof's joint"; ffi().nv],
1014 (mut = unsafe) dof_parentid: &[i32; "id of dof's parent; -1: none"; ffi().nv],
1015 (mut = unsafe) dof_treeid: &[i32; "id of dof's kinematic tree"; ffi().nv],
1016 (mut = unsafe) dof_Madr: &[i32; "dof address in M-diagonal"; ffi().nv],
1017 dof_simplenum: &[i32; "number of consecutive simple dofs"; ffi().nv],
1018 dof_solref: &[[MjtNum; mjNREF as usize] [force]; "constraint solver reference:frictionloss"; ffi().nv],
1019 dof_solimp: &[[MjtNum; mjNIMP as usize] [force]; "constraint solver impedance:frictionloss"; ffi().nv],
1020 dof_frictionloss: &[MjtNum; "dof friction loss"; ffi().nv],
1021 dof_armature: &[MjtNum; "dof armature inertia/mass"; ffi().nv],
1022 dof_damping: &[MjtNum; "damping coefficient"; ffi().nv],
1023 dof_dampingpoly: &[[MjtNum; mjNPOLY as usize] [force]; "high-order damping coefficients"; ffi().nv],
1024 dof_invweight0: &[MjtNum; "diag. inverse inertia in qpos0"; ffi().nv],
1025 dof_M0: &[MjtNum; "diag. inertia in qpos0"; ffi().nv],
1026 dof_length: &[MjtNum; "linear: 1; angular: approx. length scale"; ffi().nv],
1027 (mut = unsafe) tree_bodyadr: &[i32; "start addr of bodies"; ffi().ntree],
1028 (mut = unsafe) tree_bodynum: &[i32; "number of bodies in tree"; ffi().ntree],
1029 (mut = unsafe) tree_dofadr: &[i32; "start addr of dofs"; ffi().ntree],
1030 (mut = unsafe) tree_dofnum: &[i32; "number of dofs in tree"; ffi().ntree],
1031 tree_sleep_policy: &[MjtSleepPolicy [force]; "sleep policy"; ffi().ntree],
1032 (mut = unsafe) geom_type: &[MjtGeom [force]; "geometric type"; ffi().ngeom],
1033 geom_contype: &[i32; "geom contact type"; ffi().ngeom],
1034 geom_conaffinity: &[i32; "geom contact affinity"; ffi().ngeom],
1035 (mut = unsafe) geom_condim: &[i32; "contact dimensionality (1, 3, 4, 6)"; ffi().ngeom],
1036 (mut = unsafe) geom_bodyid: &[i32; "id of geom's body"; ffi().ngeom],
1037 (mut = unsafe) geom_dataid: &[i32; "id of geom's mesh/hfield; -1: none"; ffi().ngeom],
1038 (mut = unsafe) geom_matid: &[i32; "material id for rendering; -1: none"; ffi().ngeom],
1039 geom_group: &[i32; "group for visibility"; ffi().ngeom],
1040 geom_priority: &[i32; "geom contact priority"; ffi().ngeom],
1041 (mut = unsafe) geom_plugin: &[i32; "plugin instance id; -1: not in use"; ffi().ngeom],
1042 geom_sameframe: &[MjtSameFrame [force]; "same frame as body"; ffi().ngeom],
1043 geom_solmix: &[MjtNum; "mixing coef for solref/imp in geom pair"; ffi().ngeom],
1044 geom_solref: &[[MjtNum; mjNREF as usize] [force]; "constraint solver reference: contact"; ffi().ngeom],
1045 geom_solimp: &[[MjtNum; mjNIMP as usize] [force]; "constraint solver impedance: contact"; ffi().ngeom],
1046 geom_size: &[[MjtNum; 3] [force]; "geom-specific size parameters"; ffi().ngeom],
1047 geom_aabb: &[[MjtNum; 6] [force]; "bounding box, (center, size)"; ffi().ngeom],
1048 geom_rbound: &[MjtNum; "radius of bounding sphere"; ffi().ngeom],
1049 geom_pos: &[[MjtNum; 3] [force]; "local position offset rel. to body"; ffi().ngeom],
1050 geom_quat: &[[MjtNum; 4] [force]; "local orientation offset rel. to body"; ffi().ngeom],
1051 geom_friction: &[[MjtNum; 3] [force]; "friction for (slide, spin, roll)"; ffi().ngeom],
1052 geom_margin: &[MjtNum; "geometric inflation for contact"; ffi().ngeom],
1053 geom_gap: &[MjtNum; "additional contact detection buffer"; ffi().ngeom],
1054 geom_fluid: &[[MjtNum; mjNFLUID as usize] [force]; "fluid interaction parameters"; ffi().ngeom],
1055 geom_rgba: &[[f32; 4] [force]; "rgba when material is omitted"; ffi().ngeom],
1056 site_type: &[MjtGeom [force]; "geom type for rendering"; ffi().nsite],
1057 (mut = unsafe) site_bodyid: &[i32; "id of site's body"; ffi().nsite],
1058 (mut = unsafe) site_matid: &[i32; "material id for rendering; -1: none"; ffi().nsite],
1059 site_group: &[i32; "group for visibility"; ffi().nsite],
1060 site_sameframe: &[MjtSameFrame [force]; "same frame as body"; ffi().nsite],
1061 site_size: &[[MjtNum; 3] [force]; "geom size for rendering"; ffi().nsite],
1062 site_pos: &[[MjtNum; 3] [force]; "local position offset rel. to body"; ffi().nsite],
1063 site_quat: &[[MjtNum; 4] [force]; "local orientation offset rel. to body"; ffi().nsite],
1064 site_rgba: &[[f32; 4] [force]; "rgba when material is omitted"; ffi().nsite],
1065 cam_mode: &[MjtCamLight [force]; "camera tracking mode"; ffi().ncam],
1066 (mut = unsafe) cam_bodyid: &[i32; "id of camera's body"; ffi().ncam],
1067 (mut = unsafe) cam_targetbodyid: &[i32; "id of targeted body; -1: none"; ffi().ncam],
1068 cam_pos: &[[MjtNum; 3] [force]; "position rel. to body frame"; ffi().ncam],
1069 cam_quat: &[[MjtNum; 4] [force]; "orientation rel. to body frame"; ffi().ncam],
1070 cam_poscom0: &[[MjtNum; 3] [force]; "global position rel. to sub-com in qpos0"; ffi().ncam],
1071 cam_pos0: &[[MjtNum; 3] [force]; "global position rel. to body in qpos0"; ffi().ncam],
1072 cam_mat0: &[[MjtNum; 9] [force]; "global orientation in qpos0"; ffi().ncam],
1073 cam_projection: &[MjtProjection [force]; "projection type"; ffi().ncam],
1074 cam_fovy: &[MjtNum; "y field-of-view (ortho ? len : deg)"; ffi().ncam],
1075 cam_ipd: &[MjtNum; "inter-pupillary distance"; ffi().ncam],
1076 (mut = unsafe) cam_resolution: &[[i32; 2] [force]; "resolution: pixels [width, height]"; ffi().ncam],
1077 cam_output: &[i32; "output types (MjtCamOutBit bit flags)"; ffi().ncam],
1078 cam_sensorsize: &[[f32; 2] [force]; "sensor size: length [width, height]"; ffi().ncam],
1079 cam_intrinsic: &[[f32; 4] [force]; "[focal length; principal point]"; ffi().ncam],
1080 light_mode: &[MjtCamLight [force]; "light tracking mode"; ffi().nlight],
1081 (mut = unsafe) light_bodyid: &[i32; "id of light's body"; ffi().nlight],
1082 (mut = unsafe) light_targetbodyid: &[i32; "id of targeted body; -1: none"; ffi().nlight],
1083 light_type: &[MjtLightType [force]; "spot, directional, etc."; ffi().nlight],
1084 (mut = unsafe) light_texid: &[i32; "texture id for image lights"; ffi().nlight],
1085 light_castshadow: &[MjtBool; "does light cast shadows"; ffi().nlight],
1086 light_bulbradius: &[f32; "light radius for soft shadows"; ffi().nlight],
1087 light_intensity: &[f32; "intensity, in candela"; ffi().nlight],
1088 light_range: &[f32; "range of effectiveness"; ffi().nlight],
1089 light_active: &[MjtBool; "is light on"; ffi().nlight],
1090 light_pos: &[[MjtNum; 3] [force]; "position rel. to body frame"; ffi().nlight],
1091 light_dir: &[[MjtNum; 3] [force]; "direction rel. to body frame"; ffi().nlight],
1092 light_poscom0: &[[MjtNum; 3] [force]; "global position rel. to sub-com in qpos0"; ffi().nlight],
1093 light_pos0: &[[MjtNum; 3] [force]; "global position rel. to body in qpos0"; ffi().nlight],
1094 light_dir0: &[[MjtNum; 3] [force]; "global direction in qpos0"; ffi().nlight],
1095 light_attenuation: &[[f32; 3] [force]; "OpenGL attenuation (quadratic model)"; ffi().nlight],
1096 light_cutoff: &[f32; "OpenGL cutoff"; ffi().nlight],
1097 light_exponent: &[f32; "OpenGL exponent"; ffi().nlight],
1098 light_ambient: &[[f32; 3] [force]; "ambient rgb (alpha=1)"; ffi().nlight],
1099 light_diffuse: &[[f32; 3] [force]; "diffuse rgb (alpha=1)"; ffi().nlight],
1100 light_specular: &[[f32; 3] [force]; "specular rgb (alpha=1)"; ffi().nlight],
1101 flex_contype: &[i32; "flex contact type"; ffi().nflex],
1102 flex_conaffinity: &[i32; "flex contact affinity"; ffi().nflex],
1103 (mut = unsafe) flex_condim: &[i32; "contact dimensionality (1, 3, 4, 6)"; ffi().nflex],
1104 flex_priority: &[i32; "flex contact priority"; ffi().nflex],
1105 flex_solmix: &[MjtNum; "mix coef for solref/imp in contact pair"; ffi().nflex],
1106 flex_solref: &[[MjtNum; mjNREF as usize] [force]; "constraint solver reference: contact"; ffi().nflex],
1107 flex_solimp: &[[MjtNum; mjNIMP as usize] [force]; "constraint solver impedance: contact"; ffi().nflex],
1108 flex_friction: &[[MjtNum; 3] [force]; "friction for (slide, spin, roll)"; ffi().nflex],
1109 flex_margin: &[MjtNum; "geometric inflation for contact"; ffi().nflex],
1110 flex_gap: &[MjtNum; "additional contact detection buffer"; ffi().nflex],
1111 flex_internal: &[MjtBool; "internal flex collision enabled"; ffi().nflex],
1112 flex_selfcollide: &[MjtFlexSelf [force]; "self collision mode"; ffi().nflex],
1113 flex_activelayers: &[i32; "number of active element layers, 3D only"; ffi().nflex],
1114 flex_passive: &[i32; "passive collisions enabled"; ffi().nflex],
1115 (mut = unsafe) flex_dim: &[i32; "1: lines, 2: triangles, 3: tetrahedra"; ffi().nflex],
1116 (mut = unsafe) flex_matid: &[i32; "material id for rendering"; ffi().nflex],
1117 flex_group: &[i32; "group for visibility"; ffi().nflex],
1118 (mut = unsafe) flex_interp: &[i32; "interpolation (0: vertex, 1: nodes)"; ffi().nflex],
1119 (mut = unsafe) flex_cellnum: &[[i32; 3] [force]; "finite cell num per dimension"; ffi().nflex],
1120 (mut = unsafe) flex_nodeadr: &[i32; "first node address"; ffi().nflex],
1121 (mut = unsafe) flex_nodenum: &[i32; "number of nodes"; ffi().nflex],
1122 (mut = unsafe) flex_vertadr: &[i32; "first vertex address"; ffi().nflex],
1123 (mut = unsafe) flex_vertnum: &[i32; "number of vertices"; ffi().nflex],
1124 (mut = unsafe) flex_edgeadr: &[i32; "first edge address"; ffi().nflex],
1125 (mut = unsafe) flex_edgenum: &[i32; "number of edges"; ffi().nflex],
1126 (mut = unsafe) flex_elemadr: &[i32; "first element address"; ffi().nflex],
1127 (mut = unsafe) flex_elemnum: &[i32; "number of elements"; ffi().nflex],
1128 (mut = unsafe) flex_elemdataadr: &[i32; "first element vertex id address"; ffi().nflex],
1129 (mut = unsafe) flex_stiffnessadr: &[i32; "stiffness matrix address"; ffi().nflex],
1130 (mut = unsafe) flex_elemedgeadr: &[i32; "first element edge id address"; ffi().nflex],
1131 (mut = unsafe) flex_bendingadr: &[i32; "first bending data address"; ffi().nflex],
1132 (mut = unsafe) flex_shellnum: &[i32; "number of shells"; ffi().nflex],
1133 (mut = unsafe) flex_shelldataadr: &[i32; "first shell data address"; ffi().nflex],
1134 (mut = unsafe) flex_evpairadr: &[i32; "first evpair address"; ffi().nflex],
1135 (mut = unsafe) flex_evpairnum: &[i32; "number of evpairs"; ffi().nflex],
1136 (mut = unsafe) flex_texcoordadr: &[i32; "address in flex_texcoord; -1: none"; ffi().nflex],
1137 (mut = unsafe) flex_nodebodyid: &[i32; "node body ids"; ffi().nflexnode],
1138 (mut = unsafe) flex_vertbodyid: &[i32; "vertex body ids"; ffi().nflexvert],
1139 (mut = unsafe) flex_vertedgeadr: &[i32; "first edge address"; ffi().nflexvert],
1140 (mut = unsafe) flex_vertedgenum: &[i32; "number of edges"; ffi().nflexvert],
1141 (mut = unsafe) flex_vertedge: &[[i32; 2] [force]; "edge indices"; ffi().nflexedge],
1142 (mut = unsafe) flex_edge: &[[i32; 2] [force]; "edge vertex ids (2 per edge)"; ffi().nflexedge],
1143 (mut = unsafe) flex_edgeflap: &[[i32; 2] [force]; "adjacent vertex ids (dim=2 only)"; ffi().nflexedge],
1144 (mut = unsafe) flex_elem: &[i32; "element vertex ids (dim+1 per elem)"; ffi().nflexelemdata],
1145 (mut = unsafe) flex_elemtexcoord: &[i32; "element texture coordinates (dim+1)"; ffi().nflexelemdata],
1146 (mut = unsafe) flex_elemedge: &[i32; "element edge ids"; ffi().nflexelemedge],
1147 flex_elemlayer: &[i32; "element distance from surface, 3D only"; ffi().nflexelem],
1148 (mut = unsafe) flex_shell: &[i32; "shell fragment vertex ids (dim per frag)"; ffi().nflexshelldata],
1149 (mut = unsafe) flex_evpair: &[[i32; 2] [force]; "(element, vertex) collision pairs"; ffi().nflexevpair],
1150 flex_vert: &[[MjtNum; 3] [force]; "vertex positions in local body frames"; ffi().nflexvert],
1151 flex_vert0: &[[MjtNum; 3] [force]; "vertex positions in qpos0 on [0, 1]^d"; ffi().nflexvert],
1152 flex_vertmetric: &[[MjtNum; 4] [force]; "inverse of reference shape matrix"; ffi().nflexvert],
1153 flex_node: &[[MjtNum; 3] [force]; "node positions in local body frames"; ffi().nflexnode],
1154 flex_node0: &[[MjtNum; 3] [force]; "Cartesian node positions in qpos0"; ffi().nflexnode],
1155 flexedge_length0: &[MjtNum; "edge lengths in qpos0"; ffi().nflexedge],
1156 flexedge_invweight0: &[MjtNum; "edge inv. weight in qpos0"; ffi().nflexedge],
1157 flex_radius: &[MjtNum; "radius around primitive element"; ffi().nflex],
1158 flex_size: &[[MjtNum; 3] [force]; "vertex bounding box half sizes in qpos0"; ffi().nflex],
1159 flex_stiffness: &[MjtNum; "finite element stiffness matrix"; ffi().nflexstiffness],
1160 flex_bending: &[MjtNum; "bending stiffness"; ffi().nflexbending],
1161 flex_damping: &[MjtNum; "Rayleigh's damping coefficient"; ffi().nflex],
1162 flex_edgestiffness: &[MjtNum; "edge stiffness"; ffi().nflex],
1163 flex_edgedamping: &[MjtNum; "edge damping"; ffi().nflex],
1164 flex_edgeequality: &[i32; "0: none, 1: edges, 2: vertices, 3: strain"; ffi().nflex],
1165 flex_rigid: &[MjtBool; "are all vertices in the same body"; ffi().nflex],
1166 flexedge_rigid: &[MjtBool; "are both edge vertices in same body"; ffi().nflexedge],
1167 flex_centered: &[MjtBool; "are all vertex coordinates (0,0,0)"; ffi().nflex],
1168 flex_flatskin: &[MjtBool; "render flex skin with flat shading"; ffi().nflex],
1169 (mut = unsafe) flex_bvhadr: &[i32; "address of bvh root; -1: no bvh"; ffi().nflex],
1170 (mut = unsafe) flex_bvhnum: &[i32; "number of bounding volumes"; ffi().nflex],
1171 (mut = unsafe) flexedge_J_rownnz: &[i32; "number of non-zeros in Jacobian row"; ffi().nflexedge],
1172 (mut = unsafe) flexedge_J_rowadr: &[i32; "row start address in colind array"; ffi().nflexedge],
1173 (mut = unsafe) flexedge_J_colind: &[i32; "column indices in sparse Jacobian"; ffi().nJfe],
1174 (mut = unsafe) flexvert_J_rownnz: &[[i32; 2] [force]; "number of non-zeros in Jacobian row"; ffi().nflexvert],
1175 (mut = unsafe) flexvert_J_rowadr: &[[i32; 2] [force]; "row start address in colind array"; ffi().nflexvert],
1176 (mut = unsafe) flexvert_J_colind: &[[i32; 2] [force]; "column indices in sparse Jacobian"; ffi().nJfv],
1177 flex_rgba: &[[f32; 4] [force]; "rgba when material is omitted"; ffi().nflex],
1178 flex_texcoord: &[[f32; 2] [force]; "vertex texture coordinates"; ffi().nflextexcoord],
1179 (mut = unsafe) mesh_vertadr: &[i32; "first vertex address"; ffi().nmesh],
1180 (mut = unsafe) mesh_vertnum: &[i32; "number of vertices"; ffi().nmesh],
1181 (mut = unsafe) mesh_faceadr: &[i32; "first face address"; ffi().nmesh],
1182 (mut = unsafe) mesh_facenum: &[i32; "number of faces"; ffi().nmesh],
1183 (mut = unsafe) mesh_bvhadr: &[i32; "address of bvh root"; ffi().nmesh],
1184 (mut = unsafe) mesh_bvhnum: &[i32; "number of bvh"; ffi().nmesh],
1185 (mut = unsafe) mesh_octadr: &[i32; "address of octree root"; ffi().nmesh],
1186 (mut = unsafe) mesh_octnum: &[i32; "number of octree nodes"; ffi().nmesh],
1187 (mut = unsafe) mesh_normaladr: &[i32; "first normal address"; ffi().nmesh],
1188 (mut = unsafe) mesh_normalnum: &[i32; "number of normals"; ffi().nmesh],
1189 (mut = unsafe) mesh_texcoordadr: &[i32; "texcoord data address; -1: no texcoord"; ffi().nmesh],
1190 (mut = unsafe) mesh_texcoordnum: &[i32; "number of texcoord"; ffi().nmesh],
1191 (mut = unsafe) mesh_graphadr: &[i32; "graph data address; -1: no graph"; ffi().nmesh],
1192 mesh_vert: &[[f32; 3] [force]; "vertex positions for all meshes"; ffi().nmeshvert],
1193 mesh_normal: &[[f32; 3] [force]; "normals for all meshes"; ffi().nmeshnormal],
1194 mesh_texcoord: &[[f32; 2] [force]; "vertex texcoords for all meshes"; ffi().nmeshtexcoord],
1195 (mut = unsafe) mesh_face: &[[i32; 3] [force]; "vertex face data"; ffi().nmeshface],
1196 (mut = unsafe) mesh_facenormal: &[[i32; 3] [force]; "normal face data"; ffi().nmeshface],
1197 (mut = unsafe) mesh_facetexcoord: &[[i32; 3] [force]; "texture face data"; ffi().nmeshface],
1198 (mut = unsafe) mesh_graph: &[i32; "convex graph data"; ffi().nmeshgraph],
1199 mesh_scale: &[[MjtNum; 3] [force]; "scaling applied to asset vertices"; ffi().nmesh],
1200 mesh_pos: &[[MjtNum; 3] [force]; "translation applied to asset vertices"; ffi().nmesh],
1201 mesh_quat: &[[MjtNum; 4] [force]; "rotation applied to asset vertices"; ffi().nmesh],
1202 (mut = unsafe) mesh_pathadr: &[i32; "address of asset path for mesh; -1: none"; ffi().nmesh],
1203 (mut = unsafe) mesh_polynum: &[i32; "number of polygons per mesh"; ffi().nmesh],
1204 (mut = unsafe) mesh_polyadr: &[i32; "first polygon address per mesh"; ffi().nmesh],
1205 mesh_polynormal: &[[MjtNum; 3] [force]; "all polygon normals"; ffi().nmeshpoly],
1206 (mut = unsafe) mesh_polyvertadr: &[i32; "polygon vertex start address"; ffi().nmeshpoly],
1207 (mut = unsafe) mesh_polyvertnum: &[i32; "number of vertices per polygon"; ffi().nmeshpoly],
1208 (mut = unsafe) mesh_polyvert: &[i32; "all polygon vertices"; ffi().nmeshpolyvert],
1209 (mut = unsafe) mesh_polymapadr: &[i32; "first polygon address per vertex"; ffi().nmeshvert],
1210 (mut = unsafe) mesh_polymapnum: &[i32; "number of polygons per vertex"; ffi().nmeshvert],
1211 (mut = unsafe) mesh_polymap: &[i32; "vertex to polygon map"; ffi().nmeshpolymap],
1212 (mut = unsafe) skin_matid: &[i32; "skin material id; -1: none"; ffi().nskin],
1213 skin_group: &[i32; "group for visibility"; ffi().nskin],
1214 skin_rgba: &[[f32; 4] [force]; "skin rgba"; ffi().nskin],
1215 skin_inflate: &[f32; "inflate skin in normal direction"; ffi().nskin],
1216 (mut = unsafe) skin_vertadr: &[i32; "first vertex address"; ffi().nskin],
1217 (mut = unsafe) skin_vertnum: &[i32; "number of vertices"; ffi().nskin],
1218 (mut = unsafe) skin_texcoordadr: &[i32; "texcoord data address; -1: no texcoord"; ffi().nskin],
1219 (mut = unsafe) skin_faceadr: &[i32; "first face address"; ffi().nskin],
1220 (mut = unsafe) skin_facenum: &[i32; "number of faces"; ffi().nskin],
1221 (mut = unsafe) skin_boneadr: &[i32; "first bone in skin"; ffi().nskin],
1222 (mut = unsafe) skin_bonenum: &[i32; "number of bones in skin"; ffi().nskin],
1223 skin_vert: &[[f32; 3] [force]; "vertex positions for all skin meshes"; ffi().nskinvert],
1224 skin_texcoord: &[[f32; 2] [force]; "vertex texcoords for all skin meshes"; ffi().nskintexvert],
1225 (mut = unsafe) skin_face: &[[i32; 3] [force]; "triangle faces for all skin meshes"; ffi().nskinface],
1226 (mut = unsafe) skin_bonevertadr: &[i32; "first vertex in each bone"; ffi().nskinbone],
1227 (mut = unsafe) skin_bonevertnum: &[i32; "number of vertices in each bone"; ffi().nskinbone],
1228 skin_bonebindpos: &[[f32; 3] [force]; "bind pos of each bone"; ffi().nskinbone],
1229 skin_bonebindquat: &[[f32; 4] [force]; "bind quat of each bone"; ffi().nskinbone],
1230 (mut = unsafe) skin_bonebodyid: &[i32; "body id of each bone"; ffi().nskinbone],
1231 (mut = unsafe) skin_bonevertid: &[i32; "mesh ids of vertices in each bone"; ffi().nskinbonevert],
1232 skin_bonevertweight: &[f32; "weights of vertices in each bone"; ffi().nskinbonevert],
1233 (mut = unsafe) skin_pathadr: &[i32; "address of asset path for skin; -1: none"; ffi().nskin],
1234 hfield_size: &[[MjtNum; 4] [force]; "(x, y, z_top, z_bottom)"; ffi().nhfield],
1235 (mut = unsafe) hfield_nrow: &[i32; "number of rows in grid"; ffi().nhfield],
1236 (mut = unsafe) hfield_ncol: &[i32; "number of columns in grid"; ffi().nhfield],
1237 (mut = unsafe) hfield_adr: &[i32; "address in hfield_data"; ffi().nhfield],
1238 hfield_data: &[f32; "elevation data"; ffi().nhfielddata],
1239 (mut = unsafe) hfield_pathadr: &[i32; "address of hfield asset path; -1: none"; ffi().nhfield],
1240 tex_type: &[MjtTexture [force]; "texture type"; ffi().ntex],
1241 tex_colorspace: &[MjtColorSpace [force]; "texture colorspace"; ffi().ntex],
1242 (mut = unsafe) tex_height: &[i32; "number of rows in texture image"; ffi().ntex],
1243 (mut = unsafe) tex_width: &[i32; "number of columns in texture image"; ffi().ntex],
1244 (mut = unsafe) tex_nchannel: &[i32; "number of channels in texture image"; ffi().ntex],
1245 (mut = unsafe) tex_adr: &[MjtSize; "start address in tex_data"; ffi().ntex],
1246 tex_data: &[MjtByte; "pixel values"; ffi().ntexdata],
1247 (mut = unsafe) tex_pathadr: &[i32; "address of texture asset path; -1: none"; ffi().ntex],
1248 (mut = unsafe) mat_texid: &[[i32; MjtTextureRole::mjNTEXROLE as usize] [force]; "indices of textures; -1: none"; ffi().nmat],
1249 mat_texuniform: &[MjtBool; "make texture cube uniform"; ffi().nmat],
1250 mat_texrepeat: &[[f32; 2] [force]; "texture repetition for 2d mapping"; ffi().nmat],
1251 mat_emission: &[f32; "emission (x rgb)"; ffi().nmat],
1252 mat_specular: &[f32; "specular (x white)"; ffi().nmat],
1253 mat_shininess: &[f32; "shininess coef"; ffi().nmat],
1254 mat_reflectance: &[f32; "reflectance (0: disable)"; ffi().nmat],
1255 mat_metallic: &[f32; "metallic coef"; ffi().nmat],
1256 mat_roughness: &[f32; "roughness coef"; ffi().nmat],
1257 mat_rgba: &[[f32; 4] [force]; "rgba"; ffi().nmat],
1258 (mut = unsafe) pair_dim: &[i32; "contact dimensionality"; ffi().npair],
1259 (mut = unsafe) pair_geom1: &[i32; "id of geom1"; ffi().npair],
1260 (mut = unsafe) pair_geom2: &[i32; "id of geom2"; ffi().npair],
1261 pair_signature: &[i32; "body1 << 16 + body2"; ffi().npair],
1262 pair_solref: &[[MjtNum; mjNREF as usize] [force]; "solver reference: contact normal"; ffi().npair],
1263 pair_solreffriction: &[[MjtNum; mjNREF as usize] [force]; "solver reference: contact friction"; ffi().npair],
1264 pair_solimp: &[[MjtNum; mjNIMP as usize] [force]; "solver impedance: contact"; ffi().npair],
1265 pair_margin: &[MjtNum; "geometric inflation for contact"; ffi().npair],
1266 pair_gap: &[MjtNum; "additional contact detection buffer"; ffi().npair],
1267 pair_friction: &[[MjtNum; 5] [force]; "tangent1, 2, spin, roll1, 2"; ffi().npair],
1268 exclude_signature: &[i32; "body1 << 16 + body2"; ffi().nexclude],
1269 (mut = unsafe) eq_type: &[MjtEq [force]; "constraint type"; ffi().neq],
1270 (mut = unsafe) eq_obj1id: &[i32; "id of object 1"; ffi().neq],
1271 (mut = unsafe) eq_obj2id: &[i32; "id of object 2"; ffi().neq],
1272 (mut = unsafe) eq_objtype: &[MjtObj [force]; "type of both objects"; ffi().neq],
1273 eq_active0: &[MjtBool; "initial enable/disable constraint state"; ffi().neq],
1274 eq_solref: &[[MjtNum; mjNREF as usize] [force]; "constraint solver reference"; ffi().neq],
1275 eq_solimp: &[[MjtNum; mjNIMP as usize] [force]; "constraint solver impedance"; ffi().neq],
1276 eq_data: &[[MjtNum; mjNEQDATA as usize] [force]; "numeric data for constraint"; ffi().neq],
1277 (mut = unsafe) tendon_adr: &[i32; "address of first object in tendon's path"; ffi().ntendon],
1278 (mut = unsafe) tendon_num: &[i32; "number of objects in tendon's path"; ffi().ntendon],
1279 (mut = unsafe) tendon_matid: &[i32; "material id for rendering"; ffi().ntendon],
1280 (mut = unsafe) tendon_actuatorid: &[i32; "actuator contributing damping / armature"; ffi().ntendon],
1281 tendon_group: &[i32; "group for visibility"; ffi().ntendon],
1282 tendon_treenum: &[i32; "number of trees along tendon's path"; ffi().ntendon],
1283 (mut = unsafe) tendon_treeid: &[[i32; 2] [force]; "first two trees along tendon's path"; ffi().ntendon],
1284 (mut = unsafe) ten_J_rownnz: &[i32; "number of non-zeros in Jacobian row"; ffi().ntendon],
1285 (mut = unsafe) ten_J_rowadr: &[i32; "row start address in colind array"; ffi().ntendon],
1286 (mut = unsafe) ten_J_colind: &[i32; "column indices in sparse Jacobian"; ffi().nJten],
1287 tendon_limited: &[MjtBool; "does tendon have length limits"; ffi().ntendon],
1288 tendon_actfrclimited: &[MjtBool; "does tendon have actuator force limits"; ffi().ntendon],
1289 tendon_width: &[MjtNum; "width for rendering"; ffi().ntendon],
1290 tendon_solref_lim: &[[MjtNum; mjNREF as usize] [force]; "constraint solver reference: limit"; ffi().ntendon],
1291 tendon_solimp_lim: &[[MjtNum; mjNIMP as usize] [force]; "constraint solver impedance: limit"; ffi().ntendon],
1292 tendon_solref_fri: &[[MjtNum; mjNREF as usize] [force]; "constraint solver reference: friction"; ffi().ntendon],
1293 tendon_solimp_fri: &[[MjtNum; mjNIMP as usize] [force]; "constraint solver impedance: friction"; ffi().ntendon],
1294 tendon_range: &[[MjtNum; 2] [force]; "tendon length limits"; ffi().ntendon],
1295 tendon_actfrcrange: &[[MjtNum; 2] [force]; "range of total actuator force"; ffi().ntendon],
1296 tendon_margin: &[MjtNum; "min distance for limit detection"; ffi().ntendon],
1297 tendon_stiffness: &[MjtNum; "stiffness coefficient"; ffi().ntendon],
1298 tendon_stiffnesspoly: &[[MjtNum; mjNPOLY as usize] [force]; "high-order stiffness coefficients"; ffi().ntendon],
1299 tendon_damping: &[MjtNum; "damping coefficient"; ffi().ntendon],
1300 tendon_dampingpoly: &[[MjtNum; mjNPOLY as usize] [force]; "high-order damping coefficients"; ffi().ntendon],
1301 tendon_armature: &[MjtNum; "inertia associated with tendon velocity"; ffi().ntendon],
1302 tendon_frictionloss: &[MjtNum; "loss due to friction"; ffi().ntendon],
1303 tendon_lengthspring: &[[MjtNum; 2] [force]; "spring resting length range"; ffi().ntendon],
1304 tendon_length0: &[MjtNum; "tendon length in qpos0"; ffi().ntendon],
1305 tendon_invweight0: &[MjtNum; "inv. weight in qpos0"; ffi().ntendon],
1306 tendon_rgba: &[[f32; 4] [force]; "rgba when material is omitted"; ffi().ntendon],
1307 (mut = unsafe) wrap_type: &[MjtWrap [force]; "wrap object type"; ffi().nwrap],
1308 (mut = unsafe) wrap_objid: &[i32; "object id: geom, site, joint"; ffi().nwrap],
1309 (mut = unsafe) wrap_prm: &[MjtNum; "divisor, joint coef, or site id"; ffi().nwrap],
1310 (mut = unsafe) actuator_trntype: &[MjtTrn [force]; "transmission type"; ffi().nu],
1311 (mut = unsafe) actuator_dyntype: &[MjtDyn [force]; "dynamics type"; ffi().nu],
1312 actuator_gaintype: &[MjtGain [force]; "gain type"; ffi().nu],
1313 actuator_biastype: &[MjtBias [force]; "bias type"; ffi().nu],
1314 (mut = unsafe) actuator_trnid: &[[i32; 2] [force]; "transmission id: joint, tendon, site"; ffi().nu],
1315 (mut = unsafe) actuator_actadr: &[i32; "first activation address; -1: stateless"; ffi().nu],
1316 (mut = unsafe) actuator_actnum: &[i32; "number of activation variables"; ffi().nu],
1317 actuator_group: &[i32; "group for visibility"; ffi().nu],
1318 (mut = unsafe) actuator_history: &[[i32; 2] [force]; "history buffer: [nsample, interp]"; ffi().nu],
1319 (mut = unsafe) actuator_historyadr: &[i32; "address in history buffer; -1: none"; ffi().nu],
1320 actuator_delay: &[MjtNum; "delay time in seconds; 0: no delay"; ffi().nu],
1321 actuator_ctrllimited: &[MjtBool; "is control limited"; ffi().nu],
1322 actuator_forcelimited: &[MjtBool; "is force limited"; ffi().nu],
1323 actuator_actlimited: &[MjtBool; "is activation limited"; ffi().nu],
1324 actuator_dynprm: &[[MjtNum; mjNDYN as usize] [force]; "dynamics parameters"; ffi().nu],
1325 actuator_gainprm: &[[MjtNum; mjNGAIN as usize] [force]; "gain parameters"; ffi().nu],
1326 actuator_biasprm: &[[MjtNum; mjNBIAS as usize] [force]; "bias parameters"; ffi().nu],
1327 actuator_actearly: &[MjtBool; "step activation before force"; ffi().nu],
1328 actuator_ctrlrange: &[[MjtNum; 2] [force]; "range of controls"; ffi().nu],
1329 actuator_forcerange: &[[MjtNum; 2] [force]; "range of forces"; ffi().nu],
1330 actuator_actrange: &[[MjtNum; 2] [force]; "range of activations"; ffi().nu],
1331 actuator_damping: &[MjtNum; "linear damping coefficient"; ffi().nu],
1332 actuator_dampingpoly: &[[MjtNum; mjNPOLY as usize] [force]; "high-order damping coefficients"; ffi().nu],
1333 actuator_armature: &[MjtNum; "armature added to target"; ffi().nu],
1334 actuator_gear: &[[MjtNum; 6] [force]; "scale length and transmitted force"; ffi().nu],
1335 actuator_cranklength: &[MjtNum; "crank length for slider-crank"; ffi().nu],
1336 actuator_acc0: &[MjtNum; "acceleration from unit force in qpos0"; ffi().nu],
1337 actuator_length0: &[MjtNum; "actuator length in qpos0"; ffi().nu],
1338 actuator_lengthrange: &[[MjtNum; 2] [force]; "feasible actuator length range"; ffi().nu],
1339 (mut = unsafe) actuator_plugin: &[i32; "plugin instance id; -1: not a plugin"; ffi().nu],
1340 (mut = unsafe) sensor_type: &[MjtSensor [force]; "sensor type"; ffi().nsensor],
1341 sensor_datatype: &[MjtDataType [force]; "numeric data type"; ffi().nsensor],
1342 sensor_needstage: &[MjtStage [force]; "required compute stage"; ffi().nsensor],
1343 (mut = unsafe) sensor_objtype: &[MjtObj [force]; "type of sensorized object"; ffi().nsensor],
1344 (mut = unsafe) sensor_objid: &[i32; "id of sensorized object"; ffi().nsensor],
1345 (mut = unsafe) sensor_reftype: &[MjtObj [force]; "type of reference frame"; ffi().nsensor],
1346 (mut = unsafe) sensor_refid: &[i32; "id of reference frame; -1: global frame"; ffi().nsensor],
1347 sensor_intprm: &[[i32; mjNSENS as usize] [force]; "sensor parameters"; ffi().nsensor],
1348 (mut = unsafe) sensor_dim: &[i32; "number of scalar outputs"; ffi().nsensor],
1349 (mut = unsafe) sensor_adr: &[i32; "address in sensor array"; ffi().nsensor],
1350 sensor_cutoff: &[MjtNum; "cutoff for real and positive; 0: ignore"; ffi().nsensor],
1351 sensor_noise: &[MjtNum; "noise standard deviation"; ffi().nsensor],
1352 (mut = unsafe) sensor_history: &[[i32; 2] [force]; "history buffer: [nsample, interp]"; ffi().nsensor],
1353 (mut = unsafe) sensor_historyadr: &[i32; "address in history buffer; -1: none"; ffi().nsensor],
1354 sensor_delay: &[MjtNum; "delay time in seconds; 0: no delay"; ffi().nsensor],
1355 sensor_interval: &[[MjtNum; 2] [force]; "interval: [period, phase] in seconds"; ffi().nsensor],
1356 (mut = unsafe) sensor_plugin: &[i32; "plugin instance id; -1: not a plugin"; ffi().nsensor],
1357 (mut = unsafe) plugin: &[i32; "globally registered plugin slot number"; ffi().nplugin],
1358 (mut = unsafe) plugin_stateadr: &[i32; "address in the plugin state array"; ffi().nplugin],
1359 (mut = unsafe) plugin_statenum: &[i32; "number of states in the plugin instance"; ffi().nplugin],
1360 (mut = unsafe) plugin_attr: &[c_char; "config attributes of plugin instances"; ffi().npluginattr],
1361 (mut = unsafe) plugin_attradr: &[i32; "address to each instance's config attrib"; ffi().nplugin],
1362 (mut = unsafe) numeric_adr: &[i32; "address of field in numeric_data"; ffi().nnumeric],
1363 (mut = unsafe) numeric_size: &[i32; "size of numeric field"; ffi().nnumeric],
1364 numeric_data: &[MjtNum; "array of all numeric fields"; ffi().nnumericdata],
1365 (mut = unsafe) text_adr: &[i32; "address of text in text_data"; ffi().ntext],
1366 (mut = unsafe) text_size: &[i32; "size of text field (strlen+1)"; ffi().ntext],
1367 (mut = unsafe) text_data: &[c_char; "array of all text fields (0-terminated)"; ffi().ntextdata],
1368 (mut = unsafe) tuple_adr: &[i32; "address of text in text_data"; ffi().ntuple],
1369 (mut = unsafe) tuple_size: &[i32; "number of objects in tuple"; ffi().ntuple],
1370 tuple_objtype: &[MjtObj [force]; "array of object types in all tuples"; ffi().ntupledata],
1371 (mut = unsafe) tuple_objid: &[i32; "array of object ids in all tuples"; ffi().ntupledata],
1372 tuple_objprm: &[MjtNum; "array of object params in all tuples"; ffi().ntupledata],
1373 key_time: &[MjtNum; "key time"; ffi().nkey],
1374 (mut = unsafe) name_bodyadr: &[i32; "body name pointers"; ffi().nbody],
1375 (mut = unsafe) name_jntadr: &[i32; "joint name pointers"; ffi().njnt],
1376 (mut = unsafe) name_geomadr: &[i32; "geom name pointers"; ffi().ngeom],
1377 (mut = unsafe) name_siteadr: &[i32; "site name pointers"; ffi().nsite],
1378 (mut = unsafe) name_camadr: &[i32; "camera name pointers"; ffi().ncam],
1379 (mut = unsafe) name_lightadr: &[i32; "light name pointers"; ffi().nlight],
1380 (mut = unsafe) name_flexadr: &[i32; "flex name pointers"; ffi().nflex],
1381 (mut = unsafe) name_meshadr: &[i32; "mesh name pointers"; ffi().nmesh],
1382 (mut = unsafe) name_skinadr: &[i32; "skin name pointers"; ffi().nskin],
1383 (mut = unsafe) name_hfieldadr: &[i32; "hfield name pointers"; ffi().nhfield],
1384 (mut = unsafe) name_texadr: &[i32; "texture name pointers"; ffi().ntex],
1385 (mut = unsafe) name_matadr: &[i32; "material name pointers"; ffi().nmat],
1386 (mut = unsafe) name_pairadr: &[i32; "geom pair name pointers"; ffi().npair],
1387 (mut = unsafe) name_excludeadr: &[i32; "exclude name pointers"; ffi().nexclude],
1388 (mut = unsafe) name_eqadr: &[i32; "equality constraint name pointers"; ffi().neq],
1389 (mut = unsafe) name_tendonadr: &[i32; "tendon name pointers"; ffi().ntendon],
1390 (mut = unsafe) name_actuatoradr: &[i32; "actuator name pointers"; ffi().nu],
1391 (mut = unsafe) name_sensoradr: &[i32; "sensor name pointers"; ffi().nsensor],
1392 (mut = unsafe) name_numericadr: &[i32; "numeric name pointers"; ffi().nnumeric],
1393 (mut = unsafe) name_textadr: &[i32; "text name pointers"; ffi().ntext],
1394 (mut = unsafe) name_tupleadr: &[i32; "tuple name pointers"; ffi().ntuple],
1395 (mut = unsafe) name_keyadr: &[i32; "keyframe name pointers"; ffi().nkey],
1396 (mut = unsafe) name_pluginadr: &[i32; "plugin instance name pointers"; ffi().nplugin],
1397 (mut = unsafe) names: &[c_char; "names of all objects, 0-terminated"; ffi().nnames],
1398 (mut = unsafe) names_map: &[i32; "internal hash map of names"; ffi().nnames_map],
1399 (mut = unsafe) paths: &[c_char; "paths to assets, 0-terminated"; ffi().npaths],
1400 (mut = unsafe) B_rownnz: &[i32; "body-dof: non-zeros in each row"; ffi().nbody],
1401 (mut = unsafe) B_rowadr: &[i32; "body-dof: row addresses"; ffi().nbody],
1402 (mut = unsafe) B_colind: &[i32; "body-dof: column indices"; ffi().nB],
1403 (mut = unsafe) M_rownnz: &[i32; "reduced inertia: non-zeros in each row"; ffi().nv],
1404 (mut = unsafe) M_rowadr: &[i32; "reduced inertia: row addresses"; ffi().nv],
1405 (mut = unsafe) M_colind: &[i32; "reduced inertia: column indices"; ffi().nC],
1406 (mut = unsafe) mapM2M: &[i32; "index mapping from qM to M"; ffi().nC],
1407 (mut = unsafe) D_rownnz: &[i32; "non-zeros in each row"; ffi().nv],
1408 (mut = unsafe) D_rowadr: &[i32; "full inertia: row addresses"; ffi().nv],
1409 (mut = unsafe) D_diag: &[i32; "full inertia: index of diagonal element"; ffi().nv],
1410 (mut = unsafe) D_colind: &[i32; "full inertia: column indices"; ffi().nD],
1411 (mut = unsafe) mapM2D: &[i32; "index mapping from M to D"; ffi().nD],
1412 (mut = unsafe) mapD2M: &[i32; "index mapping from D to M"; ffi().nC]
1413 }
1414
1415 array_slice_dyn! {
1416 sublen_dep {
1417 key_qpos: &[[MjtNum; ffi().nq] [force]; "key position"; ffi().nkey],
1418 key_qvel: &[[MjtNum; ffi().nv] [force]; "key velocity"; ffi().nkey],
1419 key_act: &[[MjtNum; ffi().na] [force]; "key activation"; ffi().nkey],
1420 key_mpos: &[[MjtNum; ffi().nmocap * 3] [force]; "key mocap position"; ffi().nkey],
1421 key_mquat: &[[MjtNum; ffi().nmocap * 4] [force]; "key mocap quaternion"; ffi().nkey],
1422 key_ctrl: &[[MjtNum; ffi().nu] [force]; "key control"; ffi().nkey],
1423
1424 sensor_user: &[[MjtNum; ffi().nuser_sensor] [force]; "user data"; ffi().nsensor],
1425 actuator_user: &[[MjtNum; ffi().nuser_actuator] [force]; "user data"; ffi().nu],
1426 tendon_user: &[[MjtNum; ffi().nuser_tendon] [force]; "user data"; ffi().ntendon],
1427 cam_user: &[[MjtNum; ffi().nuser_cam] [force]; "user data"; ffi().ncam],
1428 site_user: &[[MjtNum; ffi().nuser_site] [force]; "user data"; ffi().nsite],
1429 geom_user: &[[MjtNum; ffi().nuser_geom] [force]; "user data"; ffi().ngeom],
1430 jnt_user: &[[MjtNum; ffi().nuser_jnt] [force]; "user data"; ffi().njnt],
1431 body_user: &[[MjtNum; ffi().nuser_body] [force]; "user data"; ffi().nbody]
1432 }
1433 }
1434}
1435
1436impl Clone for MjModel {
1437 fn clone(&self) -> Self {
1441 self.try_clone().expect("failed to clone model")
1442 }
1443}
1444
1445impl Drop for MjModel {
1446 fn drop(&mut self) {
1447 unsafe {
1449 mj_deleteModel(self.0.as_ptr());
1450 }
1451 }
1452}
1453
1454info_with_view!(Model, actuator,
1455 [[actuator_] group: i32,
1456 [actuator_] delay: MjtNum, [actuator_] ctrllimited: MjtBool,
1457 [actuator_] forcelimited: MjtBool, [actuator_] actlimited: MjtBool,
1458 [actuator_] dynprm: MjtNum, [actuator_] gainprm: MjtNum,
1459 [actuator_] biasprm: MjtNum, [actuator_] actearly: MjtBool,
1460 [actuator_] ctrlrange: MjtNum, [actuator_] forcerange: MjtNum,
1461 [actuator_] actrange: MjtNum, [actuator_] gear: MjtNum,
1462 [actuator_] damping: MjtNum, [actuator_] dampingpoly: MjtNum,
1463 [actuator_] armature: MjtNum,
1464 [actuator_] cranklength: MjtNum, [actuator_] acc0: MjtNum,
1465 [actuator_] length0: MjtNum, [actuator_] lengthrange: MjtNum,
1466 [actuator_] user: MjtNum,
1467 [actuator_] gaintype: MjtGain [force], [actuator_] biastype: MjtBias [force],
1468 [actuator_] plugin: i32],
1469 [[actuator_] trntype: MjtTrn [force], [actuator_] dyntype: MjtDyn [force],
1470 [actuator_] trnid: i32, [actuator_] actadr: i32,
1471 [actuator_] actnum: i32, [actuator_] history: i32,
1472 [actuator_] historyadr: i32],
1473 []);
1474
1475info_with_view!(Model, body,
1476 [[body_] sameframe: MjtSameFrame [force],
1477 [body_] pos: MjtNum,
1478 [body_] quat: MjtNum, [body_] ipos: MjtNum,
1479 [body_] iquat: MjtNum, [body_] mass: MjtNum,
1480 [body_] subtreemass: MjtNum, [body_] inertia: MjtNum,
1481 [body_] invweight0: MjtNum, [body_] gravcomp: MjtNum,
1482 [body_] margin: MjtNum,
1483 [body_] contype: i32, [body_] conaffinity: i32,
1484 [body_] user: MjtNum,
1485 [body_] simple: MjtByte, [body_] plugin: i32],
1486 [[body_] parentid: i32, [body_] rootid: i32,
1487 [body_] weldid: i32, [body_] mocapid: i32,
1488 [body_] jntnum: i32, [body_] jntadr: i32,
1489 [body_] dofnum: i32, [body_] dofadr: i32,
1490 [body_] treeid: i32, [body_] geomnum: i32,
1491 [body_] geomadr: i32,
1492 [body_] bvhadr: i32, [body_] bvhnum: i32],
1493 []);
1494
1495info_with_view!(Model, camera,
1496 [[cam_] mode: MjtCamLight [force],
1497 [cam_] pos: MjtNum,
1498 [cam_] quat: MjtNum,
1499 [cam_] poscom0: MjtNum,
1500 [cam_] pos0: MjtNum,
1501 [cam_] mat0: MjtNum,
1502 [cam_] projection: MjtProjection [force],
1503 [cam_] fovy: MjtNum,
1504 [cam_] ipd: MjtNum,
1505 [cam_] output: i32,
1506 [cam_] sensorsize: f32,
1507 [cam_] intrinsic: f32,
1508 [cam_] user: MjtNum],
1509 [[cam_] bodyid: i32,
1510 [cam_] targetbodyid: i32,
1511 [cam_] resolution: i32],
1512 []);
1513
1514info_with_view!(Model, equality,
1515 [[eq_] active0: MjtBool,
1516 [eq_] solref: MjtNum,
1517 [eq_] solimp: MjtNum,
1518 [eq_] data: MjtNum],
1519 [[eq_] r#type: MjtEq [force],
1520 [eq_] obj1id: i32,
1521 [eq_] obj2id: i32,
1522 [eq_] objtype: MjtObj [force]],
1523 []);
1524
1525info_with_view!(Model, exclude,
1526 [[exclude_] signature: i32],
1527 [],
1528 []);
1529
1530info_with_view!(Model, geom,
1531 [[geom_] contype: i32,
1532 [geom_] conaffinity: i32,
1533 [geom_] group: i32,
1534 [geom_] priority: i32, [geom_] sameframe: MjtSameFrame [force],
1535 [geom_] solmix: MjtNum, [geom_] solref: MjtNum,
1536 [geom_] solimp: MjtNum, [geom_] size: MjtNum,
1537 [geom_] aabb: MjtNum,
1538 [geom_] rbound: MjtNum, [geom_] pos: MjtNum,
1539 [geom_] quat: MjtNum, [geom_] friction: MjtNum,
1540 [geom_] margin: MjtNum, [geom_] gap: MjtNum, [geom_] fluid: MjtNum,
1541 [geom_] user: MjtNum, [geom_] rgba: f32],
1542 [[geom_] r#type: MjtGeom [force], [geom_] condim: i32,
1543 [geom_] bodyid: i32, [geom_] dataid: i32,
1544 [geom_] matid: i32, [geom_] plugin: i32],
1545 []);
1546
1547info_with_view!(Model, hfield,
1548 [[hfield_] size: MjtNum],
1549 [[hfield_] nrow: i32,
1550 [hfield_] ncol: i32,
1551 [hfield_] adr: i32,
1552 [hfield_] pathadr: i32],
1553 [[hfield_] data: f32]);
1554
1555info_with_view!(Model, joint,
1556 [qpos0: MjtNum, qpos_spring: MjtNum,
1557 [jnt_] group: i32,
1558 [jnt_] limited: MjtBool, [jnt_] actfrclimited: MjtBool, [jnt_] actgravcomp: MjtBool,
1559 [jnt_] solref: MjtNum, [jnt_] solimp: MjtNum,
1560 [jnt_] pos: MjtNum,
1561 [jnt_] axis: MjtNum, [jnt_] stiffness: MjtNum,
1562 [jnt_] stiffnesspoly: MjtNum,
1563 [jnt_] range: MjtNum, [jnt_] actfrcrange: MjtNum, [jnt_] margin: MjtNum,
1564 [jnt_] user: MjtNum,
1565 [dof_] frictionloss: MjtNum, [dof_] armature: MjtNum,
1566 [dof_] damping: MjtNum,
1567 [dof_] dampingpoly: MjtNum,
1568 [dof_] invweight0: MjtNum,
1569 [dof_] M0: MjtNum,
1570 [dof_] simplenum: i32],
1571 [[jnt_] r#type: MjtJoint [force],
1572 [jnt_] qposadr: i32,
1573 [jnt_] dofadr: i32, [jnt_] bodyid: i32, [jnt_] actuatorid: i32,
1574 dof_bodyid: i32, [dof_] jntid: i32,
1575 [dof_] parentid: i32, dof_treeid: i32,
1576 [dof_] Madr: i32],
1577 []);
1578
1579info_with_view!(Model, light,
1580 [[light_] mode: MjtCamLight [force],
1581 [light_] r#type: MjtLightType [force],
1582 [light_] castshadow: MjtBool,
1583 [light_] bulbradius: f32,
1584 [light_] intensity: f32,
1585 [light_] range: f32,
1586 [light_] active: MjtBool,
1587 [light_] pos: MjtNum,
1588 [light_] dir: MjtNum,
1589 [light_] poscom0: MjtNum,
1590 [light_] pos0: MjtNum,
1591 [light_] dir0: MjtNum,
1592 [light_] attenuation: f32,
1593 [light_] cutoff: f32,
1594 [light_] exponent: f32,
1595 [light_] ambient: f32,
1596 [light_] diffuse: f32,
1597 [light_] specular: f32],
1598 [[light_] bodyid: i32,
1599 [light_] targetbodyid: i32,
1600 [light_] texid: i32],
1601 []);
1602
1603info_with_view!(Model, material,
1604 [[mat_] texuniform: MjtBool,
1605 [mat_] texrepeat: f32,
1606 [mat_] emission: f32,
1607 [mat_] specular: f32,
1608 [mat_] shininess: f32,
1609 [mat_] reflectance: f32,
1610 [mat_] rgba: f32,
1611 [mat_] metallic: f32,
1612 [mat_] roughness: f32],
1613 [[mat_] texid: i32],
1614 []);
1615
1616info_with_view!(Model, mesh,
1617 [[mesh_] scale: MjtNum,
1618 [mesh_] pos: MjtNum,
1619 [mesh_] quat: MjtNum],
1620 [[mesh_] vertadr: i32,
1621 [mesh_] vertnum: i32,
1622 [mesh_] texcoordadr: i32,
1623 [mesh_] faceadr: i32,
1624 [mesh_] facenum: i32,
1625 [mesh_] graphadr: i32,
1626 [mesh_] normaladr: i32,
1627 [mesh_] normalnum: i32,
1628 [mesh_] texcoordnum: i32,
1629 [mesh_] bvhadr: i32,
1630 [mesh_] bvhnum: i32,
1631 [mesh_] octadr: i32,
1632 [mesh_] octnum: i32,
1633 [mesh_] pathadr: i32,
1634 [mesh_] polynum: i32,
1635 [mesh_] polyadr: i32],
1636 []);
1637
1638info_with_view!(Model, numeric,
1639 [],
1640 [[numeric_] adr: i32,
1641 [numeric_] size: i32],
1642 [[numeric_] data: MjtNum]);
1643
1644info_with_view!(Model, pair,
1645 [[pair_] solref: MjtNum,
1646 [pair_] solimp: MjtNum,
1647 [pair_] margin: MjtNum,
1648 [pair_] gap: MjtNum,
1649 [pair_] friction: MjtNum,
1650 [pair_] solreffriction: MjtNum,
1651 [pair_] signature: i32],
1652 [[pair_] dim: i32,
1653 [pair_] geom1: i32,
1654 [pair_] geom2: i32],
1655 []);
1656
1657info_with_view!(Model, sensor,
1658 [[sensor_] cutoff: MjtNum,
1659 [sensor_] noise: MjtNum,
1660 [sensor_] delay: MjtNum,
1661 [sensor_] interval: MjtNum,
1662 [sensor_] user: MjtNum,
1663 [sensor_] datatype: MjtDataType [force],
1664 [sensor_] needstage: MjtStage [force],
1665 [sensor_] intprm: i32],
1666 [[sensor_] r#type: MjtSensor [force],
1667 [sensor_] objid: i32,
1668 [sensor_] refid: i32,
1669 [sensor_] objtype: MjtObj [force],
1670 [sensor_] reftype: MjtObj [force],
1671 [sensor_] dim: i32,
1672 [sensor_] adr: i32,
1673 [sensor_] history: i32,
1674 [sensor_] historyadr: i32,
1675 [sensor_] plugin: i32],
1676 []);
1677
1678info_with_view!(Model, site,
1679 [[site_] group: i32,
1680 [site_] sameframe: MjtSameFrame [force],
1681 [site_] size: MjtNum,
1682 [site_] pos: MjtNum,
1683 [site_] quat: MjtNum,
1684 [site_] user: MjtNum,
1685 [site_] rgba: f32,
1686 [site_] r#type: MjtGeom [force]],
1687 [[site_] bodyid: i32,
1688 [site_] matid: i32],
1689 []);
1690
1691info_with_view!(Model, skin,
1692 [[skin_] group: i32,
1693 [skin_] rgba: f32,
1694 [skin_] inflate: f32],
1695 [[skin_] matid: i32,
1696 [skin_] vertadr: i32,
1697 [skin_] vertnum: i32,
1698 [skin_] texcoordadr: i32,
1699 [skin_] faceadr: i32,
1700 [skin_] facenum: i32,
1701 [skin_] boneadr: i32,
1702 [skin_] bonenum: i32,
1703 [skin_] pathadr: i32],
1704 []);
1705
1706info_with_view!(Model, tendon,
1707 [[tendon_] group: i32,
1708 [tendon_] limited: MjtBool, [tendon_] actfrclimited: MjtBool, [tendon_] width: MjtNum,
1709 [tendon_] solref_lim: MjtNum, [tendon_] solimp_lim: MjtNum,
1710 [tendon_] solref_fri: MjtNum, [tendon_] solimp_fri: MjtNum,
1711 [tendon_] range: MjtNum, [tendon_] actfrcrange: MjtNum, [tendon_] margin: MjtNum,
1712 [tendon_] stiffness: MjtNum,
1713 [tendon_] stiffnesspoly: MjtNum,
1714 [tendon_] damping: MjtNum,
1715 [tendon_] dampingpoly: MjtNum,
1716 [tendon_] armature: MjtNum,
1717 [tendon_] frictionloss: MjtNum, [tendon_] lengthspring: MjtNum,
1718 [tendon_] length0: MjtNum, [tendon_] invweight0: MjtNum,
1719 [tendon_] user: MjtNum, [tendon_] rgba: f32,
1720 [tendon_] treenum: i32],
1721 [[tendon_] matid: i32, [tendon_] actuatorid: i32, [tendon_] treeid: i32,
1722 [tendon_] adr: i32, [tendon_] num: i32,
1723 [ten_] J_rownnz: i32, [ten_] J_rowadr: i32, [ten_] J_colind: i32],
1724 []);
1725
1726info_with_view!(Model, texture,
1727 [[tex_] colorspace: MjtColorSpace [force],
1728 [tex_] r#type: MjtTexture [force]],
1729 [[tex_] height: i32,
1730 [tex_] width: i32,
1731 [tex_] nchannel: i32,
1732 [tex_] adr: MjtSize,
1733 [tex_] pathadr: i32],
1734 [[tex_] data: MjtByte]);
1735
1736info_with_view!(Model, tuple,
1737 [[tuple_] objprm: MjtNum,
1738 [tuple_] objtype: MjtObj [force]],
1739 [[tuple_] adr: i32,
1740 [tuple_] size: i32,
1741 [tuple_] objid: i32],
1742 []);
1743
1744info_with_view!(Model, key,
1745 [[key_] time: MjtNum,
1746 [key_] qpos: MjtNum,
1747 [key_] qvel: MjtNum,
1748 [key_] act: MjtNum,
1749 [key_] mpos: MjtNum,
1750 [key_] mquat: MjtNum,
1751 [key_] ctrl: MjtNum],
1752 [],
1753 []);
1754
1755#[cfg(test)]
1756#[allow(clippy::needless_range_loop)]
1758mod tests {
1759 use crate::assert_relative_eq;
1760
1761 use super::*;
1762 use std::fs;
1763
1764 const EXAMPLE_MODEL: &str = stringify!(
1765 <mujoco>
1766 <worldbody>
1767 <light name="lamp_light1"
1768 mode="fixed" type="directional" castshadow="false" bulbradius="0.5" intensity="250"
1769 range="10" active="true" pos="0 0 0" dir="0 0 -1" attenuation="0.1 0.05 0.01"
1770 cutoff="60" exponent="2" ambient="0.1 0.1 0.25" diffuse="0.5 1 1" specular="1 1.5 1"/>
1771
1772 <light name="lamp_light2"
1773 mode="fixed" type="spot" castshadow="true" bulbradius="0.2" intensity="500"
1774 range="10" active="true" pos="0 0 0" dir="0 0 -1" attenuation="0.1 0.05 0.01"
1775 cutoff="45" exponent="2" ambient="0.1 0.1 0.1" diffuse="1 1 1" specular="1 1 1"/>
1776
1777 <camera name="cam1" fovy="50" resolution="100 200"/>
1778
1779 <light ambient="0.2 0.2 0.2"/>
1780 <body name="ball">
1781 <geom name="green_sphere" pos=".2 .2 .2" size=".1" rgba="0 1 0 1"/>
1782 <joint name="ball" type="free" axis="1 1 1"/>
1783 <site name="touch" size="1" type="box"/>
1784 </body>
1785
1786 <body name="ball1" pos="-.5 0 0">
1787 <geom size=".1" rgba="0 1 0 1" mass="1"/>
1788 <joint type="free"/>
1789 <site name="ball1" size=".1 .1 .1" pos="0 0 0" rgba="0 1 0 0.2" type="box"/>
1790 <site name="ball12" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1791 <site name="ball13" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1792 </body>
1793
1794 <body name="ball2" pos=".5 0 0">
1795 <geom name="ball2" size=".5" rgba="0 1 1 1" mass="1"/>
1796 <joint name="ball2" type="free"/>
1797 <site name="ball2" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1798 <site name="ball22" size="0.5 0.25 0.5" pos="5 1 3" rgba="1 2 3 1" type="box"/>
1799 <site name="ball23" size=".1 .1 .1" pos="0 0 0" rgba="0 1 1 0.2" type="box"/>
1800 </body>
1801
1802 <geom name="floor" type="plane" size="10 10 1" euler="5 0 0"/>
1803
1804 <body name="slider">
1805 <geom name="rod" type="cylinder" size="1 10 0" euler="90 0 0" pos="0 0 10"/>
1806 <joint name="rod" type="slide" axis="0 1 0" range="0 1"/>
1807 </body>
1808
1809 <body name="ball3" pos="0 0 5">
1810 <geom name="ball31" size=".5" rgba="0 1 1 1" mass="1"/>
1811 <joint type="slide"/>
1812 </body>
1813
1814 <body name="ball32" pos="0 0 -5">
1815 <geom name="ball32" size=".5" rgba="0 1 1 1" mass="1"/>
1816 <joint type="slide"/>
1817 </body>
1818
1819 <body name="eq_body1" pos="0 0 0">
1820 <geom size="0.1"/>
1821 </body>
1822 <body name="eq_body2" pos="1 0 0">
1823 <geom size="0.1"/>
1824 </body>
1825 <body name="eq_body3" pos="0 0 0">
1826 <geom size="0.1"/>
1827 </body>
1828 <body name="eq_body4" pos="1 0 0">
1829 <geom size="0.1"/>
1830 </body>
1831 </worldbody>
1832
1833
1834 <equality>
1835 <connect name="eq1" body1="eq_body1" body2="eq_body2" anchor="15 0 10"/>
1836 <connect name="eq2" body1="eq_body2" body2="eq_body1" anchor="-5 0 10"/>
1837 <connect name="eq3" body1="eq_body3" body2="eq_body4" anchor="0 5 0"/>
1838 <connect name="eq4" body1="eq_body4" body2="eq_body3" anchor="5 5 10"/>
1839 </equality>
1840
1841
1842 <actuator>
1843 <general name="slider" joint="rod" biastype="affine" ctrlrange="0 1" dynprm="1 2 3 4 5 6 7 8 9 10" gaintype="fixed"/>
1844 <general name="slider2" joint="ball2" biastype="affine" ctrlrange="0 1" dynprm="10 9 8 7 6 5 4 3 2 1" gaintype="fixed"/>
1845 </actuator>
1846
1847 <sensor>
1848 <touch name="touch" site="touch"/>
1849 </sensor>
1850
1851 <tendon>
1852 <spatial name="tendon1" limited="false" range="0 5" rgba="0 .5 2 3" width=".5">
1853 <site site="ball1"/>
1854 <site site="ball2"/>
1855 </spatial>
1856 </tendon>
1857
1858 <tendon>
1859 <spatial name="tendon2" limited="true" range="0 1" rgba="0 .1 1 1" width=".005">
1860 <site site="ball1"/>
1861 <site site="ball2"/>
1862 </spatial>
1863 </tendon>
1864
1865 <tendon>
1866 <spatial name="tendon3" limited="false" range="0 5" rgba=".5 .2 .4 .3" width=".25">
1867 <site site="ball1"/>
1868 <site site="ball2"/>
1869 </spatial>
1870 </tendon>
1871
1872 <!-- Contact pair between the two geoms -->
1873 <contact>
1874 <pair name="geom_pair" geom1="ball31" geom2="ball32" condim="3" solref="0.02 1"
1875 solreffriction="0.01 0.5" solimp="0.0 0.95 0.001 0.5 2" margin="0.001" gap="0"
1876 friction="1.0 0.8 0.6 0.0 0.0">
1877 </pair>
1878 </contact>
1879
1880 <!-- A keyframe with qpos/qvel/ctrl etc. -->
1881 <keyframe>
1882 <!-- adjust nq/nv/nu in <default> or body definitions to match
1883 lengths in your test constants -->
1884 <key name="pose0"
1885 time="0.0"
1886 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"
1887 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"
1888 ctrl="0.5 0.5"/>
1889 <key name="pose1"
1890 time="1.5"
1891 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"
1892 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"
1893 ctrl="0.5 0.0"/>
1894 </keyframe>
1895
1896 <custom>
1897 <tuple name="tuple_example">
1898 <!-- First entry: a body -->
1899 <element objtype="body" objname="ball2" prm="0.5"/>
1900 <!-- Second entry: a site -->
1901 <element objtype="site" objname="ball1" prm="1.0"/>
1902 </tuple>
1903
1904 <!-- Numeric element with a single value -->
1905 <numeric name="gain_factor1" size="5" data="3.14159 0 0 0 3.14159"/>
1906 <numeric name="gain_factor2" size="3" data="1.25 5.5 10.0"/>
1907 </custom>
1908
1909 <!-- Texture definition -->
1910 <asset>
1911 <texture name="wall_tex"
1912 type="2d"
1913 colorspace="sRGB"
1914 width="128"
1915 height="128"
1916 nchannel="3"
1917 builtin="flat"
1918 rgb1="0.6 0.6 0.6"
1919 rgb2="0.6 0.6 0.6"
1920 mark="none"/>
1921
1922 <!-- Material definition -->
1923 <material name="wood_material"
1924 rgba="0.8 0.5 0.3 1"
1925 emission="0.1"
1926 specular="0.5"
1927 shininess="0.7"
1928 reflectance="0.2"
1929 metallic="0.3"
1930 roughness="0.4"
1931 texuniform="true"
1932 texrepeat="2 2"/>
1933
1934 <!-- Material definition -->
1935 <material name="also_wood_material"
1936 rgba="0.8 0.5 0.3 1"
1937 emission="0.1"
1938 specular="0.5"
1939 shininess="0.7"
1940 reflectance="0.2"
1941 metallic="0.3"
1942 roughness="0.5"
1943 texuniform="false"
1944 texrepeat="2 2"/>
1945
1946 <hfield name="hf1" nrow="2" ncol="3" size="1 1 1 0.1"/>
1947 <hfield name="hf2" nrow="5" ncol="3" size="1 1 1 5.25"/>
1948 <hfield name="hf3" nrow="2" ncol="3" size="1 1 1 0.1"/>
1949 </asset>
1950 </mujoco>
1951);
1952
1953 #[test]
1955 fn test_model_load_save() {
1956 const MODEL_SAVE_XML_PATH: &str = "./__TMP_MODEL1.xml";
1957 const MODEL_INVALID_SAVE_XML_PATH: &str = "/some/non-existent/path/";
1958
1959 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1960 model.save_last_xml(MODEL_SAVE_XML_PATH).expect("could not save the model XML.");
1961 fs::remove_file(MODEL_SAVE_XML_PATH).unwrap();
1962
1963 assert!(model.save_last_xml(MODEL_INVALID_SAVE_XML_PATH).is_err());
1965 }
1966
1967 #[test]
1968 fn test_actuator_model_view() {
1969 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
1970 let actuator_model_info = model.actuator("slider").unwrap();
1971 let view = actuator_model_info.view(&model);
1972
1973 assert_eq!(view.biastype[0], MjtBias::mjBIAS_AFFINE);
1975 assert_eq!(&view.ctrlrange[..], [0.0, 1.0]);
1976 assert!(view.ctrllimited[0]);
1977 assert!(!view.forcelimited[0]);
1978 assert_eq!(view.trntype[0], MjtTrn::mjTRN_JOINT);
1979 assert_eq!(view.gaintype[0], MjtGain::mjGAIN_FIXED);
1980
1981 assert_eq!(view.dynprm[..], model.actuator_dynprm()[actuator_model_info.id]);
1983
1984 let mut view_mut = actuator_model_info.view_mut(&mut model);
1986 view_mut.gaintype[0] = MjtGain::mjGAIN_AFFINE;
1987 view_mut.delay[0] = 3.0;
1988
1989 assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_AFFINE);
1990 assert_eq!(view_mut.delay[0], 3.0);
1991 view_mut.zero();
1992
1993 assert_eq!(view_mut.delay[0], 0.0);
1994 assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_FIXED);
1995 }
1996
1997 #[test]
1998 fn test_sensor_model_view() {
1999 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2000 let sensor_model_info = model.sensor("touch").unwrap();
2001 let view = sensor_model_info.view(&model);
2002
2003 assert_eq!(view.dim[0], 1);
2005 assert_eq!(view.objtype[0], MjtObj::mjOBJ_SITE);
2006 assert_eq!(view.noise[0], 0.0);
2007 assert_eq!(view.r#type[0], MjtSensor::mjSENS_TOUCH);
2008
2009 let mut view_mut = sensor_model_info.view_mut(&mut model);
2011 view_mut.noise[0] = 1.0;
2012 assert_eq!(view_mut.noise[0], 1.0);
2013 }
2014
2015 #[test]
2016 fn test_tendon_model_view() {
2017 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2018 let tendon_model_info = model.tendon("tendon2").unwrap();
2019 let view = tendon_model_info.view(&model);
2020
2021 assert_eq!(&view.range[..], [0.0, 1.0]);
2023 assert!(view.limited[0]);
2024 assert_eq!(view.width[0], 0.005);
2025
2026 let tendon_id = tendon_model_info.id;
2028 assert_eq!(view.width[0], model.tendon_width()[tendon_id]);
2029 assert_eq!(*view.range, model.tendon_range()[tendon_id]);
2030 assert_eq!(view.limited[0], model.tendon_limited()[tendon_id]);
2031
2032 let mut view_mut = tendon_model_info.view_mut(&mut model);
2034 view_mut.frictionloss[0] = 5e-2;
2035 assert_eq!(view_mut.frictionloss[0], 5e-2);
2036 }
2037
2038 #[test]
2039 fn test_joint_model_view() {
2040 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2041 let model_info = model.joint("rod").unwrap();
2042 let view = model_info.view(&model);
2043
2044 assert_eq!(view.r#type[0], MjtJoint::mjJNT_SLIDE);
2046 assert!(view.limited[0]);
2047 assert_eq!(&view.axis[..], [0.0, 1.0 , 0.0]);
2048 assert!(!view.dof_bodyid.is_empty());
2049 assert!(!view.dof_treeid.is_empty());
2050
2051 let dof_start = model.jnt_dofadr()[model_info.id] as usize;
2052 assert_eq!(view.dof_bodyid[0], model.dof_bodyid()[dof_start]);
2053 assert_eq!(view.dof_treeid[0], model.dof_treeid()[dof_start]);
2054
2055 let free_info = model.joint("ball2").unwrap();
2057 let free_view = free_info.view(&model);
2058 assert!(free_view.dof_bodyid.len() > 1);
2059 assert_eq!(free_view.dof_bodyid.len(), free_view.dof_treeid.len());
2060
2061 let free_dof_start = model.jnt_dofadr()[free_info.id] as usize;
2062 let free_dof_end = free_dof_start + free_view.dof_bodyid.len();
2063 assert_eq!(&free_view.dof_bodyid[..], &model.dof_bodyid()[free_dof_start..free_dof_end]);
2064 assert_eq!(&free_view.dof_treeid[..], &model.dof_treeid()[free_dof_start..free_dof_end]);
2065
2066 let mut view_mut = model_info.view_mut(&mut model);
2068 view_mut.axis.copy_from_slice(&[1.0, 0.0, 0.0]);
2069 assert_eq!(&view_mut.axis[..], [1.0, 0.0 , 0.0]);
2070 }
2071
2072 #[test]
2073 fn test_geom_model_view() {
2074 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2075 let model_info = model.geom("ball2").unwrap();
2076 let view = model_info.view(&model);
2077
2078 assert_eq!(view.r#type[0], MjtGeom::mjGEOM_SPHERE);
2080 assert_eq!(view.size[0], 0.5);
2081
2082 let mut view_mut = model_info.view_mut(&mut model);
2084 view_mut.size[0] = 1.0;
2085 assert_eq!(view_mut.size[0], 1.0);
2086 }
2087
2088 #[test]
2089 fn test_body_model_view() {
2090 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2091 let model_info = model.body("ball2").unwrap();
2092 let view = model_info.view(&model);
2093
2094 assert_eq!(view.pos[0], 0.5);
2096
2097 let body_id = model_info.id;
2099 assert_eq!(model.body_sameframe()[body_id], view.sameframe[0]);
2100
2101 let mut view_mut = model_info.view_mut(&mut model);
2103 view_mut.pos[0] = 1.0;
2104 assert_eq!(view_mut.pos[0], 1.0);
2105 }
2106
2107 #[test]
2108 fn test_try_view_model_signature_mismatch() {
2109 let model1 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint type='free'/><geom size='0.1'/></body></worldbody></mujoco>").unwrap();
2110 let mut model2 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint type='free'/><geom size='0.1'/></body><body name='extra'/></worldbody></mujoco>").unwrap();
2111
2112 let body_info = model1.body("b1").unwrap();
2113
2114 let err = body_info.try_view(&model2).unwrap_err();
2115 match err {
2116 MjModelError::SignatureMismatch { source, destination } => {
2117 assert_eq!(source, model1.signature());
2118 assert_eq!(destination, model2.signature());
2119 }
2120 other => panic!("expected SignatureMismatch, got {other:?}"),
2121 }
2122
2123 let err = body_info.try_view_mut(&mut model2).unwrap_err();
2124 match err {
2125 MjModelError::SignatureMismatch { source, destination } => {
2126 assert_eq!(source, model1.signature());
2127 assert_eq!(destination, model2.signature());
2128 }
2129 other => panic!("expected SignatureMismatch, got {other:?}"),
2130 }
2131 }
2132
2133 #[test]
2134 #[should_panic(expected = "model signature mismatch")]
2135 fn test_view_mut_model_signature_mismatch_panics() {
2136 let model1 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint type='free'/><geom size='0.1'/></body></worldbody></mujoco>").unwrap();
2137 let mut model2 = MjModel::from_xml_string("<mujoco><worldbody><body name='b1'><joint type='free'/><geom size='0.1'/></body><body name='extra'/></worldbody></mujoco>").unwrap();
2138
2139 let body_info = model1.body("b1").unwrap();
2140 let _view = body_info.view_mut(&mut model2);
2141 }
2142
2143
2144 #[test]
2145 fn test_camera_model_view() {
2146 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2147 let model_info = model.camera("cam1").unwrap();
2148 let view = model_info.view(&model);
2149
2150 assert_eq!(&view.resolution[..], [100, 200]);
2152 assert_eq!(view.fovy[0], 50.0);
2153
2154 let mut view_mut = model_info.view_mut(&mut model);
2156 view_mut.fovy[0] = 60.0;
2157 assert_eq!(view_mut.fovy[0], 60.0);
2158 }
2159
2160 #[test]
2161 fn test_id_2name_valid() {
2162 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2163
2164 let name = model.id_to_name(MjtObj::mjOBJ_BODY, 1);
2166 assert_eq!(name, Some("ball"));
2167 }
2168
2169 #[test]
2170 fn test_model_prints() {
2171 const TMP_FILE: &str = "tmpprint.txt";
2172 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2173 assert!(model.print(TMP_FILE).is_ok());
2174 fs::remove_file(TMP_FILE).unwrap();
2175
2176 assert!(model.print_formatted(TMP_FILE, "%.2f").is_ok());
2177 fs::remove_file(TMP_FILE).unwrap();
2178 }
2179
2180 #[test]
2181 fn test_id_2name_invalid() {
2182 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2183
2184 let name = model.id_to_name(MjtObj::mjOBJ_BODY, 9999);
2186 assert_eq!(name, None);
2187 }
2188
2189 #[test]
2190 fn test_totalmass_set_and_get() {
2191 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2192
2193 let mass_before = model.totalmass();
2194 model.set_totalmass(5.0);
2195 let mass_after = model.totalmass();
2196
2197 assert_relative_eq!(mass_after, 5.0, epsilon = 1e-9);
2198 assert_ne!(mass_before, mass_after);
2199 }
2200
2201 #[test]
2203 fn test_copy_model() {
2204 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2205 let _cloned = model.clone();
2206 }
2207
2208 #[test]
2209 fn test_model_save() {
2210 const MODEL_SAVE_PATH: &str = "./__TMP_MODEL2.mjb";
2211 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2212 model.save_to_file(MODEL_SAVE_PATH).unwrap();
2213
2214 let saved_data = fs::read(MODEL_SAVE_PATH).unwrap();
2215 let mut data = vec![0; saved_data.len()];
2216 model.save_to_buffer(&mut data).unwrap();
2217
2218 assert_eq!(saved_data, data);
2219 fs::remove_file(MODEL_SAVE_PATH).unwrap();
2220
2221 let model = MjModel::from_buffer(&saved_data).unwrap();
2223 assert!(model.light("lamp_light2").is_some());
2224 assert!(model.light("lamp_light-xyz").is_none());
2225 }
2226
2227 #[test]
2228 fn test_site_view() {
2229 const BODY_NAME: &str = "ball2";
2231 const SITE_NAME: &str = "ball22";
2232 const SITE_SIZE: [f64; 3] = [0.5, 0.25, 0.5];
2233 const SITE_POS: [f64; 3] = [5.0, 1.0, 3.0];
2234 const SITE_RGBA: [f32; 4] = [1.0, 2.0, 3.0, 1.0];
2235 const SITE_TYPE: MjtGeom = MjtGeom::mjGEOM_BOX;
2236
2237 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
2238 let info_ball = model.body(BODY_NAME).unwrap();
2239 let info_site = model.site(SITE_NAME).unwrap();
2240 let view_site = info_site.view(&model);
2241
2242 assert_eq!(info_site.name, SITE_NAME);
2244 assert_eq!(view_site.size[..], SITE_SIZE);
2245 assert_eq!(view_site.pos[..], SITE_POS);
2246 assert_eq!(view_site.rgba[..], SITE_RGBA);
2247 assert_eq!(view_site.r#type[0], SITE_TYPE);
2248
2249 assert_eq!(view_site.bodyid[0] as usize, info_ball.id)
2250 }
2251
2252 #[test]
2253 fn test_pair_view() {
2254 const PAIR_NAME: &str = "geom_pair";
2255 const DIM: i32 = 3;
2256 const GEOM1_NAME: &str = "ball31";
2257 const GEOM2_NAME: &str = "ball32";
2258 const SOLREF: [f64; mjNREF as usize] = [0.02, 1.0];
2259 const SOLREFFRICTION: [f64; mjNREF as usize] = [0.01, 0.5];
2260 const SOLIMP: [f64; mjNIMP as usize] = [0., 0.95, 0.001, 0.5, 2.0];
2261 const MARGIN: f64 = 0.001;
2262 const GAP: f64 = 0.0;
2263 const FRICTION: [f64; 5] = [1.0, 0.8, 0.6, 0.0, 0.0];
2264
2265 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2266 let info_pair = model.pair(PAIR_NAME).unwrap();
2267 let view_pair = info_pair.view(&model);
2268
2269 let geom1_info = model.geom(GEOM1_NAME).unwrap();
2270 let geom2_info = model.geom(GEOM2_NAME).unwrap();
2271
2272 let signature = ((geom1_info.view(&model).bodyid[0] as u32) << 16) + geom2_info.view(&model).bodyid[0] as u32;
2274
2275 assert_eq!(view_pair.dim[0], DIM);
2276 assert_eq!(view_pair.geom1[0] as usize, geom1_info.id);
2277 assert_eq!(view_pair.geom2[0] as usize, geom2_info.id);
2278 assert_eq!(view_pair.signature[0] as u32, signature);
2279 assert_eq!(view_pair.solref[..], SOLREF);
2280 assert_eq!(view_pair.solreffriction[..], SOLREFFRICTION);
2281 assert_eq!(view_pair.solimp[..], SOLIMP);
2282 assert_eq!(view_pair.margin[0], MARGIN);
2283 assert_eq!(view_pair.gap[0], GAP);
2284 assert_eq!(view_pair.friction[..], FRICTION);
2285 }
2286
2287 #[test]
2288 fn test_key_view() {
2289 const KEY_NAME: &str = "pose1";
2290 const TIME: f64 = 1.5;
2291 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];
2292 const ACT: &[f64] = &[];
2293 const CTRL: &[f64] = &[0.5, 0.0];
2294
2295 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2296 let info_key = model.key(KEY_NAME).unwrap();
2297 let view_key = info_key.view(&model);
2298
2299 assert_eq!(view_key.time[0], TIME);
2300 assert_eq!(&view_key.qvel[..model.ffi().nv as usize], QVEL);
2303 assert_eq!(&view_key.act[..model.ffi().na as usize], ACT);
2304 assert_eq!(&view_key.ctrl[..model.ffi().nu as usize], CTRL);
2305
2306 let key_qvel = &model.key_qvel()[model.ffi().nv as usize..];
2307 assert_eq!(key_qvel, QVEL);
2308
2309 let key_act = &model.key_act()[model.ffi().na as usize..];
2310 assert_eq!(key_act, ACT);
2311
2312 let key_ctrl = &model.key_ctrl()[model.ffi().nu as usize..];
2313 assert_eq!(key_ctrl, CTRL);
2314 }
2315
2316 #[test]
2317 fn test_tuple_view() {
2318 const TUPLE_NAME: &str = "tuple_example";
2319 const SIZE: i32 = 2;
2320 const OBJTYPE: &[MjtObj] = &[MjtObj::mjOBJ_BODY, MjtObj::mjOBJ_SITE];
2321 const OBJPRM: &[f64] = &[0.5, 1.0];
2322
2323 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2324 let info_tuple = model.tuple(TUPLE_NAME).unwrap();
2325 let view_tuple = info_tuple.view(&model);
2326
2327 let objid = &[
2328 model.body("ball2").unwrap().id as i32,
2329 model.site("ball1").unwrap().id as i32,
2330 ];
2331
2332 assert_eq!(view_tuple.size[0], SIZE);
2333 assert_eq!(&view_tuple.objtype[..SIZE as usize], OBJTYPE);
2334 assert_eq!(&view_tuple.objid[..SIZE as usize], objid);
2335 assert_eq!(&view_tuple.objprm[..SIZE as usize], OBJPRM);
2336 }
2337
2338 #[test]
2339 fn test_texture_view() {
2340 const TEX_NAME: &str = "wall_tex";
2341 const TYPE: MjtTexture = MjtTexture::mjTEXTURE_2D; const COLORSPACE: MjtColorSpace = MjtColorSpace::mjCOLORSPACE_SRGB; const HEIGHT: i32 = 128;
2344 const WIDTH: i32 = 128;
2345 const NCHANNEL: i32 = 3;
2346
2347 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2348 let info_tex = model.texture(TEX_NAME).unwrap();
2349 let view_tex = info_tex.view(&model);
2350
2351 assert_eq!(view_tex.r#type[0], TYPE);
2352 assert_eq!(view_tex.colorspace[0], COLORSPACE);
2353 assert_eq!(view_tex.height[0], HEIGHT);
2354 assert_eq!(view_tex.width[0], WIDTH);
2355 assert_eq!(view_tex.nchannel[0], NCHANNEL);
2356
2357 assert_eq!(view_tex.data.as_ref().unwrap().len(), (WIDTH * HEIGHT * NCHANNEL) as usize);
2358 }
2359
2360 #[test]
2361 fn test_numeric_view() {
2362 const NUMERIC_NAME: &str = "gain_factor2";
2363 const SIZE: i32 = 3;
2364 const DATA: [f64; 3] = [1.25, 5.5, 10.0];
2365
2366 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2367 let info_numeric = model.numeric(NUMERIC_NAME).unwrap();
2368 let view_numeric = info_numeric.view(&model);
2369
2370 assert_eq!(view_numeric.size[0], SIZE);
2371 assert_eq!(&view_numeric.data.as_ref().unwrap()[..SIZE as usize], DATA);
2372 }
2373
2374 #[test]
2375 fn test_material_view() {
2376 const MATERIAL_NAME: &str = "also_wood_material";
2377
2378 const TEXUNIFORM: bool = false;
2379 const TEXREPEAT: [f32; 2] = [2.0, 2.0];
2380 const EMISSION: f32 = 0.1;
2381 const SPECULAR: f32 = 0.5;
2382 const SHININESS: f32 = 0.7;
2383 const REFLECTANCE: f32 = 0.2;
2384 const METALLIC: f32 = 0.3;
2385 const ROUGHNESS: f32 = 0.5;
2386 const RGBA: [f32; 4] = [0.8, 0.5, 0.3, 1.0];
2387 const TEXID: i32 = -1;
2388
2389 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2390 let info_material = model.material(MATERIAL_NAME).unwrap();
2391 let view_material = info_material.view(&model);
2392
2393 assert_eq!(view_material.texuniform[0], TEXUNIFORM);
2394 assert_eq!(view_material.texrepeat[..], TEXREPEAT);
2395 assert_eq!(view_material.emission[0], EMISSION);
2396 assert_eq!(view_material.specular[0], SPECULAR);
2397 assert_eq!(view_material.shininess[0], SHININESS);
2398 assert_eq!(view_material.reflectance[0], REFLECTANCE);
2399 assert_eq!(view_material.metallic[0], METALLIC);
2400 assert_eq!(view_material.roughness[0], ROUGHNESS);
2401 assert_eq!(view_material.rgba[..], RGBA);
2402 assert_eq!(view_material.texid[0], TEXID);
2403 }
2404
2405 #[test]
2406 fn test_light_view() {
2407 const LIGHT_NAME: &str = "lamp_light2";
2408 const MODE: MjtCamLight = MjtCamLight::mjCAMLIGHT_FIXED;
2409 const BODYID: usize = 0; const TYPE: MjtLightType = MjtLightType::mjLIGHT_SPOT; const CASTSHADOW: bool = true;
2412 const ACTIVE: bool = true;
2413
2414 const POS: [MjtNum; 3] = [0.0, 0.0, 0.0];
2415 const DIR: [MjtNum; 3] = [0.0, 0.0, -1.0];
2416 const POS0: [MjtNum; 3] = [0.0, 0.0, 0.0];
2417 const DIR0: [MjtNum; 3] = [0.0, 0.0, -1.0];
2418 const ATTENUATION: [f32; 3] = [0.1, 0.05, 0.01];
2419 const CUTOFF: f32 = 45.0;
2420 const EXPONENT: f32 = 2.0;
2421 const AMBIENT: [f32; 3] = [0.1, 0.1, 0.1];
2422 const DIFFUSE: [f32; 3] = [1.0, 1.0, 1.0];
2423 const SPECULAR: [f32; 3] = [1.0, 1.0, 1.0];
2424
2425 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2426 let info_light = model.light(LIGHT_NAME).unwrap();
2427 let view_light = info_light.view(&model);
2428
2429 assert_eq!(view_light.mode[0], MODE);
2430 assert_eq!(view_light.bodyid[0] as usize, BODYID);
2431 assert_eq!(view_light.targetbodyid[0], -1);
2432 assert_eq!(view_light.r#type[0], TYPE);
2433 assert_eq!(view_light.castshadow[0], CASTSHADOW);
2434 assert_eq!(view_light.active[0], ACTIVE);
2435
2436 assert_eq!(view_light.pos[..], POS);
2437 assert_eq!(view_light.dir[..], DIR);
2438 assert_eq!(view_light.pos0[..], POS0);
2439 assert_eq!(view_light.dir0[..], DIR0);
2440 assert_eq!(view_light.attenuation[..], ATTENUATION);
2441 assert_eq!(view_light.cutoff[0], CUTOFF);
2442 assert_eq!(view_light.exponent[0], EXPONENT);
2443 assert_eq!(view_light.ambient[..], AMBIENT);
2444 assert_eq!(view_light.diffuse[..], DIFFUSE);
2445 assert_eq!(view_light.specular[..], SPECULAR);
2446 }
2447
2448 #[test]
2449 fn test_connect_eq_view() {
2450 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2451
2452 let info_eq = model.equality("eq3").unwrap();
2454 let view_eq = info_eq.view(&model);
2455
2456 assert_eq!(view_eq.r#type[0], MjtEq::mjEQ_CONNECT);
2458
2459 assert_eq!(view_eq.obj1id[0], model.name_to_id(MjtObj::mjOBJ_BODY, "eq_body3").unwrap() as i32);
2461 assert_eq!(view_eq.obj2id[0], model.name_to_id(MjtObj::mjOBJ_BODY, "eq_body4").unwrap() as i32);
2462 assert_eq!(view_eq.objtype[0], MjtObj::mjOBJ_BODY);
2463
2464 assert!(view_eq.active0[0]);
2466
2467 let anchor = &view_eq.data[0..3];
2469 assert_eq!(anchor[0], 0.0);
2470 assert_eq!(anchor[1], 5.0);
2471 assert_eq!(anchor[2], 0.0);
2472 }
2473
2474 #[test]
2475 fn test_hfield_view() {
2476 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2477
2478 let info_hf = model.hfield("hf2").unwrap();
2480 let view_hf = info_hf.view(&model);
2481
2482 let expected_size: [f64; 4] = [1.0, 1.0, 1.0, 5.25]; let expected_nrow = 5;
2485 let expected_ncol = 3;
2486 let expected_data: [f32; 15] = [0.0; 15];
2487
2488 assert_eq!(view_hf.size[..], expected_size);
2490 assert_eq!(view_hf.nrow[0], expected_nrow);
2491 assert_eq!(view_hf.ncol[0], expected_ncol);
2492
2493 assert_eq!(view_hf.data.as_ref().unwrap().len(), (expected_nrow * expected_ncol) as usize);
2495 assert_eq!(&view_hf.data.as_ref().unwrap()[..], &expected_data[..]);
2496
2497 assert_eq!(view_hf.pathadr[0], -1);
2499 }
2500
2501 #[test]
2503 fn test_state_extract() {
2504 use crate::wrappers::mj_data::MjtState;
2505
2506 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2507 let data = MjData::new(&model);
2508
2509 let state_full_physics = data.state(MjtState::mjSTATE_FULLPHYSICS as u32);
2513 let state_physics = data.state(MjtState::mjSTATE_PHYSICS as u32);
2514
2515 let required_size = model.state_size(MjtState::mjSTATE_PHYSICS as u32);
2516 let mut dst_buffer = vec![0.0; required_size].into_boxed_slice();
2517 let _bytes_written = model.extract_state_into(
2518 &state_full_physics, MjtState::mjSTATE_FULLPHYSICS as u32,
2519 &mut dst_buffer, MjtState::mjSTATE_PHYSICS as u32
2520 );
2521
2522 assert_eq!(state_physics, dst_buffer);
2523
2524 let state_full_physics = data.state(MjtState::mjSTATE_FULLPHYSICS as u32);
2528 let state_physics = data.state(MjtState::mjSTATE_PHYSICS as u32);
2529
2530 let dst_buffer = model.extract_state(
2531 &state_full_physics, MjtState::mjSTATE_FULLPHYSICS as u32,
2532 MjtState::mjSTATE_PHYSICS as u32
2533 );
2534
2535 assert_eq!(state_physics, dst_buffer);
2536 }
2537
2538 #[test]
2542 fn test_state_extract_state_invalid_src() {
2543 use crate::wrappers::mj_data::MjtState;
2544
2545 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2546 let data = MjData::new(&model);
2547
2548 let state_full_physics = data.state(MjtState::mjSTATE_PHYSICS as u32);
2549 let res = model.try_extract_state(
2550 &state_full_physics, MjtState::mjSTATE_FULLPHYSICS as u32,
2551 MjtState::mjSTATE_PHYSICS as u32
2552 );
2553
2554 let err = res.unwrap_err();
2555 assert!(matches!(err, MjModelError::StateSliceLengthMismatch { .. }));
2556 }
2557
2558 #[test]
2559 fn test_state_extract_state_into_invalid_src() {
2560 use crate::wrappers::mj_data::MjtState;
2561
2562 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2563 let data = MjData::new(&model);
2564
2565 let required_size = model.state_size(MjtState::mjSTATE_PHYSICS as u32);
2566 let mut dst_buffer = vec![0.0; required_size].into_boxed_slice();
2567 let state_full_physics = data.state(MjtState::mjSTATE_PHYSICS as u32);
2568 let res = model.try_extract_state_into(
2569 &state_full_physics, MjtState::mjSTATE_FULLPHYSICS as u32,
2570 &mut dst_buffer, MjtState::mjSTATE_PHYSICS as u32
2571 );
2572
2573 let err = res.unwrap_err();
2574 assert!(matches!(err, MjModelError::StateSliceLengthMismatch { .. }));
2575 }
2576
2577 #[test]
2578 fn test_state_extract_dst_spec_not_subset() {
2579 use crate::wrappers::mj_data::MjtState;
2580
2581 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2582 let data = MjData::new(&model);
2583
2584 let state_physics = data.state(MjtState::mjSTATE_PHYSICS as u32);
2585 let res = model.try_extract_state(
2586 &state_physics, MjtState::mjSTATE_PHYSICS as u32,
2587 MjtState::mjSTATE_FULLPHYSICS as u32
2588 );
2589
2590 let err = res.unwrap_err();
2591 assert!(matches!(err, MjModelError::SpecNotSubset));
2592 }
2593
2594 #[test]
2595 fn test_state_extract_into_dst_spec_not_subset() {
2596 use crate::wrappers::mj_data::MjtState;
2597
2598 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2599 let data = MjData::new(&model);
2600
2601 let state_physics = data.state(MjtState::mjSTATE_PHYSICS as u32);
2602 let mut dst = vec![0.0; model.state_size(MjtState::mjSTATE_PHYSICS as u32)];
2603
2604 let res = model.try_extract_state_into(
2605 &state_physics, MjtState::mjSTATE_PHYSICS as u32,
2606 &mut dst, MjtState::mjSTATE_FULLPHYSICS as u32
2607 );
2608
2609 let err = res.unwrap_err();
2610 assert!(matches!(err, MjModelError::SpecNotSubset));
2611 }
2612
2613 #[test]
2614 fn test_state_extract_into_dst_buffer_too_small() {
2615 use crate::wrappers::mj_data::MjtState;
2616
2617 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2618 let data = MjData::new(&model);
2619
2620 let state_full = data.state(MjtState::mjSTATE_FULLPHYSICS as u32);
2621 let required = model.state_size(MjtState::mjSTATE_PHYSICS as u32);
2622 let mut dst = vec![0.0; required.saturating_sub(1)];
2624
2625 let res = model.try_extract_state_into(
2626 &state_full, MjtState::mjSTATE_FULLPHYSICS as u32,
2627 &mut dst, MjtState::mjSTATE_PHYSICS as u32
2628 );
2629
2630 let err = res.unwrap_err();
2631 assert!(matches!(err, MjModelError::BufferTooSmall { .. }));
2632 }
2633
2634 #[test]
2635 fn test_state_extract_zero_spec() {
2636 use crate::wrappers::mj_data::MjtState;
2637
2638 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2639 let data = MjData::new(&model);
2640
2641 let state_full = data.state(MjtState::mjSTATE_FULLPHYSICS as u32);
2642
2643 let dst = model.extract_state(&state_full, MjtState::mjSTATE_FULLPHYSICS as u32, 0u32);
2645 assert!(dst.is_empty());
2646
2647 let buf: &mut [f64] = &mut [];
2649 let written = model.extract_state_into(&state_full, MjtState::mjSTATE_FULLPHYSICS as u32, buf, 0u32);
2650 assert_eq!(written, 0);
2651 }
2652
2653 #[test]
2660 fn test_force_cast_body_model_arrays() {
2661 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2662 let nbody = model.ffi().nbody as usize;
2663
2664 let body_pos = model.body_pos();
2665 let body_quat = model.body_quat();
2666 let body_inertia = model.body_inertia();
2667 let body_invweight0 = model.body_invweight0();
2668 let body_ipos = model.body_ipos();
2669 let body_iquat = model.body_iquat();
2670
2671 assert_eq!(body_pos.len(), nbody);
2672 assert_eq!(body_quat.len(), nbody);
2673 assert_eq!(body_inertia.len(), nbody);
2674 assert_eq!(body_invweight0.len(), nbody);
2675 assert_eq!(body_ipos.len(), nbody);
2676 assert_eq!(body_iquat.len(), nbody);
2677
2678 for i in 0..nbody {
2680 for j in 0..3 {
2681 assert_eq!(body_pos[i][j], unsafe { *model.ffi().body_pos.add(i * 3 + j) },
2682 "body_pos[{}][{}] mismatch", i, j);
2683 }
2684 for j in 0..4 {
2685 assert_eq!(body_quat[i][j], unsafe { *model.ffi().body_quat.add(i * 4 + j) },
2686 "body_quat[{}][{}] mismatch", i, j);
2687 }
2688 for j in 0..3 {
2689 assert_eq!(body_inertia[i][j], unsafe { *model.ffi().body_inertia.add(i * 3 + j) },
2690 "body_inertia[{}][{}] mismatch", i, j);
2691 }
2692 for j in 0..2 {
2693 assert_eq!(body_invweight0[i][j], unsafe { *model.ffi().body_invweight0.add(i * 2 + j) },
2694 "body_invweight0[{}][{}] mismatch", i, j);
2695 }
2696 }
2697 }
2698
2699 #[test]
2701 fn test_force_cast_jnt_type_enum() {
2702 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2703 let njnt = model.ffi().njnt as usize;
2704 let jnt_type = model.jnt_type();
2705
2706 assert_eq!(jnt_type.len(), njnt);
2707
2708 for i in 0..njnt {
2710 let raw_i32 = unsafe { *model.ffi().jnt_type.add(i) };
2711 let expected: MjtJoint = unsafe { crate::util::force_cast(raw_i32) };
2712 assert_eq!(jnt_type[i], expected,
2713 "jnt_type[{}]: got {:?}, expected {:?} (raw={})", i, jnt_type[i], expected, raw_i32);
2714 }
2715
2716 let ball_jnt = model.joint("ball").unwrap();
2718 assert_eq!(jnt_type[ball_jnt.id], MjtJoint::mjJNT_FREE);
2719
2720 let rod_jnt = model.joint("rod").unwrap();
2721 assert_eq!(jnt_type[rod_jnt.id], MjtJoint::mjJNT_SLIDE);
2722 }
2723
2724 #[test]
2726 fn test_force_cast_jnt_limited_bool() {
2727 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2728 let njnt = model.ffi().njnt as usize;
2729 let jnt_limited = model.jnt_limited();
2730
2731 assert_eq!(jnt_limited.len(), njnt);
2732
2733 for i in 0..njnt {
2735 let raw_bool = unsafe { *model.ffi().jnt_limited.add(i) };
2736 assert_eq!(jnt_limited[i], raw_bool,
2737 "jnt_limited[{}] mismatch: bool={}, raw={}", i, jnt_limited[i], raw_bool);
2738 }
2739
2740 let rod_jnt = model.joint("rod").unwrap();
2742 assert!(jnt_limited[rod_jnt.id]);
2743
2744 let ball_jnt = model.joint("ball").unwrap();
2745 assert!(!jnt_limited[ball_jnt.id]);
2746 }
2747
2748 #[test]
2750 fn test_force_cast_geom_type_enum() {
2751 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2752 let ngeom = model.ffi().ngeom as usize;
2753 let geom_type = model.geom_type();
2754
2755 assert_eq!(geom_type.len(), ngeom);
2756
2757 for i in 0..ngeom {
2759 let raw_i32 = unsafe { *model.ffi().geom_type.add(i) };
2760 let expected: MjtGeom = unsafe { crate::util::force_cast(raw_i32) };
2761 assert_eq!(geom_type[i], expected);
2762 }
2763
2764 let sphere_geom = model.geom("green_sphere").unwrap();
2766 assert_eq!(geom_type[sphere_geom.id], MjtGeom::mjGEOM_SPHERE);
2767
2768 let floor_geom = model.geom("floor").unwrap();
2769 assert_eq!(geom_type[floor_geom.id], MjtGeom::mjGEOM_PLANE);
2770
2771 let rod_geom = model.geom("rod").unwrap();
2772 assert_eq!(geom_type[rod_geom.id], MjtGeom::mjGEOM_CYLINDER);
2773 }
2774
2775 #[test]
2779 fn test_force_cast_geom_model_arrays() {
2780 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2781 let ngeom = model.ffi().ngeom as usize;
2782
2783 let geom_size = model.geom_size();
2784 let geom_pos = model.geom_pos();
2785 let geom_quat = model.geom_quat();
2786 let geom_rgba = model.geom_rgba();
2787 let geom_friction = model.geom_friction();
2788 let geom_aabb = model.geom_aabb();
2789
2790 assert_eq!(geom_size.len(), ngeom);
2791 assert_eq!(geom_pos.len(), ngeom);
2792 assert_eq!(geom_quat.len(), ngeom);
2793 assert_eq!(geom_rgba.len(), ngeom);
2794 assert_eq!(geom_friction.len(), ngeom);
2795 assert_eq!(geom_aabb.len(), ngeom);
2796
2797 for i in 0..ngeom {
2799 for j in 0..3 {
2800 assert_eq!(geom_size[i][j], unsafe { *model.ffi().geom_size.add(i * 3 + j) });
2801 assert_eq!(geom_pos[i][j], unsafe { *model.ffi().geom_pos.add(i * 3 + j) });
2802 assert_eq!(geom_friction[i][j], unsafe { *model.ffi().geom_friction.add(i * 3 + j) });
2803 }
2804 for j in 0..4 {
2805 assert_eq!(geom_quat[i][j], unsafe { *model.ffi().geom_quat.add(i * 4 + j) });
2806 assert_eq!(geom_rgba[i][j], unsafe { *model.ffi().geom_rgba.add(i * 4 + j) });
2807 }
2808 for j in 0..6 {
2809 assert_eq!(geom_aabb[i][j], unsafe { *model.ffi().geom_aabb.add(i * 6 + j) });
2810 }
2811 }
2812
2813 let gs = model.geom("green_sphere").unwrap();
2815 assert_eq!(geom_rgba[gs.id], [0.0f32, 1.0, 0.0, 1.0]);
2816 assert_relative_eq!(geom_size[gs.id][0], 0.1, epsilon = 1e-9);
2817 }
2818
2819 #[test]
2823 fn test_force_cast_camera_model_arrays() {
2824 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2825 let ncam = model.ffi().ncam as usize;
2826
2827 if ncam == 0 {
2828 return;
2830 }
2831
2832 let cam_mode = model.cam_mode();
2833 let cam_projection = model.cam_projection();
2834 let cam_resolution = model.cam_resolution();
2835 let cam_sensorsize = model.cam_sensorsize();
2836 let cam_intrinsic = model.cam_intrinsic();
2837 let cam_mat0 = model.cam_mat0();
2838
2839 assert_eq!(cam_mode.len(), ncam);
2840 assert_eq!(cam_projection.len(), ncam);
2841 assert_eq!(cam_resolution.len(), ncam);
2842 assert_eq!(cam_sensorsize.len(), ncam);
2843 assert_eq!(cam_intrinsic.len(), ncam);
2844 assert_eq!(cam_mat0.len(), ncam);
2845
2846 for i in 0..ncam {
2848 let raw_mode = unsafe { *model.ffi().cam_mode.add(i) };
2849 let expected_mode: MjtCamLight = unsafe { crate::util::force_cast(raw_mode) };
2850 assert_eq!(cam_mode[i], expected_mode);
2851
2852 let raw_proj = unsafe { *model.ffi().cam_projection.add(i) };
2853 let expected_proj: MjtProjection = unsafe { crate::util::force_cast(raw_proj) };
2854 assert_eq!(cam_projection[i], expected_proj);
2855
2856 for j in 0..2 {
2857 assert_eq!(cam_resolution[i][j], unsafe { *model.ffi().cam_resolution.add(i * 2 + j) });
2858 assert_eq!(cam_sensorsize[i][j], unsafe { *model.ffi().cam_sensorsize.add(i * 2 + j) });
2859 }
2860 for j in 0..4 {
2861 assert_eq!(cam_intrinsic[i][j], unsafe { *model.ffi().cam_intrinsic.add(i * 4 + j) });
2862 }
2863 for j in 0..9 {
2864 assert_eq!(cam_mat0[i][j], unsafe { *model.ffi().cam_mat0.add(i * 9 + j) });
2865 }
2866 }
2867
2868 let cam1 = model.camera("cam1").unwrap();
2870 assert_eq!(cam_resolution[cam1.id], [100, 200]);
2871 }
2872
2873 #[test]
2875 fn test_force_cast_bvh_model_arrays() {
2876 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2877 let nbvh = model.ffi().nbvh as usize;
2878
2879 let bvh_child = model.bvh_child();
2880 assert_eq!(bvh_child.len(), nbvh);
2881
2882 for i in 0..nbvh {
2883 for j in 0..2 {
2884 assert_eq!(bvh_child[i][j], unsafe { *model.ffi().bvh_child.add(i * 2 + j) });
2885 }
2886 }
2887
2888 let nbvhstatic = model.ffi().nbvhstatic as usize;
2889 let bvh_aabb = model.bvh_aabb();
2890 assert_eq!(bvh_aabb.len(), nbvhstatic);
2891
2892 for i in 0..nbvhstatic {
2893 for j in 0..6 {
2894 assert_eq!(bvh_aabb[i][j], unsafe { *model.ffi().bvh_aabb.add(i * 6 + j) });
2895 }
2896 }
2897 }
2898
2899 #[test]
2901 fn test_force_cast_sameframe_enum() {
2902 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2903 let nbody = model.ffi().nbody as usize;
2904 let ngeom = model.ffi().ngeom as usize;
2905
2906 let body_sameframe = model.body_sameframe();
2907 let geom_sameframe = model.geom_sameframe();
2908
2909 assert_eq!(body_sameframe.len(), nbody);
2910 assert_eq!(geom_sameframe.len(), ngeom);
2911
2912 for i in 0..nbody {
2913 let raw = unsafe { *model.ffi().body_sameframe.add(i) };
2914 let expected: MjtSameFrame = unsafe { crate::util::force_cast(raw) };
2915 assert_eq!(body_sameframe[i], expected, "body_sameframe[{}] mismatch", i);
2916 }
2917
2918 for i in 0..ngeom {
2919 let raw = unsafe { *model.ffi().geom_sameframe.add(i) };
2920 let expected: MjtSameFrame = unsafe { crate::util::force_cast(raw) };
2921 assert_eq!(geom_sameframe[i], expected, "geom_sameframe[{}] mismatch", i);
2922 }
2923 }
2924
2925 #[test]
2928 fn test_force_cast_equality_model_arrays() {
2929 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2930 let neq = model.ffi().neq as usize;
2931
2932 if neq == 0 {
2933 return;
2934 }
2935
2936 let eq_type = model.eq_type();
2937 let eq_objtype = model.eq_objtype();
2938 let eq_active0 = model.eq_active0();
2939
2940 assert_eq!(eq_type.len(), neq);
2941 assert_eq!(eq_objtype.len(), neq);
2942 assert_eq!(eq_active0.len(), neq);
2943
2944 for i in 0..neq {
2946 let raw_type = unsafe { *model.ffi().eq_type.add(i) };
2947 let expected_type: MjtEq = unsafe { crate::util::force_cast(raw_type) };
2948 assert_eq!(eq_type[i], expected_type);
2949
2950 let raw_objtype = unsafe { *model.ffi().eq_objtype.add(i) };
2951 let expected_objtype: MjtObj = unsafe { crate::util::force_cast(raw_objtype) };
2952 assert_eq!(eq_objtype[i], expected_objtype);
2953
2954 let raw_active = unsafe { *model.ffi().eq_active0.add(i) };
2955 assert_eq!(eq_active0[i], raw_active);
2956 }
2957
2958 let eq1 = model.equality("eq1").unwrap();
2960 assert_eq!(eq_type[eq1.id], MjtEq::mjEQ_CONNECT);
2961 assert_eq!(eq_objtype[eq1.id], MjtObj::mjOBJ_BODY);
2962 assert!(eq_active0[eq1.id]);
2963 }
2964
2965 #[test]
2968 fn test_force_cast_sensor_model_enums() {
2969 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
2970 let nsensor = model.ffi().nsensor as usize;
2971
2972 if nsensor == 0 {
2973 return;
2974 }
2975
2976 let sensor_type = model.sensor_type();
2977 let sensor_datatype = model.sensor_datatype();
2978 let sensor_needstage = model.sensor_needstage();
2979 let sensor_objtype = model.sensor_objtype();
2980 let sensor_reftype = model.sensor_reftype();
2981
2982 assert_eq!(sensor_type.len(), nsensor);
2983 assert_eq!(sensor_datatype.len(), nsensor);
2984 assert_eq!(sensor_needstage.len(), nsensor);
2985 assert_eq!(sensor_objtype.len(), nsensor);
2986 assert_eq!(sensor_reftype.len(), nsensor);
2987
2988 for i in 0..nsensor {
2989 let raw_type = unsafe { *model.ffi().sensor_type.add(i) };
2990 let raw_datatype = unsafe { *model.ffi().sensor_datatype.add(i) };
2991 let raw_needstage = unsafe { *model.ffi().sensor_needstage.add(i) };
2992 let raw_objtype = unsafe { *model.ffi().sensor_objtype.add(i) };
2993 let raw_reftype = unsafe { *model.ffi().sensor_reftype.add(i) };
2994
2995 assert_eq!(sensor_type[i], unsafe { crate::util::force_cast::<_, MjtSensor>(raw_type) });
2996 assert_eq!(sensor_datatype[i], unsafe { crate::util::force_cast::<_, MjtDataType>(raw_datatype) });
2997 assert_eq!(sensor_needstage[i], unsafe { crate::util::force_cast::<_, MjtStage>(raw_needstage) });
2998 assert_eq!(sensor_objtype[i], unsafe { crate::util::force_cast::<_, MjtObj>(raw_objtype) });
2999 assert_eq!(sensor_reftype[i], unsafe { crate::util::force_cast::<_, MjtObj>(raw_reftype) });
3000 }
3001
3002 let touch = model.sensor("touch").unwrap();
3004 assert_eq!(sensor_type[touch.id], MjtSensor::mjSENS_TOUCH);
3005 assert_eq!(sensor_objtype[touch.id], MjtObj::mjOBJ_SITE);
3006 }
3007
3008 #[test]
3011 fn test_force_cast_actuator_model_enums_and_bools() {
3012 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3013 let nu = model.ffi().nu as usize;
3014
3015 if nu == 0 {
3016 return;
3017 }
3018
3019 let trntype = model.actuator_trntype();
3020 let dyntype = model.actuator_dyntype();
3021 let gaintype = model.actuator_gaintype();
3022 let biastype = model.actuator_biastype();
3023 let ctrllimited = model.actuator_ctrllimited();
3024 let forcelimited = model.actuator_forcelimited();
3025 let actlimited = model.actuator_actlimited();
3026 let actearly = model.actuator_actearly();
3027
3028 assert_eq!(trntype.len(), nu);
3029 assert_eq!(dyntype.len(), nu);
3030 assert_eq!(gaintype.len(), nu);
3031 assert_eq!(biastype.len(), nu);
3032 assert_eq!(ctrllimited.len(), nu);
3033 assert_eq!(forcelimited.len(), nu);
3034 assert_eq!(actlimited.len(), nu);
3035 assert_eq!(actearly.len(), nu);
3036
3037 for i in 0..nu {
3038 assert_eq!(trntype[i], unsafe { crate::util::force_cast::<_, MjtTrn>(*model.ffi().actuator_trntype.add(i)) });
3040 assert_eq!(dyntype[i], unsafe { crate::util::force_cast::<_, MjtDyn>(*model.ffi().actuator_dyntype.add(i)) });
3041 assert_eq!(gaintype[i], unsafe { crate::util::force_cast::<_, MjtGain>(*model.ffi().actuator_gaintype.add(i)) });
3042 assert_eq!(biastype[i], unsafe { crate::util::force_cast::<_, MjtBias>(*model.ffi().actuator_biastype.add(i)) });
3043
3044 let raw_ctrllimited = unsafe { *model.ffi().actuator_ctrllimited.add(i) };
3046 assert_eq!(ctrllimited[i], raw_ctrllimited);
3047 let raw_forcelimited = unsafe { *model.ffi().actuator_forcelimited.add(i) };
3048 assert_eq!(forcelimited[i], raw_forcelimited);
3049 let raw_actlimited = unsafe { *model.ffi().actuator_actlimited.add(i) };
3050 assert_eq!(actlimited[i], raw_actlimited);
3051 let raw_actearly = unsafe { *model.ffi().actuator_actearly.add(i) };
3052 assert_eq!(actearly[i], raw_actearly);
3053 }
3054
3055 let slider = model.actuator("slider").unwrap();
3057 assert_eq!(biastype[slider.id], MjtBias::mjBIAS_AFFINE);
3058 assert_eq!(gaintype[slider.id], MjtGain::mjGAIN_FIXED);
3059 assert!(ctrllimited[slider.id]);
3060 }
3061
3062 #[test]
3065 fn test_force_cast_actuator_param_arrays() {
3066 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3067 let nu = model.ffi().nu as usize;
3068
3069 let dynprm = model.actuator_dynprm();
3070 let ctrlrange = model.actuator_ctrlrange();
3071 let gear = model.actuator_gear();
3072 let trnid = model.actuator_trnid();
3073
3074 assert_eq!(dynprm.len(), nu);
3075 assert_eq!(ctrlrange.len(), nu);
3076 assert_eq!(gear.len(), nu);
3077 assert_eq!(trnid.len(), nu);
3078
3079 let slider = model.actuator("slider").unwrap();
3081 assert_eq!(dynprm[slider.id][0..10], [1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0]);
3082 assert_eq!(ctrlrange[slider.id], [0.0, 1.0]);
3083
3084 let slider2 = model.actuator("slider2").unwrap();
3086 assert_eq!(dynprm[slider2.id][0..10], [10.0, 9.0, 8.0, 7.0, 6.0, 5.0, 4.0, 3.0, 2.0, 1.0]);
3087
3088 for i in 0..nu {
3090 for j in 0..6 {
3091 assert_eq!(gear[i][j], unsafe { *model.ffi().actuator_gear.add(i * 6 + j) });
3092 }
3093 for j in 0..2 {
3094 assert_eq!(trnid[i][j], unsafe { *model.ffi().actuator_trnid.add(i * 2 + j) });
3095 assert_eq!(ctrlrange[i][j], unsafe { *model.ffi().actuator_ctrlrange.add(i * 2 + j) });
3096 }
3097 }
3098 }
3099
3100 #[test]
3103 fn test_force_cast_tendon_model_arrays() {
3104 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3105 let ntendon = model.ffi().ntendon as usize;
3106
3107 if ntendon == 0 {
3108 return;
3109 }
3110
3111 let tendon_limited = model.tendon_limited();
3112 let tendon_range = model.tendon_range();
3113 let tendon_rgba = model.tendon_rgba();
3114 let tendon_treeid = model.tendon_treeid();
3115 let tendon_lengthspring = model.tendon_lengthspring();
3116
3117 assert_eq!(tendon_limited.len(), ntendon);
3118 assert_eq!(tendon_range.len(), ntendon);
3119 assert_eq!(tendon_rgba.len(), ntendon);
3120 assert_eq!(tendon_treeid.len(), ntendon);
3121 assert_eq!(tendon_lengthspring.len(), ntendon);
3122
3123 for i in 0..ntendon {
3124 let raw_limited = unsafe { *model.ffi().tendon_limited.add(i) };
3125 assert_eq!(tendon_limited[i], raw_limited);
3126
3127 for j in 0..2 {
3128 assert_eq!(tendon_range[i][j], unsafe { *model.ffi().tendon_range.add(i * 2 + j) });
3129 assert_eq!(tendon_treeid[i][j], unsafe { *model.ffi().tendon_treeid.add(i * 2 + j) });
3130 assert_eq!(tendon_lengthspring[i][j], unsafe { *model.ffi().tendon_lengthspring.add(i * 2 + j) });
3131 }
3132
3133 for j in 0..4 {
3134 assert_eq!(tendon_rgba[i][j], unsafe { *model.ffi().tendon_rgba.add(i * 4 + j) });
3135 }
3136 }
3137
3138 let ten2 = model.tendon("tendon2").unwrap();
3140 assert!(tendon_limited[ten2.id]);
3141 assert_eq!(tendon_range[ten2.id], [0.0, 1.0]);
3142 assert_relative_eq!(tendon_rgba[ten2.id][0], 0.0f32, epsilon = 1e-6);
3143 assert_relative_eq!(tendon_rgba[ten2.id][1], 0.1f32, epsilon = 1e-6);
3144 }
3145
3146 #[test]
3148 fn test_force_cast_texture_model_enums() {
3149 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3150 let ntex = model.ffi().ntex as usize;
3151
3152 if ntex == 0 {
3153 return;
3154 }
3155
3156 let tex_type = model.tex_type();
3157 let tex_colorspace = model.tex_colorspace();
3158
3159 assert_eq!(tex_type.len(), ntex);
3160 assert_eq!(tex_colorspace.len(), ntex);
3161
3162 for i in 0..ntex {
3163 let raw_type = unsafe { *model.ffi().tex_type.add(i) };
3164 let expected_type: MjtTexture = unsafe { crate::util::force_cast(raw_type) };
3165 assert_eq!(tex_type[i], expected_type);
3166
3167 let raw_cs = unsafe { *model.ffi().tex_colorspace.add(i) };
3168 let expected_cs: MjtColorSpace = unsafe { crate::util::force_cast(raw_cs) };
3169 assert_eq!(tex_colorspace[i], expected_cs);
3170 }
3171
3172 let wall_tex = model.texture("wall_tex").unwrap();
3174 assert_eq!(tex_type[wall_tex.id], MjtTexture::mjTEXTURE_2D);
3175 assert_eq!(tex_colorspace[wall_tex.id], MjtColorSpace::mjCOLORSPACE_SRGB);
3176 }
3177
3178 #[test]
3181 fn test_force_cast_material_model_arrays() {
3182 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3183 let nmat = model.ffi().nmat as usize;
3184
3185 if nmat == 0 {
3186 return;
3187 }
3188
3189 let mat_texuniform = model.mat_texuniform();
3190 let mat_texrepeat = model.mat_texrepeat();
3191 let mat_rgba = model.mat_rgba();
3192
3193 assert_eq!(mat_texuniform.len(), nmat);
3194 assert_eq!(mat_texrepeat.len(), nmat);
3195 assert_eq!(mat_rgba.len(), nmat);
3196
3197 for i in 0..nmat {
3198 let raw_uniform = unsafe { *model.ffi().mat_texuniform.add(i) };
3199 assert_eq!(mat_texuniform[i], raw_uniform);
3200
3201 for j in 0..2 {
3202 assert_eq!(mat_texrepeat[i][j], unsafe { *model.ffi().mat_texrepeat.add(i * 2 + j) });
3203 }
3204 for j in 0..4 {
3205 assert_eq!(mat_rgba[i][j], unsafe { *model.ffi().mat_rgba.add(i * 4 + j) });
3206 }
3207 }
3208
3209 let mat = model.material("also_wood_material").unwrap();
3211 assert!(!mat_texuniform[mat.id]);
3212 assert_eq!(mat_texrepeat[mat.id], [2.0f32, 2.0]);
3213 assert_eq!(mat_rgba[mat.id], [0.8f32, 0.5, 0.3, 1.0]);
3214 }
3215
3216 #[test]
3220 fn test_force_cast_light_model_arrays() {
3221 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3222 let nlight = model.ffi().nlight as usize;
3223
3224 if nlight == 0 {
3225 return;
3226 }
3227
3228 let light_mode = model.light_mode();
3229 let light_type = model.light_type();
3230 let light_castshadow = model.light_castshadow();
3231 let light_active = model.light_active();
3232 let light_attenuation = model.light_attenuation();
3233 let light_ambient = model.light_ambient();
3234 let light_diffuse = model.light_diffuse();
3235 let light_specular = model.light_specular();
3236 let light_pos = model.light_pos();
3237 let light_dir = model.light_dir();
3238
3239 assert_eq!(light_mode.len(), nlight);
3240 assert_eq!(light_type.len(), nlight);
3241 assert_eq!(light_castshadow.len(), nlight);
3242 assert_eq!(light_active.len(), nlight);
3243
3244 for i in 0..nlight {
3245 assert_eq!(light_mode[i], unsafe { crate::util::force_cast::<_, MjtCamLight>(*model.ffi().light_mode.add(i)) });
3246 assert_eq!(light_type[i], unsafe { crate::util::force_cast::<_, MjtLightType>(*model.ffi().light_type.add(i)) });
3247
3248 let raw_shadow = unsafe { *model.ffi().light_castshadow.add(i) };
3249 assert_eq!(light_castshadow[i], raw_shadow);
3250 let raw_active = unsafe { *model.ffi().light_active.add(i) };
3251 assert_eq!(light_active[i], raw_active);
3252
3253 for j in 0..3 {
3254 assert_eq!(light_attenuation[i][j], unsafe { *model.ffi().light_attenuation.add(i * 3 + j) });
3255 assert_eq!(light_ambient[i][j], unsafe { *model.ffi().light_ambient.add(i * 3 + j) });
3256 assert_eq!(light_diffuse[i][j], unsafe { *model.ffi().light_diffuse.add(i * 3 + j) });
3257 assert_eq!(light_specular[i][j], unsafe { *model.ffi().light_specular.add(i * 3 + j) });
3258 assert_eq!(light_pos[i][j], unsafe { *model.ffi().light_pos.add(i * 3 + j) });
3259 assert_eq!(light_dir[i][j], unsafe { *model.ffi().light_dir.add(i * 3 + j) });
3260 }
3261 }
3262
3263 let l2 = model.light("lamp_light2").unwrap();
3265 assert_eq!(light_mode[l2.id], MjtCamLight::mjCAMLIGHT_FIXED);
3266 assert_eq!(light_type[l2.id], MjtLightType::mjLIGHT_SPOT);
3267 assert!(light_castshadow[l2.id]);
3268 }
3269
3270 #[test]
3274 fn test_force_cast_site_model_arrays() {
3275 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3276 let nsite = model.ffi().nsite as usize;
3277
3278 let site_type = model.site_type();
3279 let site_sameframe = model.site_sameframe();
3280 let site_size = model.site_size();
3281 let site_pos = model.site_pos();
3282 let site_quat = model.site_quat();
3283 let site_rgba = model.site_rgba();
3284
3285 assert_eq!(site_type.len(), nsite);
3286 assert_eq!(site_sameframe.len(), nsite);
3287 assert_eq!(site_size.len(), nsite);
3288 assert_eq!(site_pos.len(), nsite);
3289 assert_eq!(site_quat.len(), nsite);
3290 assert_eq!(site_rgba.len(), nsite);
3291
3292 for i in 0..nsite {
3293 assert_eq!(site_type[i], unsafe { crate::util::force_cast::<_, MjtGeom>(*model.ffi().site_type.add(i)) });
3294 assert_eq!(site_sameframe[i], unsafe { crate::util::force_cast::<_, MjtSameFrame>(*model.ffi().site_sameframe.add(i)) });
3295
3296 for j in 0..3 {
3297 assert_eq!(site_size[i][j], unsafe { *model.ffi().site_size.add(i * 3 + j) });
3298 assert_eq!(site_pos[i][j], unsafe { *model.ffi().site_pos.add(i * 3 + j) });
3299 }
3300 for j in 0..4 {
3301 assert_eq!(site_quat[i][j], unsafe { *model.ffi().site_quat.add(i * 4 + j) });
3302 assert_eq!(site_rgba[i][j], unsafe { *model.ffi().site_rgba.add(i * 4 + j) });
3303 }
3304 }
3305 }
3306
3307 #[test]
3311 fn test_force_cast_joint_model_solver_arrays() {
3312 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3313 let njnt = model.ffi().njnt as usize;
3314
3315 let jnt_solref = model.jnt_solref();
3316 let jnt_solimp = model.jnt_solimp();
3317 let jnt_pos = model.jnt_pos();
3318 let jnt_axis = model.jnt_axis();
3319 let jnt_range = model.jnt_range();
3320
3321 assert_eq!(jnt_solref.len(), njnt);
3322 assert_eq!(jnt_solimp.len(), njnt);
3323 assert_eq!(jnt_pos.len(), njnt);
3324 assert_eq!(jnt_axis.len(), njnt);
3325 assert_eq!(jnt_range.len(), njnt);
3326
3327 let nref = mjNREF as usize;
3328 let nimp = mjNIMP as usize;
3329
3330 for i in 0..njnt {
3331 for j in 0..nref {
3332 assert_eq!(jnt_solref[i][j], unsafe { *model.ffi().jnt_solref.add(i * nref + j) });
3333 }
3334 for j in 0..nimp {
3335 assert_eq!(jnt_solimp[i][j], unsafe { *model.ffi().jnt_solimp.add(i * nimp + j) });
3336 }
3337 for j in 0..3 {
3338 assert_eq!(jnt_pos[i][j], unsafe { *model.ffi().jnt_pos.add(i * 3 + j) });
3339 assert_eq!(jnt_axis[i][j], unsafe { *model.ffi().jnt_axis.add(i * 3 + j) });
3340 }
3341 for j in 0..2 {
3342 assert_eq!(jnt_range[i][j], unsafe { *model.ffi().jnt_range.add(i * 2 + j) });
3343 }
3344 }
3345
3346 let rod = model.joint("rod").unwrap();
3348 assert_eq!(&jnt_axis[rod.id][..], &[0.0, 1.0, 0.0]);
3349 assert_eq!(&jnt_range[rod.id][..], &[0.0, 1.0]);
3350 }
3351
3352 #[test]
3356 fn test_force_cast_view_enum_fields() {
3357 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3358
3359 let rod_info = model.joint("rod").unwrap();
3361 let rod_view = rod_info.view(&model);
3362 assert_eq!(rod_view.r#type[0], MjtJoint::mjJNT_SLIDE);
3363 assert!(rod_view.limited[0]);
3364
3365 let ball2_info = model.geom("ball2").unwrap();
3367 let ball2_view = ball2_info.view(&model);
3368 assert_eq!(ball2_view.r#type[0], MjtGeom::mjGEOM_SPHERE);
3369
3370 let touch_info = model.sensor("touch").unwrap();
3372 let touch_view = touch_info.view(&model);
3373 assert_eq!(touch_view.r#type[0], MjtSensor::mjSENS_TOUCH);
3374 assert_eq!(touch_view.objtype[0], MjtObj::mjOBJ_SITE);
3375
3376 let slider_info = model.actuator("slider").unwrap();
3378 let slider_view = slider_info.view(&model);
3379 assert_eq!(slider_view.trntype[0], MjtTrn::mjTRN_JOINT);
3380 assert_eq!(slider_view.biastype[0], MjtBias::mjBIAS_AFFINE);
3381 assert_eq!(slider_view.gaintype[0], MjtGain::mjGAIN_FIXED);
3382 assert!(slider_view.ctrllimited[0]);
3383
3384 let mut slider_view_mut = slider_info.view_mut(&mut model);
3386 slider_view_mut.gaintype[0] = MjtGain::mjGAIN_AFFINE;
3387 let slider_view2 = slider_info.view(&model);
3388 assert_eq!(slider_view2.gaintype[0], MjtGain::mjGAIN_AFFINE);
3389 }
3390
3391 #[test]
3394 fn test_model_view_mut_roundtrip() {
3395 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3396
3397 let ball2_info = model.body("ball2").unwrap();
3399 let ball2_id = ball2_info.id;
3400 let orig_pos = model.body_pos()[ball2_id];
3401 assert_eq!(orig_pos, [0.5, 0.0, 0.0]);
3402
3403 {
3404 let mut body_view = ball2_info.view_mut(&mut model);
3405 body_view.pos.copy_from_slice(&[99.0, 88.0, 77.0]);
3406 }
3407 assert_eq!(model.body_pos()[ball2_id], [99.0, 88.0, 77.0]);
3408
3409 for j in 0..3 {
3411 let ffi_val = unsafe { *model.ffi().body_pos.add(ball2_id * 3 + j) };
3412 assert_eq!(ffi_val, [99.0, 88.0, 77.0][j]);
3413 }
3414
3415 let gs_info = model.geom("green_sphere").unwrap();
3417 let gs_id = gs_info.id;
3418 {
3419 let mut geom_view = gs_info.view_mut(&mut model);
3420 geom_view.rgba.copy_from_slice(&[1.0f32, 0.0, 0.0, 0.5]);
3421 }
3422 assert_eq!(model.geom_rgba()[gs_id], [1.0f32, 0.0, 0.0, 0.5]);
3423 for j in 0..4 {
3424 assert_eq!(unsafe { *model.ffi().geom_rgba.add(gs_id * 4 + j) }, [1.0f32, 0.0, 0.0, 0.5][j]);
3425 }
3426 }
3427
3428 #[test]
3431 fn test_force_cast_sublen_dep_key_arrays() {
3432 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3433 let nkey = model.ffi().nkey as usize;
3434 let nq = model.ffi().nq as usize;
3435 let nv = model.ffi().nv as usize;
3436 let na = model.ffi().na as usize;
3437 let nu = model.ffi().nu as usize;
3438
3439 assert!(nkey >= 2, "EXAMPLE_MODEL must have at least 2 keyframes");
3440
3441 let key_qpos = model.key_qpos();
3442 let key_qvel = model.key_qvel();
3443 let key_act = model.key_act();
3444 let key_ctrl = model.key_ctrl();
3445
3446 assert_eq!(key_qpos.len(), nkey * nq);
3448 assert_eq!(key_qvel.len(), nkey * nv);
3449 assert_eq!(key_act.len(), nkey * na);
3450 assert_eq!(key_ctrl.len(), nkey * nu);
3451
3452 for i in 0..(nkey * nq) {
3454 assert_eq!(key_qpos[i], unsafe { *model.ffi().key_qpos.add(i) });
3455 }
3456 for i in 0..(nkey * nv) {
3457 assert_eq!(key_qvel[i], unsafe { *model.ffi().key_qvel.add(i) });
3458 }
3459 for i in 0..(nkey * nu) {
3460 assert_eq!(key_ctrl[i], unsafe { *model.ffi().key_ctrl.add(i) });
3461 }
3462 }
3463
3464 #[test]
3467 fn test_force_cast_minimal_model_edge_case() {
3468 let xml = "<mujoco><worldbody><body><joint type='free'/><geom size='0.1'/></body></worldbody></mujoco>";
3469 let model = MjModel::from_xml_string(xml).unwrap();
3470
3471 assert_eq!(model.ffi().neq, 0);
3473 assert_eq!(model.ffi().ntendon, 0);
3474 assert_eq!(model.ffi().nu, 0);
3475 assert_eq!(model.ffi().nsensor, 0);
3476 assert_eq!(model.ffi().ncam, 0);
3477 assert_eq!(model.ffi().ntex, 0);
3478 assert_eq!(model.ffi().nmat, 0);
3479
3480 assert!(model.eq_type().is_empty());
3482 assert!(model.eq_active0().is_empty());
3483 assert!(model.tendon_limited().is_empty());
3484 assert!(model.tendon_rgba().is_empty());
3485 assert!(model.actuator_trntype().is_empty());
3486 assert!(model.actuator_ctrllimited().is_empty());
3487 assert!(model.sensor_type().is_empty());
3488 assert!(model.cam_mode().is_empty());
3489 assert!(model.cam_resolution().is_empty());
3490 assert!(model.tex_type().is_empty());
3491 assert!(model.mat_texuniform().is_empty());
3492 assert!(model.mat_rgba().is_empty());
3493
3494 let nbody = model.ffi().nbody as usize;
3496 assert!(nbody >= 2);
3497 assert_eq!(model.body_pos().len(), nbody);
3498 assert_eq!(model.body_sameframe().len(), nbody);
3499 assert_eq!(model.jnt_type().len(), model.ffi().njnt as usize);
3500 assert_eq!(model.geom_type().len(), model.ffi().ngeom as usize);
3501 }
3502
3503 #[test]
3506 fn test_force_cast_pair_model_arrays() {
3507 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3508 let npair = model.ffi().npair as usize;
3509
3510 if npair == 0 {
3511 return;
3512 }
3513
3514 let pair_solref = model.pair_solref();
3515 let pair_friction = model.pair_friction();
3516 let pair_solimp = model.pair_solimp();
3517
3518 assert_eq!(pair_solref.len(), npair);
3519 assert_eq!(pair_friction.len(), npair);
3520 assert_eq!(pair_solimp.len(), npair);
3521
3522 let nref = mjNREF as usize;
3523 let nimp = mjNIMP as usize;
3524
3525 for i in 0..npair {
3526 for j in 0..nref {
3527 assert_eq!(pair_solref[i][j], unsafe { *model.ffi().pair_solref.add(i * nref + j) });
3528 }
3529 for j in 0..5 {
3530 assert_eq!(pair_friction[i][j], unsafe { *model.ffi().pair_friction.add(i * 5 + j) });
3531 }
3532 for j in 0..nimp {
3533 assert_eq!(pair_solimp[i][j], unsafe { *model.ffi().pair_solimp.add(i * nimp + j) });
3534 }
3535 }
3536 }
3537
3538 #[test]
3541 fn test_force_cast_model_non_aliasing() {
3542 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3543 let njnt = model.ffi().njnt as usize;
3544
3545 if njnt < 2 {
3546 return;
3547 }
3548
3549 let jnt_solref = model.jnt_solref();
3550 let jnt_type = model.jnt_type();
3551
3552 assert_ne!(jnt_solref[0].as_ptr(), jnt_solref[1].as_ptr());
3554 assert_ne!(std::ptr::addr_of!(jnt_type[0]), std::ptr::addr_of!(jnt_type[1]));
3555
3556 let ptr_diff = unsafe { jnt_solref[1].as_ptr().offset_from(jnt_solref[0].as_ptr()) };
3558 assert_eq!(ptr_diff, mjNREF as isize,
3559 "jnt_solref stride must be mjNREF={}", mjNREF);
3560 }
3561
3562 const MOCAP_MODEL: &str = stringify!(
3565 <mujoco>
3566 <worldbody>
3567 <body name="mocap1" mocap="true" pos="0 0 0">
3568 <geom type="sphere" size="0.05" contype="0" conaffinity="0"/>
3569 </body>
3570 <body name="mocap2" mocap="true" pos="1 0 0">
3571 <geom type="sphere" size="0.05" contype="0" conaffinity="0"/>
3572 </body>
3573 <geom type="plane" size="5 5 0.1"/>
3574 </worldbody>
3575 <keyframe>
3576 <key name="k0"
3577 mpos="1.0 2.0 3.0 4.0 5.0 6.0"
3578 mquat="0.5 0.5 0.5 0.5 1.0 0.0 0.0 0.0"/>
3579 <key name="k1"
3580 mpos="10.0 20.0 30.0 40.0 50.0 60.0"
3581 mquat="0.0 0.0 0.0 1.0 0.0 1.0 0.0 0.0"/>
3582 </keyframe>
3583 </mujoco>
3584 );
3585
3586 #[test]
3589 fn test_key_mpos() {
3590 let model = MjModel::from_xml_string(MOCAP_MODEL).unwrap();
3591 let nkey = model.ffi().nkey as usize;
3592 let nmocap = model.ffi().nmocap as usize;
3593
3594 assert_eq!(nkey, 2, "expected 2 keyframes");
3595 assert_eq!(nmocap, 2, "expected 2 mocap bodies");
3596
3597 let mpos = model.key_mpos();
3598 assert_eq!(mpos.len(), nkey * nmocap * 3,
3599 "key_mpos length must be nkey * nmocap * 3 = {}", nkey * nmocap * 3);
3600
3601 let k0 = &mpos[..nmocap * 3];
3603 let expected_k0: &[f64] = &[1.0, 2.0, 3.0, 4.0, 5.0, 6.0];
3604 assert_eq!(k0.len(), expected_k0.len());
3605 for (&a, &b) in k0.iter().zip(expected_k0.iter()) {
3606 assert_relative_eq!(a, b, epsilon = 1e-10);
3607 }
3608
3609 let k1 = &mpos[nmocap * 3..];
3611 let expected_k1: &[f64] = &[10.0, 20.0, 30.0, 40.0, 50.0, 60.0];
3612 assert_eq!(k1.len(), expected_k1.len());
3613 for (&a, &b) in k1.iter().zip(expected_k1.iter()) {
3614 assert_relative_eq!(a, b, epsilon = 1e-10);
3615 }
3616 }
3617
3618 #[test]
3621 fn test_key_mquat() {
3622 let model = MjModel::from_xml_string(MOCAP_MODEL).unwrap();
3623 let nkey = model.ffi().nkey as usize;
3624 let nmocap = model.ffi().nmocap as usize;
3625
3626 assert_eq!(nkey, 2, "expected 2 keyframes");
3627 assert_eq!(nmocap, 2, "expected 2 mocap bodies");
3628
3629 let mquat = model.key_mquat();
3630 assert_eq!(mquat.len(), nkey * nmocap * 4,
3631 "key_mquat length must be nkey * nmocap * 4 = {}", nkey * nmocap * 4);
3632
3633 let k0 = &mquat[..nmocap * 4];
3635 let expected_k0: &[f64] = &[0.5, 0.5, 0.5, 0.5, 1.0, 0.0, 0.0, 0.0];
3636 assert_eq!(k0.len(), expected_k0.len());
3637 for (&a, &b) in k0.iter().zip(expected_k0.iter()) {
3638 assert_relative_eq!(a, b, epsilon = 1e-10);
3639 }
3640
3641 let k1 = &mquat[nmocap * 4..];
3643 let expected_k1: &[f64] = &[0.0, 0.0, 0.0, 1.0, 0.0, 1.0, 0.0, 0.0];
3644 assert_eq!(k1.len(), expected_k1.len());
3645 for (&a, &b) in k1.iter().zip(expected_k1.iter()) {
3646 assert_relative_eq!(a, b, epsilon = 1e-10);
3647 }
3648 }
3649
3650 #[test]
3653 fn test_key_mpos_view_consistency() {
3654 let model = MjModel::from_xml_string(MOCAP_MODEL).unwrap();
3655 let nmocap = model.ffi().nmocap as usize;
3656
3657 let info_k0 = model.key("k0").unwrap();
3658 let view_k0 = info_k0.view(&model);
3659
3660 let array_k0 = &model.key_mpos()[..nmocap * 3];
3662 assert_eq!(
3663 &view_k0.mpos[..nmocap * 3], array_k0,
3664 "key view mpos and key_mpos array accessor must return identical data"
3665 );
3666
3667 let info_k1 = model.key("k1").unwrap();
3668 let view_k1 = info_k1.view(&model);
3669 let array_k1 = &model.key_mpos()[nmocap * 3..];
3670 assert_eq!(
3671 &view_k1.mpos[..nmocap * 3], array_k1,
3672 "key view mpos and key_mpos array accessor must return identical data for key 1"
3673 );
3674 }
3675
3676 #[test]
3678 fn test_key_mpos_mquat_no_mocap() {
3679 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3681 assert_eq!(model.ffi().nmocap, 0, "EXAMPLE_MODEL should have no mocap bodies");
3682 assert!(model.ffi().nkey > 0, "EXAMPLE_MODEL should have keyframes");
3683
3684 assert_eq!(model.key_mpos().len(), 0,
3685 "key_mpos must be empty when nmocap == 0");
3686 assert_eq!(model.key_mquat().len(), 0,
3687 "key_mquat must be empty when nmocap == 0");
3688 }
3689
3690 #[test]
3692 fn test_from_xml_string_invalid() {
3693 let result = MjModel::from_xml_string("<this is not valid mujoco xml>");
3694 assert!(result.is_err(), "loading invalid XML must return Err");
3695 let msg = result.unwrap_err().to_string();
3696 assert!(!msg.is_empty(), "error message must not be empty for invalid XML");
3697 }
3698
3699 #[test]
3704 fn test_mesh_view_new_fields() {
3705 const MESH_MODEL: &str = "<mujoco>\
3706 <asset>\
3707 <mesh name=\"cube\" vertex=\"-0.5 -0.5 -0.5 0.5 -0.5 -0.5 -0.5 0.5 -0.5 0.5 0.5 -0.5 \
3708 -0.5 -0.5 0.5 0.5 -0.5 0.5 -0.5 0.5 0.5 0.5 0.5 0.5\"/>\
3709 </asset>\
3710 <worldbody>\
3711 <geom type=\"mesh\" mesh=\"cube\"/>\
3712 </worldbody>\
3713 </mujoco>";
3714
3715 let mut model = MjModel::from_xml_string(MESH_MODEL).unwrap();
3716 let mesh_info = model.mesh("cube").unwrap();
3717
3718 let view = mesh_info.view(&model);
3719
3720 assert_eq!(view.scale.len(), 3);
3722 assert_eq!(view.pos.len(), 3);
3723 assert_eq!(view.quat.len(), 4);
3724
3725 assert_eq!(view.normaladr.len(), 1);
3727 assert_eq!(view.normalnum.len(), 1);
3728 assert_eq!(view.texcoordnum.len(), 1);
3729 assert_eq!(view.bvhadr.len(), 1);
3730 assert_eq!(view.bvhnum.len(), 1);
3731 assert_eq!(view.octadr.len(), 1);
3732 assert_eq!(view.octnum.len(), 1);
3733 assert_eq!(view.pathadr.len(), 1);
3734 assert_eq!(view.polynum.len(), 1);
3735 assert_eq!(view.polyadr.len(), 1);
3736
3737 let mut view_mut = mesh_info.view_mut(&mut model);
3739 view_mut.scale[0] = 2.0;
3740 view_mut.scale[1] = 3.0;
3741 view_mut.scale[2] = 4.0;
3742
3743 let view2 = mesh_info.view(&model);
3744 assert_eq!(view2.scale[0], 2.0);
3745 assert_eq!(view2.scale[1], 3.0);
3746 assert_eq!(view2.scale[2], 4.0);
3747 }
3748
3749 #[test]
3752 fn test_flex_array_slices_empty_for_non_flex_model() {
3753 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3754 assert_eq!(model.ffi().nflex, 0);
3755 assert_eq!(model.flex_cellnum().len(), 0);
3756 assert_eq!(model.flex_stiffnessadr().len(), 0);
3757 assert_eq!(model.flex_bendingadr().len(), 0);
3758 }
3759
3760 #[test]
3762 fn test_max_contacts() {
3763 let model = MjModel::from_xml_string(EXAMPLE_MODEL).unwrap();
3764 let geom1 = model.name_to_id(MjtObj::mjOBJ_GEOM, "green_sphere").unwrap();
3765 let geom2 = model.name_to_id(MjtObj::mjOBJ_GEOM, "ball2").unwrap();
3766
3767 let mc = model.max_contacts(geom1, geom2, None); assert_eq!(mc, 1);
3769
3770 let mc = model.max_contacts(geom1, geom2, Some(false));
3771 assert_eq!(mc, 1);
3772
3773 let mc = model.max_contacts(geom1, geom2, Some(true));
3775 assert_eq!(mc, 1);
3776
3777 assert!( model.try_max_contacts(999, geom2, Some(true)).is_err());
3779 }
3780}