mujoco_rs/
viewer.rs

1//! Module related to implementation of the [`MjViewer`] and [`MjViewerCpp`].
2
3use glfw_mjrc_fork as glfw;
4use glfw_mjrc_fork::{Action, Context, Glfw, GlfwReceiver, Key, Modifiers, MouseButton, PWindow, WindowEvent, WindowMode};
5
6use bitflags::bitflags;
7
8use std::time::Instant;
9use std::fmt::Display;
10use std::error::Error;
11
12use crate::{get_mujoco_version, mujoco_c::*};
13
14#[cfg(feature = "cpp-viewer")]
15use std::ffi::CString;
16
17use crate::prelude::{MjrContext, MjrRectangle, MjtFont, MjtGridPos};
18use crate::wrappers::mj_primitive::MjtNum;
19use crate::wrappers::mj_visualization::*;
20use crate::wrappers::mj_model::MjModel;
21use crate::wrappers::mj_data::MjData;
22
23/****************************************** */
24// Rust native viewer
25/****************************************** */
26const MJ_VIEWER_DEFAULT_SIZE_PX: (u32, u32) = (1280, 720);
27const DOUBLE_CLICK_WINDOW_MS: u128 = 250;
28
29const HELP_MENU_TITLES: &str = concat!(
30    "Toggle help\n",
31    "Toggle full screen\n",
32    "Free camera\n",
33    "Track camera\n",
34    "Camera orbit\n",
35    "Camera pan\n",
36    "Camera look at\n",
37    "Zoom\n",
38    "Object select\n",
39    "Selection rotate\n",
40    "Selection translate\n",
41    "Exit\n",
42    "Reset simulation\n",
43    "Cycle cameras\n",
44    "Visualization toggles",
45);
46
47const HELP_MENU_VALUES: &str = concat!(
48    "F1\n",
49    "F5\n",
50    "Escape\n",
51    "Control + Alt + double-left click\n",
52    "Left drag\n",
53    "Right [+Shift] drag\n",
54    "Alt + double-left click\n",
55    "Zoom, middle drag\n",
56    "Double-left click\n",
57    "Control + [Shift] + drag\n",
58    "Control + Alt + [Shift] + drag\n",
59    "Control + Q\n",
60    "Backspace\n",
61    "[ ]\n",
62    "See MjViewer docs"
63);
64
65#[derive(Debug)]
66pub enum MjViewerError {
67    GlfwInitError (glfw::InitError),
68    WindowCreationError
69}
70
71impl Display for MjViewerError {
72    fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
73        match self {
74            Self::GlfwInitError(e) => write!(f, "glfw failed to initialize: {}", e),
75            Self::WindowCreationError => write!(f, "failed to create window"),
76        }
77    }
78}
79
80impl Error for MjViewerError {
81    fn source(&self) -> Option<&(dyn Error + 'static)> {
82        match self {
83            Self::GlfwInitError(e) => Some(e),
84            _ => None
85        }
86    }
87}
88
89/// A Rust-native implementation of the MuJoCo viewer. To confirm to rust safety rules,
90/// the viewer doesn't store a mutable reference to the [`MjData`] struct, but it instead
91/// accepts it as a parameter at its methods.
92/// 
93/// The [`MjViewer::sync`] method must be called to sync the state of [`MjViewer`] and [`MjData`].
94/// 
95/// # Shortcuts
96/// Main keyboard and mouse shortcuts can be viewed by pressing ``F1``.
97/// Additionally, some visualization toggles are included, but not displayed
98/// in the ``F1`` help menu:
99/// - C: camera,
100/// - U: actuator,
101/// - J: joint,
102/// - M: center of mass,
103/// - H: convex hull,
104/// - Z: light,
105/// - T: transparent,
106/// - I: inertia.
107/// 
108/// # Safety
109/// Due to the nature of OpenGL, this should only be run in the **main thread**.
110#[derive(Debug)]
111pub struct MjViewer<'m> {
112    /* MuJoCo rendering */
113    scene: MjvScene<'m>,
114    context: MjrContext,
115    camera: MjvCamera,
116
117    /* Other MuJoCo related */
118    model: &'m MjModel,
119    pert: MjvPerturb,
120    opt: MjvOption,
121
122    /* Internal state */
123    last_x: f64,
124    last_y: f64,
125    last_bnt_press_time: Instant,
126    rect_view: MjrRectangle,
127    rect_full: MjrRectangle,
128    status_flags: ViewerStatusBits,  // Status flag indicating the state of the menu
129
130    /* OpenGL */
131    glfw: Glfw,
132    window: PWindow,
133    events: GlfwReceiver<(f64, WindowEvent)>,
134
135    /* External interaction */
136    user_scene: MjvScene<'m>
137}
138
139impl<'m> MjViewer<'m> {
140    /// Launches the MuJoCo viewer. A [`Result`] struct is returned that either contains
141    /// [`MjViewer`] or a [`MjViewerError`]. The `scene_max_geom` parameter
142    /// defines how much space will be allocated for additional, user-defined visual-only geoms.
143    /// It can thus be set to 0 if no additional geoms will be drawn by the user.
144    pub fn launch_passive(model: &'m MjModel, scene_max_geom: usize) -> Result<Self, MjViewerError> {
145        let mut glfw = glfw::init_no_callbacks()
146            .map_err(|err| MjViewerError::GlfwInitError(err))?;
147
148        let (w, h) = MJ_VIEWER_DEFAULT_SIZE_PX;
149        let title = format!("MuJoCo Rust Viewer (MuJoCo {})", get_mujoco_version());
150
151        let (mut window, events) = match glfw.create_window(
152            w, h, &title,
153            glfw::WindowMode::Windowed
154        ) {
155            Some(x) => Ok(x),
156            None => Err(MjViewerError::WindowCreationError)
157        }?;
158
159        /* Initialize the OpenGL related things */
160        window.make_current();
161        window.set_all_polling(true);
162        glfw.set_swap_interval(glfw::SwapInterval::None);
163
164        Ok(Self {
165            glfw,
166            window,
167            events,
168            model,
169            scene: MjvScene::new(model, model.ffi().ngeom as usize + scene_max_geom + EXTRA_SCENE_GEOM_SPACE),
170            context: MjrContext::new(model),
171            camera: MjvCamera::new_free(model),
172            pert: MjvPerturb::default(),
173            opt: MjvOption::default(),
174            user_scene: MjvScene::new(model, scene_max_geom),
175            last_x: 0.0,
176            last_y: 0.0,
177            status_flags: ViewerStatusBits::HELP_MENU,
178            last_bnt_press_time: Instant::now(),
179            rect_view: MjrRectangle::default(),
180            rect_full: MjrRectangle::default(),
181        })
182    }
183
184    /// Checks whether the window is still open.
185    pub fn running(&self) -> bool {
186        !self.window.should_close()
187    }
188
189    /// Returns an immutable reference to a user scene for drawing custom visual-only geoms.
190    /// Geoms in the user scene are preserved between calls to [`MjViewer::sync`].
191    pub fn user_scene(&self) -> &MjvScene<'m>{
192        &self.user_scene
193    }
194
195    /// Returns a mutable reference to a user scene for drawing custom visual-only geoms.
196    /// Geoms in the user scene are preserved between calls to [`MjViewer::sync`].
197    pub fn user_scene_mut(&mut self) -> &mut MjvScene<'m>{
198        &mut self.user_scene
199    }
200
201    #[deprecated(since = "1.3.0", note = "use user_scene")]
202    pub fn user_scn(&self) -> &MjvScene<'m> {
203        self.user_scene()
204    }
205
206    #[deprecated(since = "1.3.0", note = "use user_scene_mut")]
207    pub fn user_scn_mut(&mut self) -> &mut MjvScene<'m> {
208        self.user_scene_mut()
209    }
210
211    /// Syncs the state of `data` with the viewer as well as perform
212    /// rendering on the viewer.
213    pub fn sync(&mut self, data: &mut MjData) {
214        /* Make sure everything is done on the viewer's window */
215        self.window.make_current();
216
217        /* Process mouse and keyboard events */
218        self.process_events(data);
219
220        /* Update the scene from data and render */
221        self.update_scene(data);
222
223        /* Update the user menu state and overlays */
224        self.update_menus();
225
226        /* Display the drawn content */
227        self.window.swap_buffers();
228
229        /* Apply perturbations */
230        self.pert.apply(self.model, data);
231    }
232
233    /// Updates the scene and draws it to the display.
234    fn update_scene(&mut self, data: &mut MjData) {
235        let model_data_ptr = unsafe {  data.model().__raw() };
236        let bound_model_ptr = unsafe { self.model.__raw() };
237        assert_eq!(model_data_ptr, bound_model_ptr, "'data' must be created from the same model as the viewer.");
238
239        /* Read the screen size */
240        self.update_rectangles(self.window.get_framebuffer_size());
241
242        /* Update the scene from the MjData state */
243        self.scene.update(data, &self.opt, &self.pert, &mut self.camera);
244
245        /* Draw user scene geoms */
246        sync_geoms(&self.user_scene, &mut self.scene)
247            .expect("could not sync the user scene with the internal scene; this is a bug, please report it.");
248
249        self.scene.render(&self.rect_full, &self.context);
250    }
251
252    /// Draws the user menu
253    fn update_menus(&mut self) {
254        let mut rectangle = self.rect_view;
255        rectangle.width = rectangle.width - rectangle.width / 4;
256
257        /* Overlay section */
258        if self.status_flags.contains(ViewerStatusBits::HELP_MENU) {  // Help
259            self.context.overlay(
260                MjtFont::mjFONT_NORMAL, MjtGridPos::mjGRID_TOPLEFT,
261                rectangle,
262                HELP_MENU_TITLES,
263                Some(HELP_MENU_VALUES)
264            );
265        }
266    }
267
268    /// Updates the dimensions of the rectangles defining the dimensions of
269    /// the user interface, as well as the actual scene viewer.
270    fn update_rectangles(&mut self, viewport_size: (i32, i32)) {
271        // The scene (middle) rectangle
272        self.rect_view.width = viewport_size.0;
273        self.rect_view.height = viewport_size.1;
274
275        self.rect_full.width = viewport_size.0;
276        self.rect_full.height = viewport_size.1;
277    }
278
279    /// Processes user input events.
280    fn process_events(&mut self, data: &mut MjData) {
281        self.glfw.poll_events();
282        while let Some((_, event)) = self.events.receive() {
283            match event {
284                // Set the viewer's state to pending exit.
285                WindowEvent::Key(Key::Q, _, Action::Press, Modifiers::Control) => {
286                    self.window.set_should_close(true);
287                    break;  // no use in polling other events
288                },
289                // Free the camera from tracking.
290                WindowEvent::Key(Key::Escape, _, Action::Press, _) => {
291                    self.camera.free();
292                },
293                // Display the help menu.
294                WindowEvent::Key(Key::F1, _, Action::Press, _) => {
295                    self.status_flags.toggle(ViewerStatusBits::HELP_MENU);
296                }
297                // Full screen
298                WindowEvent::Key(Key::F5, _, Action::Press, _) => {
299                    self.toggle_full_screen();
300                }
301                // Reset the simulation (the data).
302                WindowEvent::Key(Key::Backspace, _, Action::Press, _) => {
303                    data.reset();
304                    data.forward();
305                }
306                // Cycle to the next camera
307                WindowEvent::Key(Key::RightBracket, _, Action::Press, _) => {
308                    self.cycle_camera(1);
309                }
310                // Cycle to the previous camera
311                WindowEvent::Key(Key::LeftBracket, _, Action::Press, _) => {
312                    self.cycle_camera(-1);
313                }
314                // Toggles camera visualization.
315                WindowEvent::Key(Key::C, _, Action::Press, _) => {
316                    self.toggle_opt_flag(MjtVisFlag::mjVIS_CAMERA);
317                }
318                WindowEvent::Key(Key::U, _, Action::Press, _) => {
319                    self.toggle_opt_flag(MjtVisFlag::mjVIS_ACTUATOR);
320                }
321                WindowEvent::Key(Key::J, _, Action::Press, _) => {
322                    self.toggle_opt_flag(MjtVisFlag::mjVIS_JOINT);
323                }
324                WindowEvent::Key(Key::M, _, Action::Press, _) => {
325                    self.toggle_opt_flag(MjtVisFlag::mjVIS_COM);
326                }
327                WindowEvent::Key(Key::H, _, Action::Press, _) => {
328                    self.toggle_opt_flag(MjtVisFlag::mjVIS_CONVEXHULL);
329                }
330                WindowEvent::Key(Key::Z, _, Action::Press, _) => {
331                    self.toggle_opt_flag(MjtVisFlag::mjVIS_LIGHT);
332                }
333                WindowEvent::Key(Key::T, _, Action::Press, _) => {
334                    self.toggle_opt_flag(MjtVisFlag::mjVIS_TRANSPARENT);
335                }
336                WindowEvent::Key(Key::I, _, Action::Press, _) => {
337                    self.toggle_opt_flag(MjtVisFlag::mjVIS_INERTIA);
338                }
339                // Zoom in/out
340                WindowEvent::Scroll(_, change) => {
341                    self.process_scroll(change);
342                }
343                // Track cursor, possibly applying perturbations.
344                WindowEvent::CursorPos(x, y) => {
345                    self.process_cursor_pos(x, y, data);
346                },
347
348                // Process left clicks, for selection ob bodies.
349                WindowEvent::MouseButton(MouseButton::Left, action, modifiers) => {
350                    self.process_left_click(data, &action, &modifiers);
351                }
352                _ => {}  // ignore other events
353            }
354        }
355    }
356
357    /// Toggles visualization options.
358    fn toggle_opt_flag(&mut self, flag: MjtVisFlag) {
359        let index = flag as usize;
360        self.opt.flags[index] = !self.opt.flags[index];
361    }
362
363    /// Cycle MJCF defined cameras.
364    fn cycle_camera(&mut self, direction: i32) {
365        let n_cam = self.model.ffi().ncam;
366        if n_cam == 0 {  // No cameras, ignore.
367            return;
368        }
369
370        self.camera.fix((self.camera.fixedcamid + direction).rem_euclid(n_cam) as u32);
371    }
372
373    /// Toggles full screen mode.
374    fn toggle_full_screen(&mut self) {
375        self.glfw.with_primary_monitor(|_, m| {
376            if let Some(monitor) = m {
377                /* Obtain the new window mode outside due to lifetimes requirements */
378                let (
379                    new_mode,
380                    w, h,
381                    x, y
382                ) = self.window.with_window_mode(|mode| {
383                    // Try to obtain the monitor size, so we can center the window after.
384                    // Assume 720p (16:9) if the size can't be read.
385                    let (w, h) = monitor.get_video_mode()
386                        .map_or((1280, 720), |x| (x.width, x.height));
387                    if let WindowMode::FullScreen(_) = mode {
388                        (WindowMode::Windowed, 1280, 720, (w - 1280) / 2, (h - 720) / 2)
389                    }
390                    else {
391                        (WindowMode::FullScreen(monitor), w, h, 0, 0)
392                    }
393                });
394                self.window.set_monitor(
395                    new_mode,
396                    x as i32, y as i32,
397                    w, h, None
398                );
399            }
400        });
401    }
402
403    /// Processes scrolling events.
404    fn process_scroll(&mut self, change: f64) {
405        self.camera.move_(MjtMouse::mjMOUSE_ZOOM, self.model, 0.0, -0.05 * change, &self.scene);
406    }
407
408    /// Processes camera and perturbation movements.
409    fn process_cursor_pos(&mut self, x: f64, y: f64, data: &mut MjData) {
410        /* Calculate the change in mouse position since last call */
411        let dx = x - self.last_x;
412        let dy = y - self.last_y;
413        self.last_x = x;
414        self.last_y = y;
415
416        /* Check mouse presses and move the camera if any of them is pressed */
417        let action;
418        let height = self.window.get_size().1 as f64;
419
420        let shift = self.window.get_key(Key::LeftShift) == Action::Press;
421
422        if self.status_flags.contains(ViewerStatusBits::LEFT_CLICK) {
423            if self.pert.active == MjtPertBit::mjPERT_TRANSLATE as i32 {
424                action = if shift {MjtMouse::mjMOUSE_MOVE_H} else {MjtMouse::mjMOUSE_MOVE_V};
425            }
426            else {
427                action = if shift {MjtMouse::mjMOUSE_ROTATE_H} else {MjtMouse::mjMOUSE_ROTATE_V};
428            }
429        }
430        else if self.window.get_mouse_button(MouseButton::Right) == Action::Press {
431            action = if shift {MjtMouse::mjMOUSE_MOVE_H} else {MjtMouse::mjMOUSE_MOVE_V};
432        }
433        else if self.window.get_mouse_button(MouseButton::Middle) == Action::Press {
434            action = MjtMouse::mjMOUSE_ZOOM;
435        }
436        else {
437            return;  // If buttons aren't pressed, ignore.
438        }
439
440        /* When the perturbation isn't active, move the camera */
441        if self.pert.active == 0 {
442            self.camera.move_(action, self.model, dx / height, dy / height, &self.scene);
443        }
444        else {  // When the perturbation is active, move apply the perturbation.
445            self.pert.move_(self.model, data, action, dx / height, dy / height, &self.scene);
446        }
447    }
448
449    /// Processes left clicks and double left clicks.
450    fn process_left_click(&mut self, data: &mut MjData, action: &Action, modifiers: &Modifiers) {
451        match action {
452            Action::Press => {
453                /* Clicking and holding applies perturbation */
454                if self.pert.select > 0 && modifiers.contains(Modifiers::Control) {
455                    let type_ = if modifiers.contains(Modifiers::Alt) {
456                        MjtPertBit::mjPERT_TRANSLATE
457                    } else {
458                        MjtPertBit::mjPERT_ROTATE
459                    };
460                    self.pert.start(type_, &self.model, data, &self.scene);
461                }
462
463                /* Double click detection */
464                if !self.status_flags.contains(ViewerStatusBits::LEFT_CLICK) && self.last_bnt_press_time.elapsed().as_millis() < DOUBLE_CLICK_WINDOW_MS {
465                    let (mut x, mut y) = self.window.get_cursor_pos();
466
467                    /* Fix the coordinates */
468                    let buffer_ratio = self.window.get_framebuffer_size().0 as f64 / self.window.get_size().0 as f64;
469                    x *= buffer_ratio;
470                    y *= buffer_ratio;
471                    y = self.rect_full.height as f64 - y;  // match OpenGL's coordinate system.
472
473                    /* Obtain the selection */ 
474                    let rect: &mjrRect_ = &self.rect_view;
475                    let (body_id, _, flex_id, skin_id, xyz) = self.scene.find_selection(
476                        data, &self.opt,
477                        rect.width as MjtNum / rect.height as MjtNum,
478                        (x - rect.left as MjtNum) / rect.width as MjtNum,
479                        (y - rect.bottom as MjtNum) / rect.height as MjtNum
480                    );
481
482                    /* Set tracking camera */
483                    if modifiers.contains(Modifiers::Alt) {
484                        if body_id >= 0 {
485                            self.camera.lookat = xyz;
486                            if modifiers.contains(Modifiers::Control) {
487                                self.camera.track(body_id as u32);
488                            }
489                        }
490                    }
491                    else {
492                        /* Mark selection */
493                        if body_id >= 0 {
494                            self.pert.select = body_id;
495                            self.pert.flexselect = flex_id;
496                            self.pert.skinselect = skin_id;
497                            self.pert.active = 0;
498                            self.pert.update_local_pos(xyz, data);
499                        }
500                        else {
501                            self.pert.select = 0;
502                            self.pert.flexselect = -1;
503                            self.pert.skinselect = -1;
504                        }
505                    }
506                }
507                self.last_bnt_press_time = Instant::now();
508                self.status_flags.set(ViewerStatusBits::LEFT_CLICK, true);
509            },
510            Action::Release => {
511                // Clear perturbation when left click is released.
512                self.pert.active = 0;
513                self.status_flags.remove(ViewerStatusBits::LEFT_CLICK);
514            },
515            Action::Repeat => {}
516        };
517    }
518}
519
520
521
522bitflags! {
523    /// Boolean flags that define some of
524    /// the Viewer's internal state.
525    #[derive(Debug)]
526    struct ViewerStatusBits: u8 {
527        const LEFT_CLICK = 1 << 0;
528        const HELP_MENU  = 1 << 1;
529    }
530}
531
532/****************************************** */
533// C++ viewer wrapper
534/****************************************** */
535/// Wrapper around the C++ implementation of MujoCo viewer.
536/// If you don't need the side UI, we recommend you use the Rust-native viewer [`MjViewer`] instead.
537#[cfg(feature = "cpp-viewer")]
538pub struct MjViewerCpp<'m> {
539    sim: *mut mujoco_Simulate,
540    running: bool,
541
542    // Store these here since the C++ bindings save references to them.
543    // We don't actually need them ourselves, at least not here.
544    _cam: Box<MjvCamera>,
545    _opt: Box<MjvOption>,
546    _pert: Box<MjvPerturb>,
547    _user_scn: Box<MjvScene<'m>>,
548    _glfw: glfw::Glfw
549}
550
551#[cfg(feature = "cpp-viewer")]
552impl<'m> MjViewerCpp<'m> {
553    #[inline]
554    pub fn running(&self) -> bool {
555        self.running
556    }
557
558    #[inline]
559    pub fn user_scn_mut(&mut self) -> &mut MjvScene<'m> {
560        &mut self._user_scn
561    }
562
563    /// Launches a wrapper around MuJoCo's C++ viewer. The `scene_max_geom` parameter
564    /// defines how much space will be allocated for additional, user-defined visual-only geoms.
565    /// It can thus be set to 0 if no additional geoms will be drawn by the user.
566    /// Unlike the Rust-native viewer ([`MjViewer`]), this also accepts a `data` parameter.
567    /// Additionally, this just returns a [`MjViewerCpp`] instance directly, without result
568    /// as the initialization may fail internally in C++ anyway, which we have no way of checking.
569    ///
570    /// # Safety
571    /// To allow certain flexibility, while still maintaining
572    /// compatibility with the C++ code, [`MjViewerCpp`] keeps internals pointers to mjModel and mjData,
573    /// which are wrapped inside [`MjModel`] and [`MjData`], respectively.
574    /// This technically allows `model` and `data` to be modified
575    /// while the viewer keeps a pointer to them (their wrapped pointers).
576    /// Undefined behavior should not occur, however caution is advised as this is a violation
577    /// of the Rust's borrowing rules.
578    pub fn launch_passive(model: &'m MjModel, data: &MjData, scene_max_geom: usize) -> Self {
579        let mut _glfw = glfw::init(glfw::fail_on_errors).unwrap();
580
581        // Allocate on the heap as the data must not be moved due to C++ bindings
582        let mut _cam = Box::new(MjvCamera::default());
583        let mut _opt: Box<MjvOption> = Box::new(MjvOption::default());
584        let mut _pert = Box::new(MjvPerturb::default());
585        let mut _user_scn = Box::new(MjvScene::new(&model, scene_max_geom));
586        let sim;
587        let c_filename = CString::new("file.xml").unwrap();
588        unsafe {
589            sim = new_simulate(&mut *_cam, &mut *_opt, &mut *_pert, _user_scn.ffi_mut(), true);
590            (*sim).RenderInit();
591            (*sim).Load(model.__raw(), data.__raw(), c_filename.as_ptr());
592            (*sim).RenderStep(true);
593        }
594
595        Self {sim, running: true, _cam, _opt, _pert, _glfw, _user_scn}
596    }
597
598    /// Returns the underlying C++ binding object of the viewer.
599    pub fn __raw(&self) -> *mut mujoco_Simulate {
600        self.sim
601    }
602
603    /// Renders the simulation.
604    /// `update_timer` flag species whether the time should be updated
605    /// inside the viewer (for vsync purposes).
606    /// # SAFETY
607    /// This needs to be called periodically from the MAIN thread, otherwise
608    /// GLFW stops working.
609    pub fn render(&mut self, update_timer: bool) {
610        unsafe {
611            assert!(self.running, "render called after viewer has been closed!");
612            self.running = (*self.sim).RenderStep(update_timer);
613        }
614    }
615
616    /// Syncs the simulation state with the viewer as well as perform
617    /// rendering on the viewer.
618    pub fn sync(&mut self) {
619        unsafe {
620            (*self.sim).Sync(false);
621        }
622    }
623}
624
625#[cfg(feature = "cpp-viewer")]
626impl Drop for MjViewerCpp<'_> {
627    fn drop(&mut self) {
628        unsafe {
629            (*self.sim).RenderCleanup();
630            free_simulate(self.sim);
631        }
632    }
633}