pub struct MjViewer<'m> { /* private fields */ }Expand description
A Rust-native implementation of the MuJoCo viewer. To confirm to rust safety rules,
the viewer doesn’t store a mutable reference to the MjData struct, but it instead
accepts it as a parameter at its methods.
Currently supported (to be expanded in the future):
- Visualization of the 3D scene,
- Close via Ctrl + Q or by closing the window,
- Body tracking via Ctrl + Alt + double left click,
- Camera look at object via Alt + double left click,
- Escape from tracked camera via Esc.
- Perturbations:
- Select the object of interested by double clicking on it,
- Hold down Control and start dragging for rotational perturbations,
- Hold down Control+Alt and start dragging for translational perturbations,
- To move in the XY plane instead of the default XZ plane, hold Shift.
The MjViewer::sync method must be called to sync the state of MjViewer and MjData.
§Safety
Due to the nature of OpenGL, this should only be run in the main thread.
Implementations§
Source§impl<'m> MjViewer<'m>
impl<'m> MjViewer<'m>
Sourcepub fn launch_passive(
model: &'m MjModel,
scene_max_geom: usize,
) -> Result<Self, MjViewerError>
pub fn launch_passive( model: &'m MjModel, scene_max_geom: usize, ) -> Result<Self, MjViewerError>
Launches the MuJoCo viewer. A Result struct is returned that either contains
MjViewer or a MjViewerError. 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.
Examples found in repository?
More examples
37fn main() {
38 /* Load the model and create data */
39 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
40 let mut data = model.make_data(); // or MjData::new(&model);
41
42 /* Launch a passive Rust-native viewer */
43 let mut viewer = MjViewer::launch_passive(&model, 0)
44 .expect("could not launch the viewer");
45
46 while viewer.running() {
47 /* Step the simulation and sync the viewer */
48 viewer.sync(&mut data);
49 data.step();
50
51 std::thread::sleep(Duration::from_secs_f64(0.002));
52 }
53}29fn main() {
30 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
31
32 /******************************************/
33 /* Access a FFI attribute */
34 let timestep = model.ffi().opt.timestep;
35 /******************************************/
36
37 let mut data = model.make_data(); // or MjData::new(&model);
38 let mut viewer = MjViewer::launch_passive(&model, 100)
39 .expect("could not launch the viewer");
40
41 while viewer.running() {
42 viewer.sync(&mut data);
43 data.step();
44 std::thread::sleep(Duration::from_secs_f64(timestep));
45 }
46}32fn main() {
33 /* Load the model and create data */
34 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
35 let mut data = model.make_data(); // or MjData::new(&model);
36
37 /* Launch a passive Rust-native viewer */
38 let mut viewer = MjViewer::launch_passive(&model, 0)
39 .expect("could not launch the viewer");
40
41 let sensor_data_info = data.sensor("touch").unwrap();
42 while viewer.running() {
43 /* Step the simulation and sync the viewer */
44 viewer.sync(&mut data);
45 data.step();
46
47 /* Print the touch sensor output, which is the contact force */
48 println!("{}", sensor_data_info.view(&data).data[0]);
49
50 std::thread::sleep(Duration::from_secs_f64(0.002));
51 }
52}26fn main() {
27 /* Load the model and create data */
28 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
29 let mut data = model.make_data(); // or MjData::new(&model);
30
31 /* Launch a passive Rust-native viewer */
32 let mut viewer = MjViewer::launch_passive(&model, 0)
33 .expect("could not launch the viewer");
34
35 /* Create the joint info */
36 let ball_info = data.joint("ball_joint").unwrap();
37 while viewer.running() {
38 /* Step the simulation and sync the viewer */
39 viewer.sync(&mut data);
40 data.step();
41
42 /* Obtain the view and access first three variables of `qpos` (x, y, z) */
43 let xyz = &ball_info.view(&data).qpos[..3];
44 println!("The ball's position is: {xyz:.2?}");
45
46 std::thread::sleep(Duration::from_secs_f64(0.002));
47 }
48}32fn main() {
33 /* Create model and data */
34 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
35 let mut data = model.make_data();
36
37 /* Launch a passive Rust-native viewer */
38 let mut viewer = MjViewer::launch_passive(
39 &model,
40 10 // create space for 10 visual-only geoms
41 )
42 .expect("could not launch the viewer");
43
44 /* Obtain joint info */
45 let ball1_joint_info = data.joint("ball1_joint").unwrap();
46 let ball2_joint_info = data.joint("ball2_joint").unwrap();
47
48 /* Give the first ball some y-velocity to showcase the visualization */
49 ball1_joint_info.view_mut(&mut data).qvel[1] = 2.0;
50
51 let timestep = model.ffi().opt.timestep;
52 let mut user_scn;
53 while viewer.running() {
54 /* Step the simulation and sync the viewer */
55 viewer.sync(&mut data);
56 data.step();
57
58 /* Prepare the scene */
59 user_scn = viewer.user_scn_mut(); // obtain a mutable reference to the user scene. The method name mirrors the C++ viewer.
60 user_scn.clear_geom(); // clear existing geoms
61
62 /* Create a line, that (visually) connects the two balls we have in the example model */
63 let new_geom = user_scn.create_geom(
64 MjtGeom::mjGEOM_LINE, // type of geom to draw.
65 None, // size, ignore here as we set it below.
66 None, // position: ignore here as we set it below.
67 None, // rotational matrix: ignore here as we set it below.
68 Some([1.0, 1.0, 1.0, 1.0]) // color (rgba): pure white.
69 );
70
71 /* Read X, Y and Z coordinates of both balls. */
72 let ball1_position = ball1_joint_info.view(&data).qpos[..3]
73 .try_into().unwrap();
74 let ball2_position = ball2_joint_info.view(&data).qpos[..3]
75 .try_into().unwrap();
76
77 /* Modify the visual geom's position, orientation and length, to connect the balls */
78 new_geom.connect(
79 0.0, // width
80 ball1_position, // from
81 ball2_position // to
82 );
83
84 std::thread::sleep(Duration::from_secs_f64(timestep));
85 }
86}Sourcepub fn running(&self) -> bool
pub fn running(&self) -> bool
Checks whether the window is still open.
Examples found in repository?
More examples
37fn main() {
38 /* Load the model and create data */
39 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
40 let mut data = model.make_data(); // or MjData::new(&model);
41
42 /* Launch a passive Rust-native viewer */
43 let mut viewer = MjViewer::launch_passive(&model, 0)
44 .expect("could not launch the viewer");
45
46 while viewer.running() {
47 /* Step the simulation and sync the viewer */
48 viewer.sync(&mut data);
49 data.step();
50
51 std::thread::sleep(Duration::from_secs_f64(0.002));
52 }
53}29fn main() {
30 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
31
32 /******************************************/
33 /* Access a FFI attribute */
34 let timestep = model.ffi().opt.timestep;
35 /******************************************/
36
37 let mut data = model.make_data(); // or MjData::new(&model);
38 let mut viewer = MjViewer::launch_passive(&model, 100)
39 .expect("could not launch the viewer");
40
41 while viewer.running() {
42 viewer.sync(&mut data);
43 data.step();
44 std::thread::sleep(Duration::from_secs_f64(timestep));
45 }
46}32fn main() {
33 /* Load the model and create data */
34 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
35 let mut data = model.make_data(); // or MjData::new(&model);
36
37 /* Launch a passive Rust-native viewer */
38 let mut viewer = MjViewer::launch_passive(&model, 0)
39 .expect("could not launch the viewer");
40
41 let sensor_data_info = data.sensor("touch").unwrap();
42 while viewer.running() {
43 /* Step the simulation and sync the viewer */
44 viewer.sync(&mut data);
45 data.step();
46
47 /* Print the touch sensor output, which is the contact force */
48 println!("{}", sensor_data_info.view(&data).data[0]);
49
50 std::thread::sleep(Duration::from_secs_f64(0.002));
51 }
52}26fn main() {
27 /* Load the model and create data */
28 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
29 let mut data = model.make_data(); // or MjData::new(&model);
30
31 /* Launch a passive Rust-native viewer */
32 let mut viewer = MjViewer::launch_passive(&model, 0)
33 .expect("could not launch the viewer");
34
35 /* Create the joint info */
36 let ball_info = data.joint("ball_joint").unwrap();
37 while viewer.running() {
38 /* Step the simulation and sync the viewer */
39 viewer.sync(&mut data);
40 data.step();
41
42 /* Obtain the view and access first three variables of `qpos` (x, y, z) */
43 let xyz = &ball_info.view(&data).qpos[..3];
44 println!("The ball's position is: {xyz:.2?}");
45
46 std::thread::sleep(Duration::from_secs_f64(0.002));
47 }
48}32fn main() {
33 /* Create model and data */
34 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
35 let mut data = model.make_data();
36
37 /* Launch a passive Rust-native viewer */
38 let mut viewer = MjViewer::launch_passive(
39 &model,
40 10 // create space for 10 visual-only geoms
41 )
42 .expect("could not launch the viewer");
43
44 /* Obtain joint info */
45 let ball1_joint_info = data.joint("ball1_joint").unwrap();
46 let ball2_joint_info = data.joint("ball2_joint").unwrap();
47
48 /* Give the first ball some y-velocity to showcase the visualization */
49 ball1_joint_info.view_mut(&mut data).qvel[1] = 2.0;
50
51 let timestep = model.ffi().opt.timestep;
52 let mut user_scn;
53 while viewer.running() {
54 /* Step the simulation and sync the viewer */
55 viewer.sync(&mut data);
56 data.step();
57
58 /* Prepare the scene */
59 user_scn = viewer.user_scn_mut(); // obtain a mutable reference to the user scene. The method name mirrors the C++ viewer.
60 user_scn.clear_geom(); // clear existing geoms
61
62 /* Create a line, that (visually) connects the two balls we have in the example model */
63 let new_geom = user_scn.create_geom(
64 MjtGeom::mjGEOM_LINE, // type of geom to draw.
65 None, // size, ignore here as we set it below.
66 None, // position: ignore here as we set it below.
67 None, // rotational matrix: ignore here as we set it below.
68 Some([1.0, 1.0, 1.0, 1.0]) // color (rgba): pure white.
69 );
70
71 /* Read X, Y and Z coordinates of both balls. */
72 let ball1_position = ball1_joint_info.view(&data).qpos[..3]
73 .try_into().unwrap();
74 let ball2_position = ball2_joint_info.view(&data).qpos[..3]
75 .try_into().unwrap();
76
77 /* Modify the visual geom's position, orientation and length, to connect the balls */
78 new_geom.connect(
79 0.0, // width
80 ball1_position, // from
81 ball2_position // to
82 );
83
84 std::thread::sleep(Duration::from_secs_f64(timestep));
85 }
86}Sourcepub fn user_scn(&self) -> &MjvScene<'m>
pub fn user_scn(&self) -> &MjvScene<'m>
Returns an immutable reference to a user scene for drawing custom visual-only geoms.
Sourcepub fn user_scn_mut(&mut self) -> &mut MjvScene<'m>
pub fn user_scn_mut(&mut self) -> &mut MjvScene<'m>
Returns a mutable reference to a user scene for drawing custom visual-only geoms.
Examples found in repository?
32fn main() {
33 /* Create model and data */
34 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
35 let mut data = model.make_data();
36
37 /* Launch a passive Rust-native viewer */
38 let mut viewer = MjViewer::launch_passive(
39 &model,
40 10 // create space for 10 visual-only geoms
41 )
42 .expect("could not launch the viewer");
43
44 /* Obtain joint info */
45 let ball1_joint_info = data.joint("ball1_joint").unwrap();
46 let ball2_joint_info = data.joint("ball2_joint").unwrap();
47
48 /* Give the first ball some y-velocity to showcase the visualization */
49 ball1_joint_info.view_mut(&mut data).qvel[1] = 2.0;
50
51 let timestep = model.ffi().opt.timestep;
52 let mut user_scn;
53 while viewer.running() {
54 /* Step the simulation and sync the viewer */
55 viewer.sync(&mut data);
56 data.step();
57
58 /* Prepare the scene */
59 user_scn = viewer.user_scn_mut(); // obtain a mutable reference to the user scene. The method name mirrors the C++ viewer.
60 user_scn.clear_geom(); // clear existing geoms
61
62 /* Create a line, that (visually) connects the two balls we have in the example model */
63 let new_geom = user_scn.create_geom(
64 MjtGeom::mjGEOM_LINE, // type of geom to draw.
65 None, // size, ignore here as we set it below.
66 None, // position: ignore here as we set it below.
67 None, // rotational matrix: ignore here as we set it below.
68 Some([1.0, 1.0, 1.0, 1.0]) // color (rgba): pure white.
69 );
70
71 /* Read X, Y and Z coordinates of both balls. */
72 let ball1_position = ball1_joint_info.view(&data).qpos[..3]
73 .try_into().unwrap();
74 let ball2_position = ball2_joint_info.view(&data).qpos[..3]
75 .try_into().unwrap();
76
77 /* Modify the visual geom's position, orientation and length, to connect the balls */
78 new_geom.connect(
79 0.0, // width
80 ball1_position, // from
81 ball2_position // to
82 );
83
84 std::thread::sleep(Duration::from_secs_f64(timestep));
85 }
86}Sourcepub fn sync(&mut self, data: &mut MjData<'_>)
pub fn sync(&mut self, data: &mut MjData<'_>)
Syncs the state of data with the viewer as well as perform
rendering on the viewer.
Examples found in repository?
More examples
37fn main() {
38 /* Load the model and create data */
39 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
40 let mut data = model.make_data(); // or MjData::new(&model);
41
42 /* Launch a passive Rust-native viewer */
43 let mut viewer = MjViewer::launch_passive(&model, 0)
44 .expect("could not launch the viewer");
45
46 while viewer.running() {
47 /* Step the simulation and sync the viewer */
48 viewer.sync(&mut data);
49 data.step();
50
51 std::thread::sleep(Duration::from_secs_f64(0.002));
52 }
53}29fn main() {
30 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
31
32 /******************************************/
33 /* Access a FFI attribute */
34 let timestep = model.ffi().opt.timestep;
35 /******************************************/
36
37 let mut data = model.make_data(); // or MjData::new(&model);
38 let mut viewer = MjViewer::launch_passive(&model, 100)
39 .expect("could not launch the viewer");
40
41 while viewer.running() {
42 viewer.sync(&mut data);
43 data.step();
44 std::thread::sleep(Duration::from_secs_f64(timestep));
45 }
46}32fn main() {
33 /* Load the model and create data */
34 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
35 let mut data = model.make_data(); // or MjData::new(&model);
36
37 /* Launch a passive Rust-native viewer */
38 let mut viewer = MjViewer::launch_passive(&model, 0)
39 .expect("could not launch the viewer");
40
41 let sensor_data_info = data.sensor("touch").unwrap();
42 while viewer.running() {
43 /* Step the simulation and sync the viewer */
44 viewer.sync(&mut data);
45 data.step();
46
47 /* Print the touch sensor output, which is the contact force */
48 println!("{}", sensor_data_info.view(&data).data[0]);
49
50 std::thread::sleep(Duration::from_secs_f64(0.002));
51 }
52}26fn main() {
27 /* Load the model and create data */
28 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
29 let mut data = model.make_data(); // or MjData::new(&model);
30
31 /* Launch a passive Rust-native viewer */
32 let mut viewer = MjViewer::launch_passive(&model, 0)
33 .expect("could not launch the viewer");
34
35 /* Create the joint info */
36 let ball_info = data.joint("ball_joint").unwrap();
37 while viewer.running() {
38 /* Step the simulation and sync the viewer */
39 viewer.sync(&mut data);
40 data.step();
41
42 /* Obtain the view and access first three variables of `qpos` (x, y, z) */
43 let xyz = &ball_info.view(&data).qpos[..3];
44 println!("The ball's position is: {xyz:.2?}");
45
46 std::thread::sleep(Duration::from_secs_f64(0.002));
47 }
48}32fn main() {
33 /* Create model and data */
34 let model = MjModel::from_xml_string(EXAMPLE_MODEL).expect("could not load the model");
35 let mut data = model.make_data();
36
37 /* Launch a passive Rust-native viewer */
38 let mut viewer = MjViewer::launch_passive(
39 &model,
40 10 // create space for 10 visual-only geoms
41 )
42 .expect("could not launch the viewer");
43
44 /* Obtain joint info */
45 let ball1_joint_info = data.joint("ball1_joint").unwrap();
46 let ball2_joint_info = data.joint("ball2_joint").unwrap();
47
48 /* Give the first ball some y-velocity to showcase the visualization */
49 ball1_joint_info.view_mut(&mut data).qvel[1] = 2.0;
50
51 let timestep = model.ffi().opt.timestep;
52 let mut user_scn;
53 while viewer.running() {
54 /* Step the simulation and sync the viewer */
55 viewer.sync(&mut data);
56 data.step();
57
58 /* Prepare the scene */
59 user_scn = viewer.user_scn_mut(); // obtain a mutable reference to the user scene. The method name mirrors the C++ viewer.
60 user_scn.clear_geom(); // clear existing geoms
61
62 /* Create a line, that (visually) connects the two balls we have in the example model */
63 let new_geom = user_scn.create_geom(
64 MjtGeom::mjGEOM_LINE, // type of geom to draw.
65 None, // size, ignore here as we set it below.
66 None, // position: ignore here as we set it below.
67 None, // rotational matrix: ignore here as we set it below.
68 Some([1.0, 1.0, 1.0, 1.0]) // color (rgba): pure white.
69 );
70
71 /* Read X, Y and Z coordinates of both balls. */
72 let ball1_position = ball1_joint_info.view(&data).qpos[..3]
73 .try_into().unwrap();
74 let ball2_position = ball2_joint_info.view(&data).qpos[..3]
75 .try_into().unwrap();
76
77 /* Modify the visual geom's position, orientation and length, to connect the balls */
78 new_geom.connect(
79 0.0, // width
80 ball1_position, // from
81 ball2_position // to
82 );
83
84 std::thread::sleep(Duration::from_secs_f64(timestep));
85 }
86}