1use 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
23const 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#[derive(Debug)]
111pub struct MjViewer<'m> {
112 scene: MjvScene<'m>,
114 context: MjrContext,
115 camera: MjvCamera,
116
117 model: &'m MjModel,
119 pert: MjvPerturb,
120 opt: MjvOption,
121
122 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, glfw: Glfw,
132 window: PWindow,
133 events: GlfwReceiver<(f64, WindowEvent)>,
134
135 user_scene: MjvScene<'m>
137}
138
139impl<'m> MjViewer<'m> {
140 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 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 pub fn running(&self) -> bool {
186 !self.window.should_close()
187 }
188
189 pub fn user_scene(&self) -> &MjvScene<'m>{
192 &self.user_scene
193 }
194
195 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 pub fn sync(&mut self, data: &mut MjData) {
214 self.window.make_current();
216
217 self.process_events(data);
219
220 self.update_scene(data);
222
223 self.update_menus();
225
226 self.window.swap_buffers();
228
229 self.pert.apply(self.model, data);
231 }
232
233 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 self.update_rectangles(self.window.get_framebuffer_size());
241
242 self.scene.update(data, &self.opt, &self.pert, &mut self.camera);
244
245 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 fn update_menus(&mut self) {
254 let mut rectangle = self.rect_view;
255 rectangle.width = rectangle.width - rectangle.width / 4;
256
257 if self.status_flags.contains(ViewerStatusBits::HELP_MENU) { 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 fn update_rectangles(&mut self, viewport_size: (i32, i32)) {
271 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 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 WindowEvent::Key(Key::Q, _, Action::Press, Modifiers::Control) => {
286 self.window.set_should_close(true);
287 break; },
289 WindowEvent::Key(Key::Escape, _, Action::Press, _) => {
291 self.camera.free();
292 },
293 WindowEvent::Key(Key::F1, _, Action::Press, _) => {
295 self.status_flags.toggle(ViewerStatusBits::HELP_MENU);
296 }
297 WindowEvent::Key(Key::F5, _, Action::Press, _) => {
299 self.toggle_full_screen();
300 }
301 WindowEvent::Key(Key::Backspace, _, Action::Press, _) => {
303 data.reset();
304 data.forward();
305 }
306 WindowEvent::Key(Key::RightBracket, _, Action::Press, _) => {
308 self.cycle_camera(1);
309 }
310 WindowEvent::Key(Key::LeftBracket, _, Action::Press, _) => {
312 self.cycle_camera(-1);
313 }
314 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 WindowEvent::Scroll(_, change) => {
341 self.process_scroll(change);
342 }
343 WindowEvent::CursorPos(x, y) => {
345 self.process_cursor_pos(x, y, data);
346 },
347
348 WindowEvent::MouseButton(MouseButton::Left, action, modifiers) => {
350 self.process_left_click(data, &action, &modifiers);
351 }
352 _ => {} }
354 }
355 }
356
357 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 fn cycle_camera(&mut self, direction: i32) {
365 let n_cam = self.model.ffi().ncam;
366 if n_cam == 0 { return;
368 }
369
370 self.camera.fix((self.camera.fixedcamid + direction).rem_euclid(n_cam) as u32);
371 }
372
373 fn toggle_full_screen(&mut self) {
375 self.glfw.with_primary_monitor(|_, m| {
376 if let Some(monitor) = m {
377 let (
379 new_mode,
380 w, h,
381 x, y
382 ) = self.window.with_window_mode(|mode| {
383 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 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 fn process_cursor_pos(&mut self, x: f64, y: f64, data: &mut MjData) {
410 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 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; }
439
440 if self.pert.active == 0 {
442 self.camera.move_(action, self.model, dx / height, dy / height, &self.scene);
443 }
444 else { self.pert.move_(self.model, data, action, dx / height, dy / height, &self.scene);
446 }
447 }
448
449 fn process_left_click(&mut self, data: &mut MjData, action: &Action, modifiers: &Modifiers) {
451 match action {
452 Action::Press => {
453 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 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 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; 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 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 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 self.pert.active = 0;
513 self.status_flags.remove(ViewerStatusBits::LEFT_CLICK);
514 },
515 Action::Repeat => {}
516 };
517 }
518}
519
520
521
522bitflags! {
523 #[derive(Debug)]
526 struct ViewerStatusBits: u8 {
527 const LEFT_CLICK = 1 << 0;
528 const HELP_MENU = 1 << 1;
529 }
530}
531
532#[cfg(feature = "cpp-viewer")]
538pub struct MjViewerCpp<'m> {
539 sim: *mut mujoco_Simulate,
540 running: bool,
541
542 _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 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 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 pub fn __raw(&self) -> *mut mujoco_Simulate {
600 self.sim
601 }
602
603 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 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}