1use std::ffi::{c_int, CStr, CString};
3use std::io::{Error, ErrorKind};
4use std::marker::PhantomData;
5use std::path::Path;
6use std::ptr;
7
8#[macro_use]
9mod utility;
10use utility::*;
11
12mod traits;
13pub use traits::*;
14
15mod default;
16pub use default::*;
17
18use super::mj_model::{
19 MjModel, MjtObj, MjtGeom, MjtJoint, MjtCamLight,
20 MjtLightType, MjtSensor, MjtDataType, MjtGain,
21 MjtBias, MjtDyn, MjtEq, MjtTexture, MjtColorSpace,
22 MjtTrn, MjtStage, MjtFlexSelf
23};
24use super::mj_auxiliary::{MjVfs, MjVisual, MjStatistic, MjLROpt};
25use super::mj_option::MjOption;
26use super::mj_primitive::*;
27use crate::mujoco_c::*;
28
29use crate::getter_setter;
30
31use crate::mujoco_c::{mjs_addHField as mjs_addHfield, mjsHField as mjsHfield, mjs_asHField as mjs_asHfield};
33
34
35pub type MjsOrientation = mjsOrientation;
40impl MjsOrientation {
41 pub fn set_euler(&mut self, angle: &[f64; 3]) {
43 self.type_ = MjtOrientation::mjORIENTATION_EULER;
44 self.euler = *angle;
45 }
46
47 pub fn set_axis_angle(&mut self, angle: &[f64; 4]) {
49 self.type_ = MjtOrientation::mjORIENTATION_AXISANGLE;
50 self.axisangle = *angle;
51 }
52
53 pub fn set_xy_axis(&mut self, angle: &[f64; 6]) {
55 self.type_ = MjtOrientation::mjORIENTATION_XYAXES;
56 self.xyaxes = *angle;
57 }
58
59 pub fn set_z_axis(&mut self, angle: &[f64; 3]) {
61 self.type_ = MjtOrientation::mjORIENTATION_ZAXIS;
62 self.zaxis = *angle;
63 }
64
65 pub fn switch_quat<T: AsRef<[f64; 4]>>(&mut self) {
68 self.type_ = MjtOrientation::mjORIENTATION_QUAT;
69 }
70}
71
72pub type MjtGeomInertia = mjtGeomInertia;
74
75pub type MjtMeshInertia = mjtMeshInertia;
77
78pub type MjtBuiltin = mjtBuiltin;
80
81pub type MjtMark = mjtMark;
83
84pub type MjtLimited = mjtLimited;
86
87pub type MjtAlignFree = mjtAlignFree;
89
90pub type MjtInertiaFromGeom = mjtInertiaFromGeom;
92
93pub type MjtOrientation = mjtOrientation;
95
96pub type MjsCompiler = mjsCompiler;
98impl MjsCompiler {
99 getter_setter! {with, get, set, [
100 autolimits: bool; "infer \"limited\" attribute based on range.";
101 balanceinertia: bool; "automatically impose A + B >= C rule.";
102 fitaabb: bool; "meshfit to aabb instead of inertia box.";
103 degree: bool; "angles in radians or degrees.";
104 discardvisual: bool; "discard visual geoms in parser.";
105 usethread: bool; "use multiple threads to speed up compiler.";
106 fusestatic: bool; "fuse static bodies with parent.";
107 saveinertial: bool; "save explicit inertial clause for all bodies to XML.";
108 alignfree: bool; "align free joints with inertial frame.";
109 ]}
110
111 getter_setter! {with, get, set, [
112 boundmass: f64; "enforce minimum body mass.";
113 boundinertia: f64; "enforce minimum body diagonal inertia.";
114 settotalmass: f64; "rescale masses and inertias; <=0: ignore.";
115 ]}
116
117 getter_setter! {force!, with, get, set, [
118 inertiafromgeom: MjtInertiaFromGeom; "use geom inertias.";
119 ]}
120
121 getter_setter! {with, get, [
122 inertiagrouprange: &[i32; 2]; "range of geom groups used to compute inertia.";
123 eulerseq: &[i8; 3]; "sequence for euler rotations.";
124 LRopt: &MjLROpt; "options for lengthrange computation.";
125 ]}
126
127
128 #[inline]
130 fn ffi(&self) -> &Self {
131 self
132 }
133
134 #[inline]
135 unsafe fn ffi_mut(&mut self) -> &mut Self {
136 self
137 }
138}
139
140pub struct MjSpec(*mut mjSpec);
145
146unsafe impl Sync for MjSpec {}
148unsafe impl Send for MjSpec {}
149
150impl MjSpec {
151 pub fn new() -> Self {
153 unsafe { Self::check_spec(mj_makeSpec(), &[0]).unwrap() }
154 }
155
156 pub fn from_xml<T: AsRef<Path>>(path: T) -> Result<Self, Error> {
160 Self::from_xml_file(path, None)
161 }
162
163 pub fn from_xml_vfs<T: AsRef<Path>>(path: T, vfs: &MjVfs) -> Result<Self, Error> {
167 Self::from_xml_file(path, Some(vfs))
168 }
169
170 fn from_xml_file<T: AsRef<Path>>(path: T, vfs: Option<&MjVfs>) -> Result<Self, Error> {
171 let mut error_buffer = [0i8; 100];
172 unsafe {
173 let path = CString::new(path.as_ref().to_str().expect("invalid utf")).unwrap();
174 let raw_ptr = mj_parseXML(
175 path.as_ptr(), vfs.map_or(ptr::null(), |v| v.ffi()),
176 &mut error_buffer as *mut i8, error_buffer.len() as c_int
177 );
178
179 Self::check_spec(raw_ptr, &error_buffer)
180 }
181 }
182
183 pub fn from_xml_string(xml: &str) -> Result<Self, Error> {
187 let c_xml = CString::new(xml).unwrap();
188 let mut error_buffer = [0i8; 100];
189 unsafe {
190 let spec_ptr = mj_parseXMLString(
191 c_xml.as_ptr(), ptr::null(),
192 &mut error_buffer as *mut i8, error_buffer.len() as c_int
193 );
194 Self::check_spec(spec_ptr, &error_buffer)
195 }
196 }
197
198 unsafe fn check_spec(spec_ptr: *mut mjSpec, error_buffer: &[i8]) -> Result<Self, Error> {
202 if spec_ptr.is_null() {
203 Err(Error::new(
205 ErrorKind::UnexpectedEof,
206 unsafe { CStr::from_ptr(error_buffer.as_ptr().cast()).to_string_lossy().into_owned() }
207 ))
208 }
209 else {
210 Ok(MjSpec(spec_ptr))
211 }
212 }
213
214 pub fn ffi(&self) -> &mjSpec {
216 unsafe { self.0.as_ref().unwrap() }
217 }
218
219 pub unsafe fn ffi_mut(&mut self) -> &mut mjSpec {
221 unsafe { self.0.as_mut().unwrap() }
222 }
223
224 pub fn compile(&mut self) -> Result<MjModel, Error> {
228 let result = unsafe { MjModel::from_raw( mj_compile(self.0, ptr::null()) ) };
229 result.map_err(|_| {
230 let error = unsafe { CStr::from_ptr(mjs_getError(self.ffi_mut())).to_string_lossy().into_owned() };
231 Error::new(ErrorKind::InvalidData, error)
232 })
233 }
234
235 pub fn save_xml(&self, filename: &str) -> Result<(), Error> {
239 let mut error_buff = [0; 100];
240 let cname = CString::new(filename).unwrap(); let result = unsafe { mj_saveXML(
242 self.ffi(), cname.as_ptr(),
243 error_buff.as_mut_ptr(), error_buff.len() as i32
244 ) };
245 match result {
246 0 => Ok(()),
247 _ => Err(
248 Error::new(
249 ErrorKind::Other,
250 unsafe { CStr::from_ptr(error_buff.as_ptr().cast()).to_string_lossy().into_owned() }
251 ))
252 }
253 }
254
255 pub fn save_xml_string(&self, buffer_size: usize) -> Result<String, Error> {
258 let mut error_buff = [0; 100];
259 let mut result_buff = vec![0u8; buffer_size];
260 let result = unsafe { mj_saveXMLString(
261 self.ffi(), result_buff.as_mut_ptr().cast(), result_buff.len() as i32,
262 error_buff.as_mut_ptr(), error_buff.len() as i32
263 ) };
264 match result {
265 0 => Ok(CStr::from_bytes_until_nul(&result_buff).unwrap().to_string_lossy().into_owned()),
266 _ => Err(
267 Error::new(
268 ErrorKind::Other,
269 unsafe { CStr::from_ptr(error_buff.as_ptr().cast()).to_string_lossy().to_string() }
270 ))
271 }
272 }
273}
274
275impl MjSpec {
277 find_x_method! {
278 body, geom, joint, site, camera, light, actuator, sensor, flex, pair, equality, exclude, tendon,
279 numeric, text, tuple, key, mesh, hfield, skin, texture, material, plugin
280 }
281
282 find_x_method_direct! { default }
283
284 pub fn world_body(&mut self) -> MjsBody<'_> {
286 self.body("world").unwrap() }
288}
289
290impl MjSpec {
292 string_set_get_with! {
293 modelname; "model name.";
294 comment; "comment at top of XML.";
295 modelfiledir; "path to model file.";
296 }
297
298 getter_setter! {
299 with, get, [
300 compiler: &MjsCompiler; "compiler options.";
301 stat: &MjStatistic; "statistic overrides.";
302 visual: &MjVisual; "visualization options.";
303 option: &MjOption; "simulation options";
304 ]
305 }
306
307 getter_setter! {
308 with, get, set, [strippath: bool; "whether to strip paths from mesh files."]
309 }
310
311 getter_setter! {
312 get, [
313 memory: MjtSize; "number of bytes in arena+stack memory";
314 nemax: i32; "max number of equality constraints.";
315 nuserdata: i32; "number of mjtNums in userdata.";
316 nuser_body: i32; "number of mjtNums in body_user.";
317 nuser_jnt: i32; "number of mjtNums in jnt_user.";
318 nuser_geom: i32; "number of mjtNums in geom_user.";
319 nuser_site: i32; "number of mjtNums in site_user.";
320 nuser_cam: i32; "number of mjtNums in cam_user.";
321 nuser_tendon: i32; "number of mjtNums in tendon_user.";
322 nuser_actuator: i32; "number of mjtNums in actuator_user.";
323 nuser_sensor: i32; "number of mjtNums in sensor_user.";
324 nkey: i32; "number of keyframes.";
325 ]
326 }
327}
328
329impl MjSpec {
331 add_x_method! { actuator, pair, equality, tendon, mesh, material }
332 add_x_method_no_default! {
333 sensor, flex, exclude, numeric, text, tuple, key, plugin,
334 hfield, skin, texture
335 }
337
338 pub fn add_default(&mut self, class_name: &str, parent_class_name: Option<&str>) -> Result<MjsDefault<'_>, Error> {
345 let c_class_name = CString::new(class_name).unwrap();
346
347 let parent_ptr = if let Some(name) = parent_class_name {
348 self.default(name).ok_or_else(
349 || Error::new(ErrorKind::NotFound, "invalid parent name")
350 )?.0
351 } else {
352 ptr::null()
353 };
354
355 unsafe {
356 let ptr_default = mjs_addDefault(
357 self.ffi_mut(),
358 c_class_name.as_ptr(),
359 parent_ptr
360 );
361 if ptr_default.is_null() {
362 Err(Error::new(ErrorKind::AlreadyExists, "duplicated name"))
363 }
364 else {
365 Ok(MjsDefault(ptr_default, PhantomData))
366 }
367 }
368 }
369}
370
371impl Drop for MjSpec {
372 fn drop(&mut self) {
373 unsafe { mj_deleteSpec(self.0); }
374 }
375}
376
377mjs_wrapper!(Site);
381impl MjsSite<'_> {
382 getter_setter! {
383 with, get, [
384 pos: &[f64; 3]; "position";
386 quat: &[f64; 4]; "orientation";
387 alt: &MjsOrientation; "alternative orientation";
388 fromto: &[f64; 6]; "alternative for capsule, cylinder, box, ellipsoid";
389 size: &[f64; 3]; "geom size";
390
391 rgba: &[f32; 4]; "rgba when material is omitted";
393 ]}
394
395 getter_setter!(with, get, set, [
396 type_: MjtGeom; "geom type";
397 group: i32; "group";
398 ]);
399
400 userdata_method!(f64);
401
402 string_set_get_with! {
403 material; "name of material.";
404 }
405}
406
407mjs_wrapper!(Joint);
411impl MjsJoint<'_> {
412 getter_setter! {
413 with, get, [
414 pos: &[f64; 3]; "joint position.";
415 axis: &[f64; 3]; "joint axis.";
416 ref_: &f64; "joint reference.";
417 range: &[f64; 2]; "joint range.";
418 ]
419 }
420
421 getter_setter!(with, get, set, [
422 type_: MjtJoint; "joint type.";
423 group: i32; "joint group.";
424 ]);
425
426 userdata_method!(f64);
427}
428
429mjs_wrapper!(Geom);
433impl MjsGeom<'_> {
434 getter_setter! {
435 with, get, [
436 pos: &[f64; 3]; "geom position.";
437 quat: &[f64; 4]; "geom orientation.";
438 alt: &MjsOrientation; "alternative orientation.";
439 fromto: &[f64; 6]; "alternative for capsule, cylinder, box, ellipsoid.";
440 size: &[f64; 3]; "geom size.";
441 rgba: &[f32; 4]; "rgba when material is omitted.";
442 friction: &[f64; 3]; "one-sided friction coefficients: slide, roll, spin.";
443 solref: &[MjtNum; mjNREF as usize]; "solver reference.";
444 solimp: &[MjtNum; mjNIMP as usize]; "solver impedance.";
445 fluid_coefs: &[MjtNum; 5]; "ellipsoid-fluid interaction coefs."
446 ]
447 }
448
449 getter_setter!(with, get, set, [
450 type_: MjtGeom; "geom type.";
451 group: i32; "group.";
452 contype: i32; "contact type.";
453 conaffinity: i32; "contact affinity.";
454 condim: i32; "contact dimensionality.";
455 priority: i32; "contact priority.";
456 solmix: f64; "solver mixing for contact pairs.";
457 margin: f64; "margin for contact detection.";
458 gap: f64; "include in solver if dist < margin-gap.";
459 mass: f64; "used to compute density.";
460 density: f64; "used to compute mass and inertia from volume or surface.";
461 typeinertia: MjtGeomInertia; "selects between surface and volume inertia.";
462 fluid_ellipsoid: MjtNum; "whether ellipsoid-fluid model is active.";
463 fitscale: f64; "scale mesh uniformly.";
464 ]);
465
466 userdata_method!(f64);
467
468 string_set_get_with! {
469 meshname; "mesh attached to geom.";
470 material; "name of material.";
471 hfieldname; "heightfield attached to geom.";
472 }
473
474 plugin_wrapper_method!();
475}
476
477mjs_wrapper!(Camera);
481impl MjsCamera<'_> {
482 getter_setter! {
483 with, get, [
484 pos: &[f64; 3]; "camera position.";
485 quat: &[f64; 4]; "camera orientation.";
486 alt: &MjsOrientation; "alternative orientation.";
487 intrinsic: &[f32; 4]; "intrinsic parameters.";
488 sensor_size: &[f32; 2]; "sensor size.";
489 resolution: &[f32; 2]; "resolution.";
490 focal_length: &[f32; 2]; "focal length (length).";
491 focal_pixel: &[f32; 2]; "focal length (pixel).";
492 principal_length: &[f32; 2]; "principal point (length).";
493 principal_pixel: &[f32; 2]; "principal point (pixel).";
494 ]
495 }
496
497 getter_setter!(with, get, set, [
498 mode: MjtCamLight; "camera mode.";
499 fovy: f64; "field of view in y direction.";
500 ipd: f64; "inter-pupillary distance for stereo.";
501 ]);
502
503 getter_setter! {
504 with, get, set, [orthographic: bool; "is camera orthographic."]
505 }
506
507 userdata_method!(f64);
508
509 string_set_get_with! {
510 targetbody; "target body for tracking/targeting.";
511 }
512}
513
514mjs_wrapper!(Light);
518impl MjsLight<'_> {
519 getter_setter! {
520 with, get, [
521 pos: &[f64; 3]; "light position.";
522 dir: &[f64; 3]; "light direction.";
523 ambient: &[f32; 3]; "ambient color.";
524 diffuse: &[f32; 3]; "diffuse color.";
525 specular: &[f32; 3]; "specular color.";
526 attenuation: &[f32; 3]; "OpenGL attenuation (quadratic model).";
527 ]
528 }
529
530 getter_setter!(with, get, set, [
531 mode: MjtCamLight; "light mode.";
532 type_: MjtLightType; "light type.";
533 bulbradius: f32; "bulb radius, for soft shadows.";
534 intensity: f32; "intensity, in candelas.";
535 range: f32; "range of effectiveness.";
536 cutoff: f32; "OpenGL cutoff.";
537 exponent: f32; "OpenGL exponent.";
538 ]);
539
540 getter_setter! {
541 with, get, set, [
542 active: bool; "active flag.";
543 castshadow: bool; "whether light cast shadows."
544 ]
545 }
546
547 string_set_get_with! {
548 texture; "texture name for image lights.";
549 targetbody; "target body for targeting.";
550 }
551}
552
553mjs_wrapper!(Frame);
557impl MjsFrame<'_> {
558 add_x_method_by_frame! { body, site, joint, geom, camera, light }
559
560 getter_setter! {
561 with, get, [
562 pos: &[f64; 3]; "frame position.";
563 quat: &[f64; 4]; "frame orientation.";
564 alt: &MjsOrientation; "alternative orientation.";
565 ]
566 }
567
568 string_set_get_with! {
569 childclass; "childclass name.";
570 }
571
572 pub fn add_frame(&mut self) -> MjsFrame<'_> {
574 unsafe {
575 let parent_body = mjs_getParent(self.element_mut_pointer());
576 let parent_frame = self.element_mut_pointer();
577 let frame_ptr = mjs_addFrame(parent_body, parent_frame.cast());
578 MjsFrame(frame_ptr, PhantomData)
579 }
580 }
581}
582
583mjs_wrapper!(Actuator);
589impl MjsActuator<'_> {
590 getter_setter! {
591 with, get, [
592 gear: &[f64; 6]; "gear parameters.";
593 gainprm: &[f64; mjNGAIN as usize]; "gain parameters.";
594 biasprm: &[f64; mjNBIAS as usize]; "bias parameters.";
595 dynprm: &[f64; mjNDYN as usize]; "dynamic parameters.";
596 lengthrange: &[f64; 2]; "transmission length range.";
597 ctrlrange: &[f64; 2]; "control range.";
598 forcerange: &[f64; 2]; "force range.";
599 actrange: &[f64; 2]; "activation range.";
600 ]
601 }
602
603 getter_setter!(with, get, set, [
604 gaintype: MjtGain; "gain type.";
605 biastype: MjtBias; "bias type.";
606 dyntype: MjtDyn; "dyn type.";
607 group: i32; "group.";
608 actdim: i32; "number of activation variables.";
609 trntype: MjtTrn; "transmission type.";
610 cranklength: f64; "crank length, for slider-crank.";
611 inheritrange: f64; "automatic range setting for position and intvelocity.";
612 ]);
613
614 getter_setter! {
615 force!, with, get, set, [
616 ctrllimited: MjtLimited; "are control limits defined.";
617 forcelimited: MjtLimited; "are force limits defined.";
618 actlimited: MjtLimited; "are activation limits defined.";
619 ]
620 }
621
622 getter_setter! {
623 with, get, set, [
624 actearly: bool; "apply next activations to qfrc.";
625 ]
626 }
627
628 userdata_method!(f64);
629
630 string_set_get_with! {
631 target; "name of transmission target";
632 refsite; "reference site, for site transmission";
633 slidersite; "site defining cylinder, for slider-crank";
634 }
635
636 plugin_wrapper_method!();
637}
638
639mjs_wrapper!(Sensor);
643impl MjsSensor<'_> {
644 getter_setter! {
645 with, get, [
646 intprm: &[i32; mjNSENS as usize]; "integer parameters.";
647 ]
648 }
649
650 getter_setter!(with, get, set, [
651 type_: MjtSensor; "sensor type.";
652 objtype: MjtObj; "object type the sensor refers to.";
653 reftype: MjtObj; "type of referenced object";
654 datatype: MjtDataType; "data type.";
655 cutoff: f64; "cutoff for real and positive datatypes.";
656 noise: f64; "noise stdev.";
657 needstage: MjtStage; "compute stage needed to simulate sensor.";
658 dim: i32; "number of scalar outputs.";
659 ]);
660
661 userdata_method!(f64);
662
663 string_set_get_with! {
664 refname; "name of referenced object.";
665 objname; "name of sensorized object.";
666 }
667
668 plugin_wrapper_method!();
669}
670
671mjs_wrapper!(Flex);
675impl MjsFlex<'_> {
676 getter_setter! {
677 with, get, [
678 rgba: &[f32; 4]; "rgba when material is omitted.";
679 friction: &[f64; 3]; "contact friction vector.";
680 solref: &[MjtNum; mjNREF as usize]; "solref for the pair.";
681 solimp: &[MjtNum; mjNIMP as usize]; "solimp for the pair.";
682 ]
683 }
684
685 getter_setter! {
686 with, get, set, [
687 young: f64; "elastic stiffness.";
688 group: i32; "group.";
689 contype: i32; "contact type.";
690 conaffinity: i32; "contact affinity.";
691 condim: i32; "contact dimensionality.";
692 priority: i32; "contact priority.";
693 solmix: f64; "solver mixing for contact pairs.";
694 margin: f64; "margin for contact detection.";
695 gap: f64; "include in solver if dist < margin-gap.";
696
697 dim: i32; "element dimensionality.";
698 radius: f64; "radius around primitive element.";
699 activelayers: i32; "number of active element layers in 3D.";
700 edgestiffness: f64; "edge stiffness.";
701 edgedamping: f64; "edge damping.";
702 poisson: f64; "Poisson's ratio.";
703 damping: f64; "Rayleigh's damping.";
704 thickness: f64; "thickness (2D only).";
705 elastic2d: i32; "2D passive forces; 0: none, 1: bending, 2: stretching, 3: both.";
706 ]
707 }
708
709 getter_setter! {
710 with, get, set, [
711 internal: bool; "enable internal collisions.";
712 flatskin: bool; "render flex skin with flat shading.";
713 vertcollide: bool; "mode for vertex collision.";
714 ]
715 }
716
717 getter_setter! {
718 force!, with, get, set, [
719 selfcollide: MjtFlexSelf; "mode for flex self collision.";
720 ]
721 }
722
723 string_set_get_with! {
724 material; "name of material used for rendering.";
725 }
726
727 vec_string_set_append! {
728 nodebody; "node body names.";
729 vertbody; "vertex body names.";
730 }
731
732 vec_set_get! {
733 node: f64; "node positions.";
734 vert: f64; "vertex positions.";
735 }
736
737 vec_set! {
738 texcoord: f32; "vertex texture coordinates";
739 elem: i32; "element vertex ids.";
740 elemtexcoord: i32; "element texture coordinates.";
741 }
742}
743
744mjs_wrapper!(Pair);
748impl MjsPair<'_> {
749 getter_setter! {
750 with, get, [
751 friction: &[f64; 5]; "contact friction vector.";
752 solref: &[MjtNum; mjNREF as usize]; "solref for the pair.";
753 solimp: &[MjtNum; mjNIMP as usize]; "solimp for the pair.";
754 solreffriction: &[MjtNum; mjNREF as usize]; "solver reference, frictional directions.";
755 ]
756 }
757
758 getter_setter! {
759 with, get, set, [
760 margin: f64; "margin for contact detection.";
761 gap: f64; "include in solver if dist<margin-gap.";
762 condim: i32; "contact dimensionality.";
763 ]
764 }
765
766 string_set_get_with! {
767 geomname1; "name of geom 1.";
768 geomname2; "name of geom 2.";
769 }
770}
771
772mjs_wrapper!(Exclude);
776impl MjsExclude<'_> {
777 string_set_get_with! {
778 bodyname1; "name of body 1.";
779 bodyname2; "name of body 2.";
780 }
781}
782
783mjs_wrapper!(Equality);
787impl MjsEquality<'_> {
788 getter_setter! {
789 with, get, [
790 data: &[f64; mjNEQDATA as usize]; "data array for equality parameters.";
791 solref: &[f64; mjNREF as usize]; "solver reference";
792 solimp: &[f64; mjNIMP as usize]; "solver impedance";
793 ]
794 }
795
796 getter_setter! {with, get, set, [
797 active: bool; "active flag.";
798 ]}
799
800 getter_setter! {with, get, set, [
801 type_: MjtEq; "equality type.";
802 objtype: MjtObj; "type of both objects";
803 ]}
804
805 string_set_get_with! {
806 name1; "name of object 1";
807 name2; "name of object 2";
808 }
809}
810
811mjs_wrapper!(Tendon);
815impl MjsTendon<'_> {
816 getter_setter! {
817 with, get, [
818 springlength: &[f64; 2]; "spring length.";
819 solref_friction: &[f64; mjNREF as usize]; "solver reference: tendon friction.";
820 solimp_friction: &[f64; mjNIMP as usize]; "solver impedance: tendon friction.";
821 range: &[f64; 2]; "range.";
822 actfrcrange: &[f64; 2]; "actuator force limits.";
823 solref_limit: &[f64; mjNREF as usize]; "solver reference: tendon limits.";
824 solimp_limit: &[f64; mjNIMP as usize]; "solver impedance: tendon limits.";
825 rgba: &[f32; 4]; "rgba when material omitted.";
826 ]
827 }
828
829 getter_setter! {with, get, set, [
830 group: i32; "group.";
831 damping: f64; "damping coefficient.";
832 stiffness: f64; "stiffness coefficient.";
833 frictionloss: f64; "friction loss.";
834 armature: f64; "inertia associated with tendon velocity.";
835 margin: f64; "margin value for tendon limit detection.";
836 width: f64; "width for rendering.";
837 ]}
838
839 getter_setter! {
840 with, get, set, [
841 limited: bool; "does tendon have limits (mjtLimited).";
842 actfrclimited: bool; "does tendon have actuator force limits."
843 ]
844 }
845
846 userdata_method!(f64);
847 string_set_get_with! {
848 material; "name of material for rendering.";
849 }
850
851 pub fn wrap_site(&mut self, name: &str) -> MjsWrap<'_> {
855 let cname = CString::new(name).unwrap();
856 let wrap_ptr = unsafe { mjs_wrapSite(self.ffi_mut(), cname.as_ptr()) };
857 MjsWrap(wrap_ptr, PhantomData)
858 }
859
860 pub fn wrap_geom(&mut self, name: &str, sidesite: &str) -> MjsWrap<'_> {
864 let cname = CString::new(name).unwrap();
865 let csidesite = CString::new(sidesite).unwrap();
866 let wrap_ptr = unsafe { mjs_wrapGeom(
867 self.ffi_mut(),
868 cname.as_ptr(), csidesite.as_ptr()
869 ) };
870 MjsWrap(wrap_ptr, PhantomData)
871 }
872
873 pub fn wrap_joint(&mut self, name: &str, coef: f64) -> MjsWrap<'_> {
877 let cname = CString::new(name).unwrap();
878 let wrap_ptr = unsafe { mjs_wrapJoint(self.ffi_mut(), cname.as_ptr(), coef) };
879 MjsWrap(wrap_ptr, PhantomData)
880 }
881
882 pub fn wrap_pulley(&mut self, divisor: f64) -> MjsWrap<'_> {
884 let wrap_ptr = unsafe { mjs_wrapPulley(self.ffi_mut(), divisor) };
885 MjsWrap(wrap_ptr, PhantomData)
886 }
887}
888
889mjs_wrapper!(Wrap);
893impl MjsWrap<'_> {
894 }
896
897mjs_wrapper!(Numeric);
901impl MjsNumeric<'_> {
902 getter_setter! {
903 with, get, set, [
904 size: i32; "size of the numeric array.";
905 ]
906 }
907
908 vec_set_get! {
909 data: f64; "initialization data.";
910 }
911}
912
913mjs_wrapper!(Text);
917impl MjsText<'_> {
918 string_set_get_with! {
919 data; "text string.";
920 }
921}
922
923mjs_wrapper!(Tuple);
927impl MjsTuple<'_> {
928 vec_set! {
929 objtype: i32; "object types.";
930 }
931
932 vec_string_set_append! {
933 objname; "object names.";
934 }
935
936 vec_set_get! {
937 objprm: f64; "object parameters.";
938 }
939}
940
941mjs_wrapper!(Key);
945impl MjsKey<'_> {
946 getter_setter! {
947 with, get, set, [
948 time: f64; "time."
949 ]
950 }
951
952 vec_set_get! {
953 qpos: f64; "qpos.";
954 qvel: f64; "qvel.";
955 act: f64; "act.";
956 mpos: f64; "mocap pos.";
957 mquat: f64; "mocap quat.";
958 ctrl: f64; "ctrl.";
959 }
960}
961
962mjs_wrapper!(Plugin);
966impl MjsPlugin<'_> {
967 string_set_get_with! {
968 name; "instance name.";
969 plugin_name; "plugin name.";
970 }
971
972 getter_setter! {
973 with, get, set, [
974 active: bool; "is the plugin active.";
975 ]
976 }
977}
978
979mjs_wrapper!(Mesh);
985impl MjsMesh<'_> {
986 getter_setter! {
987 with, get, [
988 refpos: &[f64; 3]; "reference position.";
989 refquat: &[f64; 4]; "reference orientation.";
990 scale: &[f64; 3]; "scale vector.";
991 ]
992 }
993
994 getter_setter! {
995 with, get, set, [
996 inertia: MjtMeshInertia; "inertia type (convex, legacy, exact, shell).";
997 smoothnormal: MjtByte; "do not exclude large-angle faces from normals.";
998 needsdf: MjtByte; "compute sdf from mesh.";
999 maxhullvert: i32; "maximum vertex count for the convex hull.";
1000 ]
1001 }
1002
1003 string_set_get_with! {
1004 content_type; "content type of file.";
1005 file; "mesh file.";
1006 }
1007
1008 vec_set! {
1009 uservert: f32; "user vertex data.";
1010 usernormal: f32; "user normal data.";
1011 usertexcoord: f32; "user texcoord data.";
1012 userface: i32; "user vertex indices.";
1013 userfacetexcoord: i32; "user texcoord indices.";
1014 }
1015
1016 plugin_wrapper_method!();
1017}
1018
1019mjs_wrapper!(Hfield);
1023impl MjsHfield<'_> {
1024 getter_setter! {
1025 with, get, [
1026 size: &[f64; 4]; "size of the hfield.";
1027 ]
1028 }
1029
1030 getter_setter! { with, get, set, [
1031 nrow: i32; "number of rows.";
1032 ncol: i32; "number of columns.";
1033 ]}
1034
1035 string_set_get_with! {
1036 content_type; "content type of file.";
1037 file; "file: (nrow, ncol, [elevation data]).";
1038 }
1039
1040 pub fn set_userdata<T: AsRef<[f32]>>(&mut self, userdata: T) {
1042 write_mjs_vec_f32(userdata.as_ref(), unsafe {self.ffi_mut().userdata.as_mut().unwrap() })
1043 }
1044}
1045
1046mjs_wrapper!(Skin);
1050impl MjsSkin<'_> {
1051 getter_setter! {
1052 with, get, [
1053 rgba: &[f32; 4]; "rgba when material is omitted.";
1054 ]
1055 }
1056
1057 getter_setter! {
1058 with, get, set, [
1059 inflate: f32; "inflate in normal direction.";
1060 group: i32; "group for visualization.";
1061 ]
1062 }
1063
1064 string_set_get_with! {
1065 material; "name of material used for rendering.";
1066 file; "skin file.";
1067 }
1068
1069 vec_string_set_append! {
1070 bodyname; "body names.";
1071 }
1072
1073 vec_set! {
1074 vert: f32; "vertex positions.";
1075 texcoord: f32; "texture coordinates.";
1076 bindpos: f32; "bind pos.";
1077 bindquat: f32; "bind quat.";
1078 face: i32; "faces.";
1079 }
1080
1081 vec_vec_append! {
1082 vertid: i32; "vertex ids.";
1083 vertweight: f32; "vertex weights.";
1084 }
1085}
1086
1087mjs_wrapper!(Texture);
1091impl MjsTexture<'_> {
1092 getter_setter! {
1093 with, get, [
1094 rgb1: &[f64; 3]; "first color for builtin";
1095 rgb2: &[f64; 3]; "second color for builtin";
1096 markrgb: &[f64; 3]; "mark color";
1097 gridsize: &[i32; 2]; "size of grid for composite file; (1,1)-repeat";
1098 gridlayout: &[i8; 13]; "row-major: L,R,F,B,U,D for faces; . for unused";
1099 ]
1100 }
1101
1102 getter_setter! {
1103 with, get, set, [
1104 random: f64; "probability of random dots";
1105 width: i32; "image width.";
1106 height: i32; "image height.";
1107 nchannel: i32; "number of channels.";
1108 ]
1109 }
1110
1111 getter_setter! {
1112 force!, with, get, set, [
1113 type_: MjtTexture; "texture type.";
1114 colorspace: MjtColorSpace; "colorspace.";
1115 builtin: MjtBuiltin; "builtin type";
1116 mark: MjtMark; "mark type";
1117 ]
1118 }
1119
1120 vec_string_set_append! {
1121 cubefiles; "different file for each side of the cube.";
1122 }
1123
1124 getter_setter! {with, get, set, [
1125 hflip: bool; "horizontal flip.";
1126 vflip: bool; "vertical flip.";
1127 ]}
1128
1129 pub fn set_data<T>(&mut self, data: &[T]) {
1131 write_mjs_vec_byte(data, unsafe { self.ffi_mut().data.as_mut().unwrap() });
1132 }
1133
1134 string_set_get_with! {
1135 file; "png file to load; use for all sides of cube.";
1136 content_type; "content type of file.";
1137 }
1138}
1139
1140mjs_wrapper!(Material);
1144impl MjsMaterial<'_> {
1145 getter_setter! {
1146 with, get, [
1147 rgba: &[f32; 4]; "rgba color.";
1148 texrepeat: &[f32; 2]; "texture repetition for 2D mapping";
1149 ]
1150 }
1151
1152 getter_setter! {with, get, set, [
1153 texuniform: bool; "make texture cube uniform";
1154 ]}
1155
1156 getter_setter! {
1157 with, get, set, [
1158 emission: f32; "emission";
1159 specular: f32; "specular";
1160 shininess: f32; "shininess";
1161 reflectance: f32; "reflectance";
1162 metallic: f32; "metallic";
1163 roughness: f32; "roughness";
1164 ]
1165 }
1166
1167 vec_string_set_append! {
1168 textures; "names of textures (empty: none).";
1169 }
1170}
1171
1172
1173mjs_wrapper!(Body);
1177impl MjsBody<'_> {
1178 add_x_method! { body, site, joint, geom, camera, light }
1179
1180 pub fn add_frame(&mut self) -> MjsFrame<'_> {
1183 let ptr = unsafe { mjs_addFrame(self.ffi_mut(), ptr::null_mut()) };
1184 MjsFrame(ptr, PhantomData)
1185 }
1186
1187 pub fn delete(self) -> Result<(), Error> {
1192 if self.name() != "world" {
1193 SpecItem::delete(self)
1194 }
1195 else {
1196 Err(Error::new(ErrorKind::Unsupported, "the world body can't be deleted"))
1197 }
1198 }
1199}
1200
1201impl MjsBody<'_> {
1202 getter_setter! {
1204 with, get, [
1205 pos: &[f64; 3]; "frame position.";
1207 quat: &[f64; 4]; "frame orientation.";
1208 alt: &MjsOrientation; "frame alternative orientation.";
1209
1210 ipos: &[f64; 3]; "inertial frame position.";
1212 iquat: &[f64; 4]; "inertial frame orientation.";
1213 inertia: &[f64; 3]; "diagonal inertia (in i-frame).";
1214 ialt: &MjsOrientation; "inertial frame alternative orientation.";
1215 fullinertia: &[f64; 6]; "non-axis-aligned inertia matrix.";
1216 ]
1217 }
1218
1219 getter_setter! {
1221 with, get, set, [
1222 mass: f64; "mass.";
1223 gravcomp: f64; "gravity compensation.";
1224 ]
1225 }
1226
1227 getter_setter! {
1228 with, get, set, [
1229 mocap: bool; "whether this is a mocap body.";
1230 explicitinertial: bool; "whether to save the body with explicit inertial clause.";
1231 ]
1232 }
1233
1234
1235 plugin_wrapper_method!();
1237
1238 userdata_method!(f64);
1239}
1240
1241
1242#[cfg(test)]
1246mod tests {
1247 use std::io::Write;
1248 use std::fs;
1249
1250 use super::*;
1251
1252 const MODEL: &str = "\
1253<mujoco>
1254 <worldbody>
1255 <light ambient=\"0.2 0.2 0.2\"/>
1256 <body name=\"ball\" pos=\".2 .2 .1\">
1257 <geom name=\"green_sphere\" size=\".1\" rgba=\"0 1 0 1\" solref=\"0.004 1.0\"/>
1258 <joint name=\"ball\" type=\"free\"/>
1259 </body>
1260 <geom name=\"floor1\" type=\"plane\" size=\"10 10 1\" solref=\"0.004 1.0\"/>
1261 </worldbody>
1262</mujoco>";
1263
1264 #[test]
1265 fn test_parse_xml_string() {
1266 assert!(MjSpec::from_xml_string(MODEL).is_ok(), "failed to parse the model");
1267 }
1268
1269 #[test]
1270 fn test_parse_xml_file() {
1271 const PATH: &str = "./mj_spec_test_parse_xml_file.xml";
1272 let mut file = fs::File::create(PATH).expect("file creation failed");
1273 file.write_all(MODEL.as_bytes()).expect("unable to write to file");
1274 file.flush().unwrap();
1275
1276 let spec = MjSpec::from_xml(PATH);
1277 fs::remove_file(PATH).expect("file removal failed");
1278 assert!(spec.is_ok(), "failed to parse the model");
1279 }
1280
1281 #[test]
1282 fn test_parse_xml_vfs() {
1283 const PATH: &str = "./mj_spec_test_parse_xml_vfs.xml";
1284 let mut vfs = MjVfs::new();
1285 vfs.add_from_buffer(PATH, MODEL.as_bytes()).unwrap();
1286 assert!(MjSpec::from_xml_vfs(PATH, &vfs).is_ok(), "failed to parse the model");
1287 }
1288
1289 #[test]
1290 fn test_basic_edit_compile() {
1291 const TIMESTEP: f64 = 0.010;
1292 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1293 spec.option_mut().timestep = TIMESTEP; let compiled = spec.compile().expect("could not compile the model");
1296 assert_eq!(compiled.opt().timestep, TIMESTEP);
1297
1298 spec.compile().unwrap();
1299 }
1300
1301 #[test]
1302 fn test_model_name() {
1303 const DEFAULT_MODEL_NAME: &str = "MuJoCo Model";
1304 const NEW_MODEL_NAME: &str = "Test model";
1305
1306 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1307
1308 assert_eq!(spec.modelname(), DEFAULT_MODEL_NAME);
1310 spec.set_modelname(NEW_MODEL_NAME);
1312 assert_eq!(spec.modelname(), NEW_MODEL_NAME);
1313
1314 spec.compile().unwrap();
1315 }
1316
1317 #[test]
1318 fn test_item_name() {
1319 const NEW_MODEL_NAME: &str = "Test model";
1320
1321 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1322 let mut world = spec.world_body();
1323 let mut body = world.add_body();
1324 assert_eq!(body.name(), "");
1325 body.set_name(NEW_MODEL_NAME);
1326 assert_eq!(body.name(), NEW_MODEL_NAME);
1327
1328 spec.compile().unwrap();
1329 }
1330
1331 #[test]
1332 fn test_body_remove() {
1333 const NEW_MODEL_NAME: &str = "Test model";
1334
1335 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1336 let mut world = spec.world_body();
1337 let mut body = world.add_body();
1338 body.set_name(NEW_MODEL_NAME);
1339 drop(body);
1340
1341 let body = spec.body(NEW_MODEL_NAME).expect("failed to obtain the body");
1343 assert!(body.delete().is_ok(), "failed to delete model");
1344 assert!(spec.body(NEW_MODEL_NAME).is_none(), "body was not removed from spec");
1345
1346 let world = spec.world_body();
1348 assert!(world.delete().is_err(), "the world model should not be deletable");
1349
1350 spec.compile().unwrap();
1351 }
1352
1353 #[test]
1354 fn test_joint_remove() {
1355 const NEW_NAME: &str = "Test model";
1356
1357 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1358 let mut world = spec.world_body();
1359 let mut joint = world.add_joint();
1360 joint.set_name(NEW_NAME);
1361 drop(joint);
1362
1363 let joint = spec.joint(NEW_NAME).expect("failed to obtain the body");
1365 assert!(joint.delete().is_ok(), "failed to delete model");
1366 assert!(spec.joint(NEW_NAME).is_none(), "body was not removed fom spec");
1367
1368 spec.compile().unwrap();
1369 }
1370
1371 #[test]
1372 fn test_hfield_remove() {
1373 const NEW_NAME: &str = "Test model";
1374
1375 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1376 let mut world = spec.world_body();
1377 let mut joint = world.add_joint();
1378
1379 joint.set_name(NEW_NAME);
1380 drop(joint);
1381
1382 let joint = spec.joint(NEW_NAME).expect("failed to obtain the body");
1384 assert!(joint.delete().is_ok(), "failed to delete model");
1385 assert!(spec.joint(NEW_NAME).is_none(), "body was not removed from spec");
1386
1387 spec.compile().unwrap();
1388 }
1389
1390 #[test]
1391 fn test_body_userdata() {
1392 const NEW_USERDATA: [f64; 3] = [1.0, 2.0, 3.0];
1393
1394 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1395 let mut world = spec.world_body();
1396
1397 assert_eq!(world.userdata(), []);
1398
1399 world.set_userdata(NEW_USERDATA);
1400 assert_eq!(world.userdata(), NEW_USERDATA);
1401
1402 spec.compile().unwrap();
1403 }
1404
1405 #[test]
1406 fn test_body_attrs() {
1407 const TEST_VALUE_F64: f64 = 5.25;
1408
1409 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1410 let mut world = spec.world_body();
1411
1412 world.set_gravcomp(TEST_VALUE_F64);
1413 assert_eq!(world.gravcomp(), TEST_VALUE_F64);
1414
1415 world.pos_mut()[0] = TEST_VALUE_F64;
1416 assert_eq!(world.pos()[0], TEST_VALUE_F64);
1417
1418 spec.compile().unwrap();
1419 }
1420
1421 #[test]
1422 fn test_default() {
1423 const DEFAULT_NAME: &str = "floor";
1424 const NOT_DEFAULT_NAME: &str = "floor-not";
1425
1426 let mut spec = MjSpec::from_xml_string(MODEL).expect("unable to load the spec");
1427
1428 spec.add_default(DEFAULT_NAME, None).unwrap();
1430
1431 assert!(spec.default(DEFAULT_NAME).is_some());
1433 assert!(spec.default(NOT_DEFAULT_NAME).is_none());
1434
1435 let mut world = spec.world_body();
1436 let mut some_body = world.add_body();
1437 some_body.add_joint().with_name("test");
1438 some_body.add_geom().with_size([0.010, 0.0, 0.0]);
1439
1440 let mut actuator = spec.add_actuator()
1441 .with_trntype(MjtTrn::mjTRN_JOINT);
1442 actuator.set_target("test");
1443
1444 assert!(actuator.set_default(DEFAULT_NAME).is_ok());
1445
1446 spec.compile().unwrap();
1447 }
1448
1449 #[test]
1450 fn test_save() {
1451 const EXPECTED_XML: &str = "\
1453<mujoco model=\"MuJoCo Model\">
1454 <compiler angle=\"radian\"/>
1455
1456 <worldbody>
1457 <body>
1458 <geom size=\"0.01\"/>
1459 <site pos=\"0 0 0\"/>
1460 <camera pos=\"0 0 0\"/>
1461 <light pos=\"0 0 0\" dir=\"0 0 -1\"/>
1462 </body>
1463 </worldbody>
1464</mujoco>
1465";
1466
1467 let mut spec = MjSpec::new();
1468 let mut world = spec.world_body();
1469 let mut body = world.add_body();
1470 body.add_camera();
1471 body.add_geom().with_size([0.010, 0.0, 0.0]);
1472 body.add_light();
1473 body.add_site();
1474
1475 spec.compile().unwrap();
1476 assert_eq!(spec.save_xml_string(1000).unwrap(), EXPECTED_XML);
1477
1478 spec.compile().unwrap();
1479 }
1480
1481 #[test]
1482 fn test_site() {
1483 const TEST_MATERIAL: &str = "material 1";
1484 const TEST_POSITION: [f64; 3] = [1.0, 2.0, 3.0];
1485 const SITE_NAME: &str = "test_site";
1486
1487 let mut spec = MjSpec::new();
1488
1489 spec.add_material().with_name(TEST_MATERIAL);
1491
1492 let mut world = spec.world_body();
1494 world.add_site()
1495 .with_name(SITE_NAME);
1496 let mut site = spec.site(SITE_NAME).unwrap();
1497
1498 assert_eq!(site.material(), "");
1500 site.set_material(TEST_MATERIAL);
1501 assert_eq!(site.material(), TEST_MATERIAL);
1502
1503 let test_userdata: Vec<f64> = vec![0.0; 5];
1505 assert_eq!(site.userdata(), []);
1506 site.set_userdata(&test_userdata);
1507 assert_eq!(site.userdata(), test_userdata);
1508
1509 assert_eq!(site.pos(), &[0.0; 3]);
1511 *site.pos_mut() = TEST_POSITION;
1512 assert_eq!(site.pos(), &TEST_POSITION);
1513
1514 spec.compile().unwrap();
1515 }
1516
1517 #[test]
1518 fn test_frame() {
1519 let mut spec = MjSpec::new();
1520 let mut world = spec.world_body()
1521 .with_gravcomp(10.0);
1522
1523 world.add_frame()
1524 .with_pos([0.5, 0.5, 0.05])
1525 .add_body()
1526 .add_geom()
1527 .with_size([1.0, 0.0, 0.0]);
1528
1529 spec.compile().unwrap();
1530 }
1531
1532 #[test]
1533 fn test_wrap() {
1534 let mut spec = MjSpec::new();
1535 let mut world = spec.world_body();
1536 let mut body1= world.add_body().with_pos([0.0, 0.0, 0.5]);
1537 body1.add_geom().with_size([0.010;3]);
1538 body1.add_site().with_name("ball1");
1539 body1.add_joint().with_type(MjtJoint::mjJNT_FREE);
1540
1541 let mut body2= world.add_body().with_pos([0.0, 0.0, 0.5]);
1542 body2.add_geom().with_size([0.010;3]);
1543 body2.add_site().with_name("ball2");
1544 body2.add_joint().with_type(MjtJoint::mjJNT_FREE);
1545
1546 let mut tendon = spec.add_tendon()
1547 .with_range([0.0, 0.25])
1548 .with_rgba([1.0, 0.5, 0.0, 1.0]); tendon.wrap_site("ball1");
1550 tendon.wrap_site("ball2");
1551
1552 spec.world_body().add_geom().with_type(MjtGeom::mjGEOM_PLANE).with_size([1.0; 3]);
1553
1554 spec.compile().unwrap();
1555 }
1556
1557 #[test]
1558 fn test_geom() {
1559 const GEOM_NAME: &str = "test_geom";
1560 const GEOM_INVALID_NAME: &str = "geom_test";
1561 let mut spec = MjSpec::new();
1562 spec.world_body().add_geom()
1563 .with_name(GEOM_NAME);
1564
1565 assert!(spec.geom(GEOM_NAME).is_some());
1566 assert!(spec.geom(GEOM_INVALID_NAME).is_none());
1567 }
1568
1569 #[test]
1570 fn test_camera() {
1571 const CAMERA_NAME: &str = "test_cam";
1572 const CAMERA_INVALID_NAME: &str = "cam_test";
1573 let mut spec = MjSpec::new();
1574 spec.world_body().add_camera()
1575 .with_name(CAMERA_NAME);
1576
1577 assert!(spec.camera(CAMERA_NAME).is_some());
1578 assert!(spec.camera(CAMERA_INVALID_NAME).is_none());
1579 }
1580
1581 #[test]
1582 fn test_light() {
1583 const LIGHT_NAME: &str = "test_light";
1584 const LIGHT_INVALID_NAME: &str = "light_test";
1585 let mut spec = MjSpec::new();
1586 spec.world_body().add_light()
1587 .with_name(LIGHT_NAME);
1588
1589 assert!(spec.light(LIGHT_NAME).is_some());
1590 assert!(spec.light(LIGHT_INVALID_NAME).is_none());
1591 }
1592
1593 #[test]
1594 fn test_exclude() {
1595 const EXCLUDE_NAME: &str = "test_exclude";
1596 const EXCLUDE_INVALID_NAME: &str = "exclude_test";
1597 let mut spec = MjSpec::new();
1598
1599 spec.world_body().add_body().with_name("body1-left");
1600 spec.world_body().add_body().with_name("body2-right");
1601
1602 spec.add_exclude()
1603 .with_name(EXCLUDE_NAME)
1604 .with_bodyname1("body1-left")
1605 .with_bodyname2("body2-right");
1606
1607 assert!(spec.exclude(EXCLUDE_NAME).is_some());
1608 assert!(spec.exclude(EXCLUDE_INVALID_NAME).is_none());
1609
1610 assert!(spec.compile().is_ok());
1611 }
1612}