pub struct MjViewerCpp<'m> { /* private fields */ }Expand description
Wrapper around the C++ implementation of MujoCo viewer.
If you don’t need the side UI, we recommend you use the Rust-native viewer MjViewer instead.
Implementations§
Source§impl<'m> MjViewerCpp<'m>
impl<'m> MjViewerCpp<'m>
Sourcepub fn running(&self) -> bool
pub fn running(&self) -> bool
Examples found in repository?
25fn main() {
26 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
27 let mut data = model.make_data(); // or MjData::new(&model);
28 let mut viewer = MjViewerCpp::launch_passive(&model, &data, 100);
29 let step = model.ffi().opt.timestep;
30 while viewer.running() {
31 viewer.sync();
32 viewer.render(true);
33 data.step();
34 std::thread::sleep(Duration::from_secs_f64(step));
35 }
36}pub fn user_scn_mut(&mut self) -> &mut MjvScene<'m>
Sourcepub fn launch_passive(
model: &'m MjModel,
data: &MjData<'_>,
scene_max_geom: usize,
) -> Self
pub fn launch_passive( model: &'m MjModel, data: &MjData<'_>, scene_max_geom: usize, ) -> Self
Launches a wrapper around MuJoCo’s C++ viewer. The scene_max_geom parameter
defines how much space will be allocated for additional, user-defined visual-only geoms.
It can thus be set to 0 if no additional geoms will be drawn by the user.
Unlike the Rust-native viewer (MjViewer), this also accepts a data parameter.
Additionally, this just returns a MjViewerCpp instance directly, without result
as the initialization may fail internally in C++ anyway, which we have no way of checking.
§Safety
To allow certain flexibility, while still maintaining
compatibility with the C++ code, MjViewerCpp keeps internals pointers to mjModel and mjData,
which are wrapped inside MjModel and MjData, respectively.
This technically allows model and data to be modified
while the viewer keeps a pointer to them (their wrapped pointers).
Undefined behavior should not occur, however caution is advised as this is a violation
of the Rust’s borrowing rules.
Examples found in repository?
25fn main() {
26 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
27 let mut data = model.make_data(); // or MjData::new(&model);
28 let mut viewer = MjViewerCpp::launch_passive(&model, &data, 100);
29 let step = model.ffi().opt.timestep;
30 while viewer.running() {
31 viewer.sync();
32 viewer.render(true);
33 data.step();
34 std::thread::sleep(Duration::from_secs_f64(step));
35 }
36}Sourcepub fn __raw(&self) -> *mut mujoco_Simulate
pub fn __raw(&self) -> *mut mujoco_Simulate
Returns the underlying C++ binding object of the viewer.
Sourcepub fn render(&mut self, update_timer: bool)
pub fn render(&mut self, update_timer: bool)
Renders the simulation.
update_timer flag species whether the time should be updated
inside the viewer (for vsync purposes).
§SAFETY
This needs to be called periodically from the MAIN thread, otherwise GLFW stops working.
Examples found in repository?
25fn main() {
26 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
27 let mut data = model.make_data(); // or MjData::new(&model);
28 let mut viewer = MjViewerCpp::launch_passive(&model, &data, 100);
29 let step = model.ffi().opt.timestep;
30 while viewer.running() {
31 viewer.sync();
32 viewer.render(true);
33 data.step();
34 std::thread::sleep(Duration::from_secs_f64(step));
35 }
36}Sourcepub fn sync(&mut self)
pub fn sync(&mut self)
Syncs the simulation state with the viewer as well as perform rendering on the viewer.
Examples found in repository?
25fn main() {
26 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
27 let mut data = model.make_data(); // or MjData::new(&model);
28 let mut viewer = MjViewerCpp::launch_passive(&model, &data, 100);
29 let step = model.ffi().opt.timestep;
30 while viewer.running() {
31 viewer.sync();
32 viewer.render(true);
33 data.step();
34 std::thread::sleep(Duration::from_secs_f64(step));
35 }
36}