1use std::ffi::{c_int, CStr, CString, NulError};
3use std::io::{self, Error, ErrorKind};
4use std::path::Path;
5use std::ptr;
6
7use super::mj_auxiliary::{MjVfs, MjVisual, MjStatistic};
8use crate::wrappers::mj_option::MjOption;
9use crate::wrappers::mj_data::MjData;
10use super::mj_primitive::*;
11use crate::mujoco_c::*;
12
13use crate::{view_creator, fixed_size_info_method, info_with_view};
14
15
16pub type MjtTrn = mjtTrn;
22pub type MjtDyn = mjtDyn;
24pub type MjtGain = mjtGain;
26pub type MjtBias = mjtBias;
28
29pub type MjtSensor = mjtSensor;
32
33pub type MjtDataType = mjtDataType;
35
36pub type MjtStage = mjtStage;
39
40pub type MjtObj = mjtObj;
43
44pub type MjtJoint = mjtJoint;
46
47pub type MjtGeom = mjtGeom;
49
50pub type MjtSameFrame = mjtSameFrame;
52
53pub type MjtCamLight = mjtCamLight;
55
56#[derive(Debug)]
61pub struct MjModel(*mut mjModel);
62
63unsafe impl Send for MjModel {}
66unsafe impl Sync for MjModel {}
67
68
69impl MjModel {
70 pub fn from_xml<T: AsRef<Path>>(path: T) -> Result<Self, Error> {
72 Self::from_xml_file(path, None)
73 }
74
75 pub fn from_xml_vfs<T: AsRef<Path>>(path: T, vfs: &MjVfs) -> Result<Self, Error> {
77 Self::from_xml_file(path, Some(vfs))
78 }
79
80 fn from_xml_file<T: AsRef<Path>>(path: T, vfs: Option<&MjVfs>) -> Result<Self, Error> {
81 let mut error_buffer = [0i8; 100];
82 unsafe {
83 let path = CString::new(path.as_ref().to_str().expect("invalid utf")).unwrap();
84 let raw_ptr = mj_loadXML(
85 path.as_ptr(), vfs.map_or(ptr::null(), |v| v.ffi()),
86 &mut error_buffer as *mut i8, error_buffer.len() as c_int
87 );
88
89 Self::check_raw_model(raw_ptr, &error_buffer)
90 }
91 }
92
93 pub fn from_xml_string(data: &str) -> Result<Self, Error> {
95 let mut vfs = MjVfs::new();
96 let filename = "model.xml";
97
98 vfs.add_from_buffer(filename, data.as_bytes())?;
100
101 let mut error_buffer = [0i8; 100];
102 unsafe {
103 let filename_c = CString::new(filename).unwrap();
104 let raw_ptr = mj_loadXML(
105 filename_c.as_ptr(), vfs.ffi(),
106 &mut error_buffer as *mut i8, error_buffer.len() as c_int
107 );
108
109 Self::check_raw_model(raw_ptr, &error_buffer)
110 }
111 }
112
113 pub fn from_buffer(data: &[u8]) -> Result<Self, Error> {
115 unsafe {
116 let mut vfs = MjVfs::new();
119 let filename = "model.mjb";
120
121 vfs.add_from_buffer(filename, data)?;
123
124 let filename_c = CString::new(filename).unwrap();
126 let raw_model = mj_loadModel(filename_c.as_ptr(), vfs.ffi());
127 Self::check_raw_model(raw_model, &[])
128 }
129 }
130
131
132 pub fn save_last_xml(&self, filename: &str) -> io::Result<()> {
134 let mut error = [0i8; 100];
135 unsafe {
136 let cstring = CString::new(filename)?;
137 match mj_saveLastXML(
138 cstring.as_ptr(), self.ffi(),
139 error.as_mut_ptr(), (error.len() - 1) as i32
140 ) {
141 1 => Ok(()),
142 0 => {
143 let cstr_error = String::from_utf8_lossy(
144 std::slice::from_raw_parts(error.as_ptr() as *const u8, error.len())
147 );
148 Err(Error::new(ErrorKind::Other, cstr_error))
149 },
150 _ => unreachable!()
151 }
152 }
153 }
154
155 pub fn make_data<'m>(&'m self) -> MjData<'m> {
157 MjData::new(self)
158 }
159
160 fn check_raw_model(ptr_model: *mut mjModel, error_buffer: &[i8]) -> Result<Self, Error> {
161 if ptr_model.is_null() {
162 let err_u8 = error_buffer.into_iter().map(|x| *x as u8).take_while(|&x| x != 0).collect();
163 Err(Error::new(ErrorKind::UnexpectedEof, String::from_utf8(err_u8).expect("could not parse error")))
164 }
165 else {
166 Ok(Self(ptr_model))
167 }
168 }
169
170 fixed_size_info_method! { Model, ffi(), actuator, [
171 trntype: 1, dyntype: 1, gaintype: 1, biastype: 1, trnid: 2, actadr: 1, actnum: 1, group: 1, ctrllimited: 1,
172 forcelimited: 1, actlimited: 1, dynprm: mjNDYN as usize, gainprm: mjNGAIN as usize, biasprm: mjNBIAS as usize,
173 actearly: 1, ctrlrange: 2, forcerange: 2, actrange: 2, gear: 6, cranklength: 1, acc0: 1,
174 length0: 1, lengthrange: 2
175 ] }
176
177 fixed_size_info_method! { Model, ffi(), sensor, [
178 r#type: 1, datatype: 1, needstage: 1,
179 objtype: 1, objid: 1, reftype: 1, refid: 1, intprm: mjNSENS as usize,
180 dim: 1, adr: 1, cutoff: 1, noise: 1
181 ] }
182
183
184 fixed_size_info_method! { Model, ffi(), tendon, [
185 adr: 1, num: 1, matid: 1, group: 1, limited: 1,
186 actfrclimited: 1, width: 1, solref_lim: mjNREF as usize,
187 solimp_lim: mjNIMP as usize, solref_fri: mjNREF as usize, solimp_fri: mjNIMP as usize,
188 range: 2, actfrcrange: 2, margin: 1, stiffness: 1,
189 damping: 1, armature: 1, frictionloss: 1, lengthspring: 2,
190 length0: 1, invweight0: 1, rgba: 4
191 ] }
192
193 fixed_size_info_method! { Model, ffi(), joint, [
194 r#type: 1, qposadr: 1, dofadr: 1, bodyid: 1, group: 1,
195 limited: 1, actfrclimited: 1, actgravcomp: 1, solref: mjNREF as usize,
196 solimp: mjNIMP as usize, pos: 3, axis: 3, stiffness: 1,
197 range: 2, actfrcrange: 2, margin: 1
198 ] }
199
200 fixed_size_info_method! { Model, ffi(), geom, [
201 r#type: 1, contype: 1, conaffinity: 1, condim: 1, bodyid: 1, dataid: 1, matid: 1,
202 group: 1, priority: 1, plugin: 1, sameframe: 1, solmix: 1, solref: mjNREF as usize,
203 solimp: mjNIMP as usize,
204 size: 3, aabb: 6, rbound: 1, pos: 3, quat: 4, friction: 3, margin: 1, gap: 1,
205 fluid: mjNFLUID as usize, rgba: 4
206 ] }
207
208 fixed_size_info_method! { Model, ffi(), body, [
209 parentid: 1, rootid: 1, weldid: 1, mocapid: 1,
210 jntnum: 1, jntadr: 1, dofnum: 1, dofadr: 1,
211 treeid: 1, geomnum: 1, geomadr: 1, simple: 1,
212 sameframe: 1, pos: 3, quat: 4, ipos: 3, iquat: 4,
213 mass: 1, subtreemass: 1, inertia: 3, invweight0: 2,
214 gravcomp: 1, margin: 1, plugin: 1,
215 contype: 1, conaffinity: 1, bvhadr: 1, bvhnum: 1
216 ]}
217
218 fixed_size_info_method! { Model, ffi(), camera, [
219 mode: 1, bodyid: 1, targetbodyid: 1, pos: 3, quat: 4,
220 poscom0: 3, pos0: 3, mat0: 9, orthographic: 1, fovy: 1,
221 ipd: 1, resolution: 2, sensorsize: 2, intrinsic: 4
222 ] }
223
224 #[deprecated]
226 pub fn name2id(&self, type_: MjtObj, name: &str) -> i32 {
227 self.name_to_id(type_, name)
228 }
229
230 pub fn name_to_id(&self, type_: MjtObj, name: &str) -> i32 {
232 let c_string = CString::new(name).unwrap();
233 unsafe {
234 mj_name2id(self.0, type_ as i32, c_string.as_ptr())
235 }
236 }
237
238 pub fn clone(&self) -> Option<MjModel> {
242 let ptr = unsafe { mj_copyModel(ptr::null_mut(), self.ffi()) };
243 if ptr.is_null() {
244 None
245 }
246 else {
247 Some(MjModel(ptr))
248 }
249 }
250
251 pub fn save(&self, filename: Option<&str>, buffer: Option<&mut [u8]>) {
253 let c_filename = filename.map(|f| CString::new(f).unwrap());
254 let (buffer_ptr, buffer_len) = if let Some(b) = buffer {
255 (b.as_mut_ptr(), b.len())
256 }
257 else {
258 (ptr::null_mut(), 0)
259 };
260 let c_filename_ptr = c_filename.as_ref().map_or(ptr::null(), |f| f.as_ptr());
261
262 unsafe { mj_saveModel(
263 self.ffi(), c_filename_ptr,
264 buffer_ptr as *mut std::ffi::c_void, buffer_len as i32
265 ) };
266 }
267
268 pub fn size(&self) -> std::ffi::c_int {
270 unsafe { mj_sizeModel(self.ffi()) }
271 }
272
273 pub fn print_formatted(&self, filename: &str, float_format: &str) -> Result<(), NulError> {
276 let c_filename = CString::new(filename)?;
277 let c_float_format = CString::new(float_format)?;
278 unsafe { mj_printFormattedModel(self.ffi(), c_filename.as_ptr(), c_float_format.as_ptr()) }
279 Ok(())
280 }
281
282 pub fn print(&self, filename: &str) -> Result<(), NulError> {
284 let c_filename = CString::new(filename)?;
285 unsafe { mj_printModel(self.ffi(), c_filename.as_ptr()) }
286 Ok(())
287 }
288
289 pub fn state_size(&self, spec: std::ffi::c_uint) -> std::ffi::c_int {
291 unsafe { mj_stateSize(self.ffi(), spec) }
292 }
293
294 pub fn is_pyramidal(&self) -> bool {
296 unsafe { mj_isPyramidal(self.ffi()) == 1 }
297 }
298
299 pub fn is_sparse(&self) -> bool {
301 unsafe { mj_isSparse(self.ffi()) == 1 }
302 }
303
304 pub fn is_dual(&self) -> bool {
306 unsafe { mj_isDual(self.ffi()) == 1 }
307 }
308
309 pub fn id_to_name(&self, type_: MjtObj, id: std::ffi::c_int) -> Option<&str> {
312 let ptr = unsafe { mj_id2name(self.ffi(), type_ as i32, id) };
313 if ptr.is_null() {
314 None
315 }
316 else {
317 let cstr = unsafe { CStr::from_ptr(ptr).to_str().unwrap() };
318 Some(cstr)
319 }
320 }
321
322 pub fn get_totalmass(&self) -> MjtNum {
324 unsafe { mj_getTotalmass(self.ffi()) }
325 }
326
327 pub fn set_totalmass(&mut self, newmass: MjtNum) {
329 unsafe { mj_setTotalmass(self.ffi_mut(), newmass) }
330 }
331
332 pub fn ffi(&self) -> &mjModel {
335 unsafe { self.0.as_ref().unwrap() }
336 }
337
338 pub unsafe fn ffi_mut(&mut self) -> &mut mjModel {
340 unsafe { self.0.as_mut().unwrap() }
341 }
342
343 pub(crate) unsafe fn __raw(&self) -> *mut mjModel {
348 self.0
349 }
350}
351
352
353impl MjModel {
355 pub fn signature(&self) -> u64 {
357 self.ffi().signature
358 }
359
360 pub fn opt(&self) -> &MjOption {
362 &self.ffi().opt
363 }
364
365 pub fn opt_mut(&mut self) -> &mut MjOption {
367 &mut unsafe { self.ffi_mut() }.opt
369 }
370
371 pub fn vis(&self) -> &MjVisual {
373 &self.ffi().vis
374 }
375
376 pub fn vis_mut(&mut self) -> &mut MjVisual {
378 &mut unsafe { self.ffi_mut() }.vis
380 }
381
382 pub fn stat(&self) -> &MjStatistic {
384 &self.ffi().stat
385 }
386
387 pub fn stat_mut(&mut self) -> &mut MjStatistic {
389 &mut unsafe { self.ffi_mut() }.stat
391 }
392}
393
394
395impl Drop for MjModel {
396 fn drop(&mut self) {
397 unsafe {
398 mj_deleteModel(self.0);
399 }
400 }
401}
402
403
404info_with_view!(Model, actuator, actuator_,
408 [
409 trntype: MjtTrn, dyntype: MjtDyn, gaintype: MjtGain, biastype: MjtBias, trnid: i32,
410 actadr: i32, actnum: i32, group: i32, ctrllimited: bool,
411 forcelimited: bool, actlimited: bool, dynprm: MjtNum, gainprm: MjtNum, biasprm: MjtNum,
412 actearly: bool, ctrlrange: MjtNum, forcerange: MjtNum, actrange: MjtNum,
413 gear: MjtNum, cranklength: MjtNum, acc0: MjtNum, length0: MjtNum, lengthrange: MjtNum
414 ], []
415);
416
417
418info_with_view!(Model, sensor, sensor_,
422 [
423 r#type: MjtSensor, datatype: MjtDataType, needstage: MjtStage,
424 objtype: MjtObj, objid: i32, reftype: MjtObj, refid: i32, intprm: i32,
425 dim: i32, adr: i32, cutoff: MjtNum, noise: MjtNum
426 ], []
427);
428
429
430info_with_view!(Model, tendon, tendon_,
434 [
435 adr: i32, num: i32, matid: i32, group: i32, limited: bool,
436 actfrclimited: bool, width: MjtNum, solref_lim: MjtNum,
437 solimp_lim: MjtNum, solref_fri: MjtNum, solimp_fri: MjtNum,
438 range: MjtNum, actfrcrange: MjtNum, margin: MjtNum, stiffness: MjtNum,
439 damping: MjtNum, armature: MjtNum, frictionloss: MjtNum, lengthspring: MjtNum,
440 length0: MjtNum, invweight0: MjtNum, rgba: f32
441 ], []
442);
443
444
445info_with_view!(Model, joint, jnt_,
449 [
450 r#type: MjtJoint, qposadr: i32, dofadr: i32, bodyid: i32, group: i32,
451 limited: bool, actfrclimited: bool, actgravcomp: bool, solref: MjtNum,
452 solimp: MjtNum, pos: MjtNum, axis: MjtNum, stiffness: MjtNum,
453 range: MjtNum, actfrcrange: MjtNum, margin: MjtNum
454 ], []
455);
456
457info_with_view!(Model, geom, geom_,
461 [
462 r#type: MjtGeom, contype: i32, conaffinity: i32, condim: i32, bodyid: i32, dataid: i32, matid: i32,
463 group: i32, priority: i32, plugin: i32, sameframe: MjtSameFrame, solmix: MjtNum, solref: MjtNum, solimp: MjtNum,
464 size: MjtNum, aabb: MjtNum, rbound: MjtNum, pos: MjtNum, quat: MjtNum, friction: MjtNum, margin: MjtNum, gap: MjtNum,
465 fluid: MjtNum, rgba: f32
466 ], []
467);
468
469info_with_view!(Model, body, body_,
473 [
474 parentid: i32, rootid: i32, weldid: i32, mocapid: i32,
475 jntnum: i32, jntadr: i32, dofnum: i32, dofadr: i32,
476 treeid: i32, geomnum: i32, geomadr: i32, simple: MjtByte,
477 sameframe: MjtSameFrame, pos: MjtNum, quat: MjtNum, ipos: MjtNum, iquat: MjtNum,
478 mass: MjtNum, subtreemass: MjtNum, inertia: MjtNum, invweight0: MjtNum,
479 gravcomp: MjtNum, margin: MjtNum, plugin: i32,
480 contype: i32, conaffinity: i32, bvhadr: i32, bvhnum: i32
481 ], []
482);
483
484
485info_with_view!(Model, camera, cam_,
489 [
490 mode: MjtCamLight, bodyid: i32, targetbodyid: i32, pos: MjtNum, quat: MjtNum,
491 poscom0: MjtNum, pos0: MjtNum, mat0: MjtNum, orthographic: bool, fovy: MjtNum,
492 ipd: MjtNum, resolution: i32, sensorsize: f32, intrinsic: f32
493 ], []
494);
495
496
497#[cfg(test)]
498mod tests {
499 use crate::assert_relative_eq;
500
501 use super::*;
502 use std::fs;
503
504 const EXAMPLE_MODEL: &str = "
505 <mujoco>
506 <worldbody>
507 <camera name=\"cam1\" fovy=\"50\" resolution=\"100 200\"/>
508
509 <light ambient=\"0.2 0.2 0.2\"/>
510 <body name=\"ball\">
511 <geom name=\"green_sphere\" pos=\".2 .2 .2\" size=\".1\" rgba=\"0 1 0 1\"/>
512 <joint name=\"ball\" type=\"free\" axis=\"1 1 1\"/>
513 <site name=\"touch\" size=\"1\" type=\"box\"/>
514 </body>
515
516 <body name=\"ball1\" pos=\"-.5 0 0\">
517 <geom size=\".1\" rgba=\"0 1 0 1\" mass=\"1\"/>
518 <joint type=\"free\"/>
519 <site name=\"ball1\" size=\".1 .1 .1\" pos=\"0 0 0\" rgba=\"0 1 0 0.2\" type=\"box\"/>
520 </body>
521
522 <body name=\"ball2\" pos=\".5 0 0\">
523 <geom name=\"ball2\" size=\".5\" rgba=\"0 1 1 1\" mass=\"1\"/>
524 <joint type=\"free\"/>
525 <site name=\"ball2\" size=\".1 .1 .1\" pos=\"0 0 0\" rgba=\"0 1 1 0.2\" type=\"box\"/>
526 </body>
527
528 <geom name=\"floor\" type=\"plane\" size=\"10 10 1\" euler=\"5 0 0\"/>
529
530 <body name=\"slider\">
531 <geom name=\"rod\" type=\"cylinder\" size=\"1 10 0\" euler=\"90 0 0\" pos=\"0 0 10\"/>
532 <joint name=\"rod\" type=\"slide\" axis=\"0 1 0\" range=\"0 1\"/>
533 </body>
534 </worldbody>
535
536 <actuator>
537 <general name=\"slider\" joint=\"rod\" biastype=\"affine\" ctrlrange=\"0 1\" gaintype=\"fixed\"/>
538 </actuator>
539
540 <sensor>
541 <touch name=\"touch\" site=\"touch\"/>
542 </sensor>
543
544 <tendon>
545 <spatial name=\"tendon\" limited=\"true\" range=\"0 1\" rgba=\"0 .1 1 1\" width=\".005\">
546 <site site=\"ball1\"/>
547 <site site=\"ball2\"/>
548 </spatial>
549 </tendon>
550 </mujoco>
551 ";
552
553 #[test]
555 fn test_model_load_save() {
556 const MODEL_SAVE_XML_PATH: &str = "./__TMP_MODEL1.xml";
557 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
558 model.save_last_xml(MODEL_SAVE_XML_PATH).expect("could not save the model XML.");
559 fs::remove_file(MODEL_SAVE_XML_PATH).unwrap();
560 }
561
562 #[test]
563 fn test_actuator_model_view() {
564 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
565 let actuator_model_info = model.actuator("slider").unwrap();
566 let view = actuator_model_info.view(&model);
567
568 assert_eq!(view.biastype[0], MjtBias::mjBIAS_AFFINE);
570 assert_eq!(&view.ctrlrange[..], [0.0, 1.0]);
571 assert_eq!(view.ctrllimited[0], true);
572 assert_eq!(view.forcelimited[0], false);
573 assert_eq!(view.trntype[0], MjtTrn::mjTRN_JOINT);
574 assert_eq!(view.gaintype[0], MjtGain::mjGAIN_FIXED);
575
576 let mut view_mut = actuator_model_info.view_mut(&mut model);
578 view_mut.gaintype[0] = MjtGain::mjGAIN_AFFINE;
579 assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_AFFINE);
580 view_mut.zero();
581 assert_eq!(view_mut.gaintype[0], MjtGain::mjGAIN_FIXED);
582 }
583
584 #[test]
585 fn test_sensor_model_view() {
586 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
587 let sensor_model_info = model.sensor("touch").unwrap();
588 let view = sensor_model_info.view(&model);
589
590 assert_eq!(view.dim[0], 1);
592 assert_eq!(view.objtype[0], MjtObj::mjOBJ_SITE);
593 assert_eq!(view.noise[0], 0.0);
594 assert_eq!(view.r#type[0], MjtSensor::mjSENS_TOUCH);
595
596 let mut view_mut = sensor_model_info.view_mut(&mut model);
598 view_mut.noise[0] = 1.0;
599 assert_eq!(view_mut.noise[0], 1.0);
600 }
601
602 #[test]
603 fn test_tendon_model_view() {
604 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
605 let tendon_model_info = model.tendon("tendon").unwrap();
606 let view = tendon_model_info.view(&model);
607
608 assert_eq!(&view.range[..], [0.0, 1.0]);
610 assert_eq!(view.limited[0], true);
611 assert_eq!(view.width[0], 0.005);
612
613 let mut view_mut = tendon_model_info.view_mut(&mut model);
615 view_mut.frictionloss[0] = 5e-2;
616 assert_eq!(view_mut.frictionloss[0], 5e-2);
617 }
618
619 #[test]
620 fn test_joint_model_view() {
621 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
622 let model_info = model.joint("rod").unwrap();
623 let view = model_info.view(&model);
624
625 assert_eq!(view.r#type[0], MjtJoint::mjJNT_SLIDE);
627 assert_eq!(view.limited[0], true);
628 assert_eq!(&view.axis[..], [0.0, 1.0 , 0.0]);
629
630 let mut view_mut = model_info.view_mut(&mut model);
632 view_mut.axis.copy_from_slice(&[1.0, 0.0, 0.0]);
633 assert_eq!(&view_mut.axis[..], [1.0, 0.0 , 0.0]);
634 }
635
636 #[test]
637 fn test_geom_model_view() {
638 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
639 let model_info = model.geom("ball2").unwrap();
640 let view = model_info.view(&model);
641
642 assert_eq!(view.r#type[0], MjtGeom::mjGEOM_SPHERE);
644 assert_eq!(view.size[0], 0.5);
645
646 let mut view_mut = model_info.view_mut(&mut model);
648 view_mut.size[0] = 1.0;
649 assert_eq!(view_mut.size[0], 1.0);
650 }
651
652 #[test]
653 fn test_body_model_view() {
654 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
655 let model_info = model.body("ball2").unwrap();
656 let view = model_info.view(&model);
657
658 assert_eq!(view.pos[0], 0.5);
660
661 let mut view_mut = model_info.view_mut(&mut model);
663 view_mut.pos[0] = 1.0;
664 assert_eq!(view_mut.pos[0], 1.0);
665 }
666
667
668 #[test]
669 fn test_camera_model_view() {
670 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
671 let model_info = model.camera("cam1").unwrap();
672 let view = model_info.view(&model);
673
674 assert_eq!(&view.resolution[..], [100, 200]);
676 assert_eq!(view.fovy[0], 50.0);
677
678 let mut view_mut = model_info.view_mut(&mut model);
680 view_mut.fovy[0] = 60.0;
681 assert_eq!(view_mut.fovy[0], 60.0);
682 }
683
684 #[test]
685 fn test_id_2name_valid() {
686 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
687
688 let name = model.id_to_name(MjtObj::mjOBJ_BODY, 1);
690 assert_eq!(name, Some("ball"));
691 }
692
693 #[test]
694 fn test_model_prints() {
695 const TMP_FILE: &str = "tmpprint.txt";
696 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
697 assert!(model.print(TMP_FILE).is_ok());
698 fs::remove_file(TMP_FILE).unwrap();
699
700 assert!(model.print_formatted(TMP_FILE, "%.2f").is_ok());
701 fs::remove_file(TMP_FILE).unwrap();
702 }
703
704 #[test]
705 fn test_id_2name_invalid() {
706 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
707
708 let name = model.id_to_name(MjtObj::mjOBJ_BODY, 9999);
710 assert_eq!(name, None);
711 }
712
713 #[test]
714 fn test_totalmass_set_and_get() {
715 let mut model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
716
717 let mass_before = model.get_totalmass();
718 model.set_totalmass(5.0);
719 let mass_after = model.get_totalmass();
720
721 assert_relative_eq!(mass_after, 5.0, epsilon = 1e-9);
722 assert_ne!(mass_before, mass_after);
723 }
724
725 #[test]
727 fn test_copy_model() {
728 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
729 assert!(model.clone().is_some());
730 }
731
732 #[test]
733 fn test_model_save() {
734 const MODEL_SAVE_PATH: &str = "./__TMP_MODEL2.mjb";
735 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("unable to load the model.");
736 model.save(Some(MODEL_SAVE_PATH), None);
737
738 let saved_data = fs::read(MODEL_SAVE_PATH).unwrap();
739 let mut data = vec![0; saved_data.len()];
740 model.save(None, Some(&mut data));
741
742 assert_eq!(saved_data, data);
743 fs::remove_file(MODEL_SAVE_PATH).unwrap();
744
745 assert!(MjModel::from_buffer(&saved_data).is_ok());
747 }
748}