1use glfw::{Action, Context, Glfw, GlfwReceiver, Key, Modifiers, MouseButton, PWindow, WindowEvent};
4use bitflags::bitflags;
5
6use std::time::Instant;
7use std::fmt::Display;
8use std::error::Error;
9
10use crate::{get_mujoco_version, mujoco_c::*};
11
12#[cfg(feature = "cpp-viewer")]
13use std::ffi::CString;
14
15use crate::prelude::{MjrContext, MjrRectangle, MjtFont, MjtGridPos};
16use crate::wrappers::mj_primitive::MjtNum;
17use crate::wrappers::mj_visualization::*;
18use crate::wrappers::mj_model::MjModel;
19use crate::wrappers::mj_data::MjData;
20
21const MJ_VIEWER_DEFAULT_SIZE_PX: (u32, u32) = (1280, 720);
25const DOUBLE_CLICK_WINDOW_MS: u128 = 250;
26
27const HELP_MENU_TITLES: &str = concat!(
28 "Toggle help\n",
29 "Free camera\n",
30 "Track camera\n",
31 "Camera orbit\n",
32 "Camera pan\n",
33 "Camera look at\n",
34 "Zoom\n",
35 "Object select\n",
36 "Selection rotate\n",
37 "Selection translate\n",
38 "Exit"
39);
40
41const HELP_MENU_VALUES: &str = concat!(
42 "F1\n",
43 "Escape\n",
44 "Control + Alt + double-left click\n",
45 "Left drag\n",
46 "Right [+Shift] drag\n",
47 "Alt + double-left click\n",
48 "Zoom, middle drag\n",
49 "Double-left click\n",
50 "Control + [Shift] + drag\n",
51 "Control + Alt + [Shift] + drag\n",
52 "Control + Q"
53);
54
55#[derive(Debug)]
56pub enum MjViewerError {
57 GlfwInitError (glfw::InitError),
58 WindowCreationError
59}
60
61impl Display for MjViewerError {
62 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
63 match self {
64 Self::GlfwInitError(e) => write!(f, "glfw failed to initialize: {}", e),
65 Self::WindowCreationError => write!(f, "failed to create window"),
66 }
67 }
68}
69
70impl Error for MjViewerError {
71 fn source(&self) -> Option<&(dyn Error + 'static)> {
72 match self {
73 Self::GlfwInitError(e) => Some(e),
74 _ => None
75 }
76 }
77}
78
79#[derive(Debug)]
100pub struct MjViewer<'m> {
101 scene: MjvScene<'m>,
103 context: MjrContext,
104 camera: MjvCamera,
105
106 model: &'m MjModel,
108 pert: MjvPerturb,
109
110 last_x: f64,
112 last_y: f64,
113 last_bnt_press_time: Instant,
114 rect_view: MjrRectangle,
115 rect_full: MjrRectangle,
116 status_flags: ViewerStatusBits, glfw: Glfw,
120 window: PWindow,
121 events: GlfwReceiver<(f64, WindowEvent)>,
122
123 user_scene: MjvScene<'m>
125}
126
127impl<'m> MjViewer<'m> {
128 pub fn launch_passive(model: &'m MjModel, scene_max_geom: usize) -> Result<Self, MjViewerError> {
133 let mut glfw = glfw::init_no_callbacks()
134 .map_err(|err| MjViewerError::GlfwInitError(err))?;
135
136 let (w, h) = MJ_VIEWER_DEFAULT_SIZE_PX;
137 let title = format!("MuJoCo Rust Viewer (MuJoCo {})", get_mujoco_version());
138
139 let (mut window, events) = match glfw.create_window(
140 w, h, &title,
141 glfw::WindowMode::Windowed
142 ) {
143 Some(x) => Ok(x),
144 None => Err(MjViewerError::WindowCreationError)
145 }?;
146
147 window.make_current();
149 window.set_all_polling(true);
150 glfw.set_swap_interval(glfw::SwapInterval::None);
151
152 let scene = MjvScene::new(model, model.ffi().ngeom as usize + scene_max_geom + EXTRA_SCENE_GEOM_SPACE);
153 let user_scene = MjvScene::new(model, scene_max_geom);
154 let context= MjrContext::new(model);
155 let camera = MjvCamera::new_free(model);
156 let pert = MjvPerturb::default();
157 Ok(Self {
158 scene,
159 context,
160 camera,
161 model,
162 pert,
163 glfw,
164 window,
165 events,
166 user_scene,
167 last_x: 0.0,
168 last_y: 0.0,
169 status_flags: ViewerStatusBits::HELP_MENU,
170 last_bnt_press_time: Instant::now(),
171 rect_view: MjrRectangle::default(),
172 rect_full: MjrRectangle::default(),
173 })
174 }
175
176 pub fn running(&self) -> bool {
178 !self.window.should_close()
179 }
180
181 pub fn user_scene(&self) -> &MjvScene<'m>{
184 &self.user_scene
185 }
186
187 pub fn user_scene_mut(&mut self) -> &mut MjvScene<'m>{
190 &mut self.user_scene
191 }
192
193 #[deprecated(since = "1.3.0", note = "use user_scene")]
194 pub fn user_scn(&self) -> &MjvScene<'m> {
195 self.user_scene()
196 }
197
198 #[deprecated(since = "1.3.0", note = "use user_scene_mut")]
199 pub fn user_scn_mut(&mut self) -> &mut MjvScene<'m> {
200 self.user_scene_mut()
201 }
202
203 pub fn sync(&mut self, data: &mut MjData) {
206 self.window.make_current();
208
209 self.process_events(data);
211
212 self.update_scene(data);
214
215 self.update_menus();
217
218 self.window.swap_buffers();
220
221 self.pert.apply(self.model, data);
223 }
224
225 fn update_scene(&mut self, data: &mut MjData) {
227 let model_data_ptr = unsafe { data.model().__raw() };
228 let bound_model_ptr = unsafe { self.model.__raw() };
229 assert_eq!(model_data_ptr, bound_model_ptr, "'data' must be created from the same model as the viewer.");
230
231 self.update_rectangles(self.window.get_framebuffer_size());
233
234 let opt = MjvOption::default();
236 self.scene.update(data, &opt, &self.pert, &mut self.camera);
237
238 sync_geoms(&self.user_scene, &mut self.scene)
240 .expect("could not sync the user scene with the internal scene; this is a bug, please report it.");
241
242 self.scene.render(&self.rect_full, &self.context);
243 }
244
245 fn update_menus(&mut self) {
247 let mut rectangle = self.rect_view;
248 rectangle.width = rectangle.width - rectangle.width / 4;
249
250 if self.status_flags.contains(ViewerStatusBits::HELP_MENU) { self.context.overlay(
254 MjtFont::mjFONT_NORMAL, MjtGridPos::mjGRID_TOPLEFT,
255 rectangle,
256 HELP_MENU_TITLES,
257 Some(HELP_MENU_VALUES)
258 );
259 }
260 }
261
262 fn update_rectangles(&mut self, viewport_size: (i32, i32)) {
265 self.rect_view.width = viewport_size.0;
267 self.rect_view.height = viewport_size.1;
268
269 self.rect_full.width = viewport_size.0;
270 self.rect_full.height = viewport_size.1;
271 }
272
273 fn process_events(&mut self, data: &mut MjData) {
275 self.glfw.poll_events();
276 while let Some((_, event)) = self.events.receive() {
277 match event {
278 WindowEvent::Key(Key::Q, _, Action::Press, Modifiers::Control) => {
279 self.window.set_should_close(true);
280 break; },
282 WindowEvent::Key(Key::Escape, _, Action::Press, _) => {
283 self.camera.free();
284 },
285
286 WindowEvent::Key(Key::F1, _, Action::Press, _) => {
287 self.status_flags.toggle(ViewerStatusBits::HELP_MENU);
288 }
289
290 WindowEvent::Scroll(_, change) => {
291 self.process_scroll(change);
292 }
293 WindowEvent::CursorPos(x, y) => {
294 self.process_cursor_pos(x, y, data);
295 },
296
297 WindowEvent::MouseButton(MouseButton::Left, action, modifiers) => {
299 self.process_left_click(data, &action, &modifiers);
300 }
301 _ => {} }
303 }
304 }
305
306 fn process_scroll(&mut self, change: f64) {
308 self.camera.move_(MjtMouse::mjMOUSE_ZOOM, self.model, 0.0, -0.05 * change, &self.scene);
309 }
310
311 fn process_cursor_pos(&mut self, x: f64, y: f64, data: &mut MjData) {
313 let dx = x - self.last_x;
315 let dy = y - self.last_y;
316 self.last_x = x;
317 self.last_y = y;
318
319 let action;
321 let height = self.window.get_size().1 as f64;
322
323 let shift = self.window.get_key(Key::LeftShift) == Action::Press;
324
325 if self.status_flags.contains(ViewerStatusBits::LEFT_CLICK) {
326 if self.pert.active == MjtPertBit::mjPERT_TRANSLATE as i32 {
327 action = if shift {MjtMouse::mjMOUSE_MOVE_H} else {MjtMouse::mjMOUSE_MOVE_V};
328 }
329 else {
330 action = if shift {MjtMouse::mjMOUSE_ROTATE_H} else {MjtMouse::mjMOUSE_ROTATE_V};
331 }
332 }
333 else if self.window.get_mouse_button(MouseButton::Right) == Action::Press {
334 action = if shift {MjtMouse::mjMOUSE_MOVE_H} else {MjtMouse::mjMOUSE_MOVE_V};
335 }
336 else if self.window.get_mouse_button(MouseButton::Middle) == Action::Press {
337 action = MjtMouse::mjMOUSE_ZOOM;
338 }
339 else {
340 return; }
342
343 if self.pert.active == 0 {
345 self.camera.move_(action, self.model, dx / height, dy / height, &self.scene);
346 }
347 else { self.pert.move_(self.model, data, action, dx / height, dy / height, &self.scene);
349 }
350 }
351
352 fn process_left_click(&mut self, data: &mut MjData, action: &Action, modifiers: &Modifiers) {
354 match action {
355 Action::Press => {
356 if self.pert.select > 0 && modifiers.contains(Modifiers::Control) {
358 let type_ = if modifiers.contains(Modifiers::Alt) {
359 MjtPertBit::mjPERT_TRANSLATE
360 } else {
361 MjtPertBit::mjPERT_ROTATE
362 };
363 self.pert.start(type_, &self.model, data, &self.scene);
364 }
365
366 if !self.status_flags.contains(ViewerStatusBits::LEFT_CLICK) && self.last_bnt_press_time.elapsed().as_millis() < DOUBLE_CLICK_WINDOW_MS {
368 let (mut x, mut y) = self.window.get_cursor_pos();
369
370 let buffer_ratio = self.window.get_framebuffer_size().0 as f64 / self.window.get_size().0 as f64;
372 x *= buffer_ratio;
373 y *= buffer_ratio;
374 y = self.rect_full.height as f64 - y; let rect: &mjrRect_ = &self.rect_view;
378 let (body_id, _, flex_id, skin_id, xyz) = self.scene.find_selection(
379 data, &MjvOption::default(),
380 rect.width as MjtNum / rect.height as MjtNum,
381 (x - rect.left as MjtNum) / rect.width as MjtNum,
382 (y - rect.bottom as MjtNum) / rect.height as MjtNum
383 );
384
385 if modifiers.contains(Modifiers::Alt) {
387 if body_id >= 0 {
388 self.camera.lookat = xyz;
389 if modifiers.contains(Modifiers::Control) {
390 self.camera.track(body_id as u32);
391 }
392 }
393 }
394 else {
395 if body_id >= 0 {
397 self.pert.select = body_id;
398 self.pert.flexselect = flex_id;
399 self.pert.skinselect = skin_id;
400 self.pert.active = 0;
401 self.pert.update_local_pos(xyz, data);
402 }
403 else {
404 self.pert.select = 0;
405 self.pert.flexselect = -1;
406 self.pert.skinselect = -1;
407 }
408 }
409 }
410 self.last_bnt_press_time = Instant::now();
411 self.status_flags.set(ViewerStatusBits::LEFT_CLICK, true);
412 },
413 Action::Release => {
414 self.pert.active = 0;
416 self.status_flags.remove(ViewerStatusBits::LEFT_CLICK);
417 },
418 Action::Repeat => {}
419 };
420 }
421}
422
423
424
425bitflags! {
426 #[derive(Debug)]
429 struct ViewerStatusBits: u8 {
430 const LEFT_CLICK = 1 << 0;
431 const HELP_MENU = 1 << 1;
432 }
433}
434
435#[cfg(feature = "cpp-viewer")]
441pub struct MjViewerCpp<'m> {
442 sim: *mut mujoco_Simulate,
443 running: bool,
444
445 _cam: Box<MjvCamera>,
448 _opt: Box<MjvOption>,
449 _pert: Box<MjvPerturb>,
450 _user_scn: Box<MjvScene<'m>>,
451 _glfw: glfw::Glfw
452}
453
454#[cfg(feature = "cpp-viewer")]
455impl<'m> MjViewerCpp<'m> {
456 #[inline]
457 pub fn running(&self) -> bool {
458 self.running
459 }
460
461 #[inline]
462 pub fn user_scn_mut(&mut self) -> &mut MjvScene<'m> {
463 &mut self._user_scn
464 }
465
466 pub fn launch_passive(model: &'m MjModel, data: &MjData, scene_max_geom: usize) -> Self {
482 let mut _glfw = glfw::init(glfw::fail_on_errors).unwrap();
483
484 let mut _cam = Box::new(MjvCamera::default());
486 let mut _opt: Box<MjvOption> = Box::new(MjvOption::default());
487 let mut _pert = Box::new(MjvPerturb::default());
488 let mut _user_scn = Box::new(MjvScene::new(&model, scene_max_geom));
489 let sim;
490 let c_filename = CString::new("file.xml").unwrap();
491 unsafe {
492 sim = new_simulate(&mut *_cam, &mut *_opt, &mut *_pert, _user_scn.ffi_mut(), true);
493 (*sim).RenderInit();
494 (*sim).Load(model.__raw(), data.__raw(), c_filename.as_ptr());
495 (*sim).RenderStep(true);
496 }
497
498 Self {sim, running: true, _cam, _opt, _pert, _glfw, _user_scn}
499 }
500
501 pub fn __raw(&self) -> *mut mujoco_Simulate {
503 self.sim
504 }
505
506 pub fn render(&mut self, update_timer: bool) {
513 unsafe {
514 assert!(self.running, "render called after viewer has been closed!");
515 self.running = (*self.sim).RenderStep(update_timer);
516 }
517 }
518
519 pub fn sync(&mut self) {
522 unsafe {
523 (*self.sim).Sync(false);
524 }
525 }
526}
527
528#[cfg(feature = "cpp-viewer")]
529impl Drop for MjViewerCpp<'_> {
530 fn drop(&mut self) {
531 unsafe {
532 (*self.sim).RenderCleanup();
533 free_simulate(self.sim);
534 }
535 }
536}