Basic simulation¶
Loading¶
To perform basic simulation with MuJoCo, create a MjModel struct by calling one of the following methods:
MjModel::from_xml (loads XML from a file),
MjModel::from_xml_vfs (loads XML from a file on a virtual file system),
MjModel::from_xml_string (loads XML from a model defined in a string in memory),
MjModel::from_buffer (loads a compiled model from a buffer).
For example:
use mujoco_rs::prelude::*;
fn main() {
let model = MjModel::from_xml("model.xml").expect("could not load the model");
}
MjModel represents the compiled model from an XML file and contains everything from basic metadata to physics parameters.
For managing actual simulation state, MjData is used. It can be created either through the MjData::new method or through the MjModel::make_data method. For example:
use mujoco_rs::prelude::*;
fn main() {
let model = MjModel::from_xml("model.xml").expect("could not load the model");
let mut data = MjData::new(&model); // or model.make_data()
}
Tip
Using the MjData::new method is far more flexible than using the MjModel::make_data method. The former allows parameters to be of any type as long as they implement the Deref trait (e.g., Box<MjModel>). For example:
use mujoco_rs::prelude::*;
fn main() {
let model = Box::new(MjModel::from_xml("model.xml").expect("could not load the model"));
let mut data = MjData::new(model); // move model into the data
let model_ref = data.model(); // obtain a reference to the model
}
Note that all related APIs must use the same model-handle type M.
For example, if you create MjData<Box<MjModel>>, APIs expecting
MjData<&MjModel> (or Rc/Arc variants) are not interchangeable.
For shared ownership, use
Rc<MjModel>
(single-threaded) or
Arc<MjModel>
when thread-sharing is needed.
Using Box or Rc (instead of direct references) allows usage in environments with lifetime restrictions.
One such example is Python bindings created with PyO3.
The standalone/pyo3_application example shows how to create a simple MuJoCo-rs based application
for use from the Python programming language.
Running¶
Then to run/step the simulation, just call the MjData::step method like so:
use mujoco_rs::prelude::*;
fn main() {
let model = MjModel::from_xml("model.xml").expect("could not load the model");
let mut data = MjData::new(&model);
loop {
data.step();
}
}
The method MjData::step is just a wrapper around the mujoco_c::mj_step FFI function. Similarly, MjData::step1 and MjData::step2 wrap mujoco_c::mj_step1 and mujoco_c::mj_step2, respectively.
For more information about specific MuJoCo functions, see the MuJoCo documentation.
Real-time¶
The example above runs the simulation as fast as possible. To slow it down, you can either add a call to std::thread::sleep for an approximate delay, or use std::time::Instant with Instant::elapsed for precise timing.
use std::time::Duration;
use std::thread;
use mujoco_rs::prelude::*;
fn main() {
let model = MjModel::from_xml("model.xml").expect("could not load the model");
let mut data = MjData::new(&model);
let timestep = model.opt().timestep;
loop {
data.step();
/* Approximate-time delay */
thread::sleep(Duration::from_secs_f64(timestep))
}
}
Changing model’s parameters¶
For purposes of transfer from simulation to reality in reinforcement learning it is beneficial to perform domain randomization [Tobin2017]. This requires modifying different aspects of the environment, such as physics parameters — part of MjModel.
Danger
Not all parameters of MjModel are safe to change. See MuJoCo’s documentation for a list of parameters that are safe to change.
Direct mutation with model_opt_mut / model_vis_mut / model_stat_mut¶
When the model-handle type M implements
DerefMut<Target = MjModel>
(e.g., Box<MjModel>), the safe accessors
MjData::model_opt_mut,
MjData::model_vis_mut, and
MjData::model_stat_mut
give direct mutable access to the model’s physics options, visualization settings,
and statistics respectively.
1use mujoco_rs::prelude::*;
2
3fn main() {
4 let model = Box::new(MjModel::from_xml("model.xml").expect("could not load the model"));
5 let mut data = MjData::new(model);
6 data.model_opt_mut().timestep = 0.004;
7 data.model_opt_mut().gravity[2] = -5.0;
8}
Note
For full mutable access to the entire MjModel (e.g., to replace the model in-place),
use the unsafe
MjData::model_mut method.
It requires M: DerefMut<Target = MjModel> and is unsafe because swapping to an
incompatible model can violate internal invariants.
model_opt_mut and its siblings are not available when M is a shared-ownership
type (e.g., Arc<MjModel>, &MjModel). In those cases,
use MjData::swap_model
or its fallible twin MjData::try_swap_model
below. The latter two methods are not unsafe as failure results in a panic
or in a returned error, respectively.
See the simulation/model_parameters.rs example for a complete runnable comparison of both
approaches (model_opt_mut and swap_model).
Swapping models with swap_model¶
When M does not support DerefMut (e.g., Arc<MjModel>), or when you need to
swap in an entirely different model instance, use the
MjData::swap_model method
or the MjData::try_swap_model method,
which swap the MjModel owned by MjData for the MjModel given as parameter.
1use mujoco_rs::prelude::*;
2
3fn main() {
4 let mut model_template = Box::new(MjModel::from_xml("model.xml").expect("could not load the model"));
5
6 let model = model_template.clone();
7 let mut data = MjData::new(model);
8
9 // Modify simulation timestep
10 model_template.opt_mut().timestep = 0.004;
11 model_template = data.swap_model(model_template);
12}
Note that the above example uses MjModel as the model_template only
as an illustration — usually this would be something like MjSpec, however that
is reserved for the Model editing chapter.
J. Tobin, R. Fong, A. Ray, J. Schneider, W. Zaremba, and P. Abbeel, “Domain randomization for transferring deep neural networks from simulation to the real world,” in 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, Sep. 2017, pp. 23–30. doi: 10.1109/IROS.2017.8202133