mujoco_rs/
viewer.rs

1use glfw::{Action, Context, Glfw, GlfwReceiver, Key, Modifiers, MouseButton, PWindow, WindowEvent};
2
3use std::time::Instant;
4
5use crate::mujoco_c::*;
6
7#[cfg(feature = "cpp-viewer")]
8use std::ffi::CString;
9
10use crate::prelude::{MjrContext, MjrRectangle};
11use crate::wrappers::mj_visualization::*;
12use crate::wrappers::mj_model::MjModel;
13use crate::wrappers::mj_data::MjData;
14
15/****************************************** */
16// Rust native viewer
17/****************************************** */
18const MJ_VIEWER_DEFAULT_SIZE_PX: (u32, u32) = (1280, 720);
19const MJ_VIEWER_DEFAULT_TITLE: &str = "MuJoCo Viewer (Rust)";
20const DOUBLE_CLICK_WINDOW_MS: u128 = 250;
21
22
23#[derive(Debug)]
24pub enum MjViewerError {
25    GlfwInitError (glfw::InitError),
26    WindowCreationError
27}
28
29/// A Rust-native implementation of the MuJoCo viewer. To confirm to rust safety rules,
30/// the viewer doesn't store a mutable reference to the [`MjData`] struct, but it instead
31/// accepts it as a parameter at its methods.
32/// 
33/// Currently supported (to be expanded in the future):
34/// - Visualization of the 3D scene,
35/// - Close via Ctrl + Q or by closing the window,
36/// - Body tracking via Ctrl + double left-click,
37/// - Escape from tracked camera via Esc.
38/// 
39/// Only passive mode is available, which means the user must call [`MjViewer::sync`]
40/// to update the state inside the viewer.
41#[derive(Debug)]
42pub struct MjViewer<'m> {
43    /* MuJoCo rendering */
44    scene: MjvScene<'m>,
45    context: MjrContext,
46    camera: MjvCamera,
47
48    /* Other MuJoCo related */
49    model: &'m MjModel,
50    pert: MjvPerturb,
51
52    /* Internal state */
53    last_x: mjtNum,
54    last_y: mjtNum,
55    left_click: bool,
56    last_bnt_press_time: Instant,
57    rect_view: MjrRectangle,
58    rect_full: MjrRectangle,
59
60    /* OpenGL */
61    glfw: Glfw,
62    window: PWindow,
63    events: GlfwReceiver<(f64, WindowEvent)>
64}
65
66impl<'m> MjViewer<'m> {
67    /// Launches the MuJoCo viewer. A [`Result`] struct is returned that either contains
68    /// [`MjViewer`] or a [`MjViewerError`].
69    pub fn launch_passive(model: &'m MjModel, scene_max_ngeom: usize) -> Result<Self, MjViewerError> {
70        let mut glfw = glfw::init_no_callbacks()
71            .map_err(|err| MjViewerError::GlfwInitError(err))?;
72        let (w, h) = MJ_VIEWER_DEFAULT_SIZE_PX;
73        let (mut window, events) = match glfw.create_window(
74            w, h, MJ_VIEWER_DEFAULT_TITLE, glfw::WindowMode::Windowed
75        ) {
76            Some(x) => Ok(x),
77            None => Err(MjViewerError::WindowCreationError)
78        }?;
79
80        /* Initialize the OpenGL related things */
81        window.make_current();
82        window.set_all_polling(true);
83        glfw.set_swap_interval(glfw::SwapInterval::None);
84
85        let scene = MjvScene::new(model, scene_max_ngeom);
86        let context= MjrContext::new(model);
87        let camera = MjvCamera::new(0, MjtCamera::mjCAMERA_FREE, model);
88        let pert = MjvPerturb::default();
89        Ok(Self {
90            scene,
91            context,
92            camera,
93            model,
94            pert,
95            glfw,
96            window,
97            events,
98            last_x: 0.0,
99            last_y: 0.0,
100            left_click: false,
101            last_bnt_press_time: Instant::now(),
102            rect_view: MjrRectangle::default(),
103            rect_full: MjrRectangle::default(),
104        })
105    }
106
107    /// Checks whether the window is still open.
108    pub fn running(&self) -> bool {
109        !self.window.should_close()
110    }
111
112    pub fn sync(&mut self, data: &mut MjData) {
113        self.process_events(data);
114        self.update(data);
115    }
116
117
118    /// Updates the screen state
119    fn update(&mut self, data: &mut MjData) {
120        /* Read the screen size */
121        let mut viewport = MjrRectangle::default();
122        let (width, height) = self.window.get_framebuffer_size();
123        viewport.width = width;
124        viewport.height = height;
125
126        self.update_rectangles((width, height));
127
128        /* Update the scene from the MjData state */
129        let opt = MjvOption::default();
130        self.scene.update(data, &opt, &self.pert, &mut self.camera);
131        self.scene.render(&viewport, &self.context);
132
133        /* Display the changes */
134        self.window.swap_buffers();
135    }
136
137    /// Updates the dimensions of the rectangles defining the dimensions of
138    /// the user interface, as well as the actual scene viewer.
139    fn update_rectangles(&mut self, viewport_size: (i32, i32)) {
140        // The scene (middle) rectangle
141        self.rect_view.width = viewport_size.0;
142        self.rect_view.height = viewport_size.1;
143
144        self.rect_full.width = viewport_size.0;
145        self.rect_full.height = viewport_size.1;
146    }
147
148    /// Processes user input events
149    fn process_events(&mut self, data: &mut MjData) {
150        self.glfw.poll_events();
151        if let Some((_, event)) = self.events.receive() {
152            match event {
153                WindowEvent::Key(Key::Q, _, _, modifier) if modifier == Modifiers::Control => self.window.set_should_close(true),
154                WindowEvent::Key(Key::Escape, _, _, _) => {
155                    self.camera.free();
156                },
157                WindowEvent::Scroll(_, change) => {
158                    self.process_scroll(change);
159                }
160                WindowEvent::CursorPos(x, y) => {
161                    self.process_cursor_pos(x, y);
162                },
163
164                // Match left button presses
165                WindowEvent::MouseButton(MouseButton::Left, action, modifiers) => {
166                    self.process_left_click(data, &action, &modifiers);
167                }
168                _ => {}  // ignore other events
169            }
170        }
171    }
172
173    fn process_scroll(&mut self, change: f64) {
174        self.camera.move_(MjtMouse::mjMOUSE_ZOOM, self.model, 0.0, -0.05 * change, &self.scene);
175    }
176
177    fn process_cursor_pos(&mut self, x: f64, y: f64) {
178        /* Calculate the change in mouse position since last call */
179        let dx = x - self.last_x;
180        let dy = y - self.last_y;
181        self.last_x = x;
182        self.last_y = y;
183
184        /* Check mouse presses and move the camera if any of them is pressed */
185        let action;
186        let shift = self.window.get_key(Key::LeftShift) == Action::Press;
187
188        if self.window.get_mouse_button(MouseButton::Left) == Action::Press {
189            action = if shift {MjtMouse::mjMOUSE_ROTATE_H} else {MjtMouse::mjMOUSE_ROTATE_V};
190        }
191        else if self.window.get_mouse_button(MouseButton::Right) == Action::Press {
192            action = if shift {MjtMouse::mjMOUSE_MOVE_H} else {MjtMouse::mjMOUSE_MOVE_V};
193        }
194        else if self.window.get_mouse_button(MouseButton::Middle) == Action::Press {
195            action = MjtMouse::mjMOUSE_ZOOM;
196        }
197        else {
198            return;  // If buttons aren't pressed, ignore.
199        }
200
201        let height = self.window.get_size().1 as mjtNum;
202        self.camera.move_(action, self.model, dx / height, dy / height, &self.scene);
203    }
204
205    fn process_left_click(&mut self, data: &mut MjData, action: &Action, modifiers: &Modifiers) {
206        self.left_click = match action {
207            Action::Press => {
208                /* Double click detection */
209                if !self.left_click && self.last_bnt_press_time.elapsed().as_millis() < DOUBLE_CLICK_WINDOW_MS {
210                    let (mut x, mut y) = self.window.get_cursor_pos();
211
212                    /* Fix the coordinates */
213                    let buffer_ratio = self.window.get_framebuffer_size().0 as mjtNum / self.window.get_size().0 as mjtNum;
214                    x *= buffer_ratio;
215                    y *= buffer_ratio;
216                    y = self.rect_full.height as mjtNum - y;  // match OpenGL's coordinate system.
217
218                    /* Obtain the selection */ 
219                    let rect: &mjrRect_ = &self.rect_view;
220                    let (body_id, _, flex_id, skin_id, xyz) = self.scene.find_selection(
221                        data, &MjvOption::default(),
222                        rect.width as mjtNum / rect.height as mjtNum,
223                        (x - rect.left as mjtNum) / rect.width as mjtNum,
224                        (y - rect.bottom as mjtNum) / rect.height as mjtNum
225                    );
226
227                    /* Mark selection */
228                    self.pert.select = body_id;
229                    self.pert.flexselect = flex_id;
230                    self.pert.skinselect = skin_id;
231                    self.pert.active = 0;
232
233                    let mut tmp = [0.0; 3];
234                    unsafe {
235                        mju_sub3(tmp.as_mut_ptr(), xyz.as_ptr(), data.ffi().xpos.add((3 *self.pert.select) as usize));
236                        mju_mulMatTVec(self.pert.localpos.as_mut_ptr(), data.ffi().xmat.add((9*self.pert.select) as usize), tmp.as_ptr(), 3, 3);
237                    }
238
239                    /* Set tracking camera */
240                    if modifiers == &Modifiers::Control && body_id >= 0 {
241                        self.camera.track(body_id as u32);
242                    }
243                }
244                self.last_bnt_press_time = Instant::now();
245                true
246            },
247            Action::Release => false,
248            Action::Repeat => self.left_click
249        };
250    }
251}
252
253/****************************************** */
254// C++ viewer wrapper
255/****************************************** */
256/// Wrapper around the C++ implementation of MujoCo viewer
257#[cfg(feature = "cpp-viewer")]
258pub struct MjViewerCpp<'m> {
259    sim: *mut mujoco_Simulate,
260    running: bool,
261
262    // Store these here since the C++ bindings save references to them.
263    // We don't actually need them ourselves, at least not here.
264    _cam: Box<MjvCamera>,
265    _opt: Box<MjvOption>,
266    _pert: Box<MjvPerturb>,
267    _user_scn: Box<MjvScene<'m>>,
268    _glfw: glfw::Glfw
269}
270
271#[cfg(feature = "cpp-viewer")]
272impl<'m> MjViewerCpp<'m> {
273    #[inline]
274    pub fn running(&self) -> bool {
275        self.running
276    }
277
278    #[inline]
279    pub fn user_scn_mut(&mut self) -> &mut MjvScene<'m> {
280        &mut self._user_scn
281    }
282
283    pub fn launch_passive(model: &'m MjModel, data: &MjData, scene_max_ngeom: usize) -> Self {
284        let mut _glfw = glfw::init(glfw::fail_on_errors).unwrap();
285
286        // Allocate on the heap as the data must not be moved due to C++ bindings
287        let mut _cam = Box::new(MjvCamera::default());
288        let mut _opt: Box<MjvOption> = Box::new(MjvOption::default());
289        let mut _pert = Box::new(MjvPerturb::default());
290        let mut _user_scn = Box::new(MjvScene::new(&model, scene_max_ngeom));
291        let sim;
292        unsafe {
293            sim = new_simulate(&mut *_cam, &mut *_opt, &mut *_pert, _user_scn.ffi_mut(), true);
294            (*sim).RenderInit();
295            (*sim).Load(model.__raw(), data.__raw(), CString::new("file.xml").unwrap().as_ptr());
296            (*sim).RenderStep(true);
297        }
298
299        Self {sim, running: true, _cam, _opt, _pert, _glfw, _user_scn}
300    }
301
302    /// Returns the underlying C++ binding object of the viewer.
303    pub fn __raw(&self) -> *mut mujoco_Simulate {
304        self.sim
305    }
306
307    /// Renders the simulation.
308    /// `update_timer` flag species whether the time should be updated
309    /// inside the viewer (for vsync purposes).
310    /// # SAFETY
311    /// This needs to be called periodically from the MAIN thread, otherwise
312    /// GLFW stops working.
313    pub fn render(&mut self, update_timer: bool) {
314        unsafe {
315            assert!(self.running, "render called after viewer has been closed!");
316            self.running = (*self.sim).RenderStep(update_timer);
317        }
318    }
319
320    pub fn sync(&mut self) {
321        unsafe {
322            (*self.sim).Sync(false);
323        }
324    }
325}
326
327#[cfg(feature = "cpp-viewer")]
328impl Drop for MjViewerCpp<'_> {
329    fn drop(&mut self) {
330        unsafe {
331            (*self.sim).RenderCleanup();
332            free_simulate(self.sim);
333        }
334    }
335}