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