mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
Visualization

GLFW window management and the real-time render/tick loop. More...

Classes

struct  mj_kdl::Viewer
 

Functions

bool mj_kdl::init_window (Viewer *v, Robot *r, const char *title="MuJoCo", int width=1280, int height=720)
 
bool mj_kdl::init_window_sim (Viewer *v, Robot *r, const char *title="MuJoCo")
 
void mj_kdl::cleanup (Viewer *v)
 
bool mj_kdl::is_running (const Viewer *v)
 
bool mj_kdl::render (Viewer *v, const Robot *r)
 
bool mj_kdl::render (Viewer *v, mjModel *m, mjData *d)
 
bool mj_kdl::tick (Viewer *v, Robot *r)
 
bool mj_kdl::tick (Viewer *v, mjModel *m, mjData *d)
 

Detailed Description

GLFW window management and the real-time render/tick loop.

Use init_window_sim() + tick() for the full simulate UI with physics panels. Use init_window() + render() for a lightweight manual render loop.

Function Documentation

◆ cleanup()

void mj_kdl::cleanup ( Viewer v)

Release the GLFW window and MuJoCo visualization contexts owned by v.

Parameters
[in,out]vViewer to tear down; all pointers set to null afterwards.

◆ init_window()

bool mj_kdl::init_window ( Viewer v,
Robot r,
const char *  title = "MuJoCo",
int  width = 1280,
int  height = 720 
)

Open a GLFW window and initialise MuJoCo visualization contexts. Must be called after init_robot() or init_from_mjcf().

Parameters
[out]vViewer to initialise; must be zero-initialised before call.
[in]rRobot whose model drives the rendering context.
[in]titleWindow title string.
[in]widthWindow width in pixels.
[in]heightWindow height in pixels.
Returns
true on success, false if GLFW or MuJoCo context creation fails.

◆ init_window_sim()

bool mj_kdl::init_window_sim ( Viewer v,
Robot r,
const char *  title = "MuJoCo" 
)

Open the full MuJoCo simulate UI (panels, physics controls, joint viewer) in a background render thread, then return so the caller can drive the physics loop with tick().

Use this instead of init_window() when you want the simulate UI panels alongside a user-owned loop. tick() automatically acquires the render mutex, steps physics, and handles pause / perturbation / speed controls.

Note: the render thread owns the GLFW window; on Linux (X11 / Wayland) this works correctly. Not supported on macOS.

Parameters
[out]vViewer to initialise; freed by cleanup(Viewer *).
[in]rRobot to simulate.
[in]titleLabel shown in the window title bar (default "MuJoCo").
Returns
true on success.

Referenced by main().

◆ is_running()

bool mj_kdl::is_running ( const Viewer v)

Returns true if the viewer window is open and not scheduled for closing.

Parameters
[in]vViewer created by init_window().

◆ render() [1/2]

bool mj_kdl::render ( Viewer v,
const Robot r 
)

Render the current simulation frame to the viewer window.

Parameters
[in,out]vViewer created by init_window().
[in]rRobot whose model and data are rendered.
Returns
true if the window is still open after rendering.

◆ render() [2/2]

bool mj_kdl::render ( Viewer v,
mjModel *  m,
mjData *  d 
)

Render the current simulation frame to the viewer window. Model/data overload – use when no single Robot owns the scene (e.g. multi-robot).

Parameters
[in,out]vViewer created by init_window().
[in]mMuJoCo model.
[in]dMuJoCo data.
Returns
true if the window is still open after rendering.

◆ tick() [1/2]

bool mj_kdl::tick ( Viewer v,
mjModel *  m,
mjData *  d 
)

Model/data overload of tick() for multi-robot or model-owned loops where no single Robot is the canonical owner of the scene. Physics always runs (paused state is not tracked; use the sim UI pause button when using init_window_sim, or manage it externally for init_window).

Parameters
[in,out]vViewer initialised by init_window() or init_window_sim().
[in]mShared MuJoCo model.
[in]dShared MuJoCo data.
Returns
true while the window is open; false once the user closes it.

◆ tick() [2/2]

bool mj_kdl::tick ( Viewer v,
Robot r 
)

Advance one physics step, render, sync to real time, and poll GLFW events. Intended for user-owned control loops; call once per control cycle.

Sequence inside tick():

  1. glfwPollEvents() – fires keyboard / mouse callbacks
  2. real-time sleep – paces the loop to model->opt.timestep wall time
  3. if (!r->paused): apply mouse perturbation forces (if active) mj_step()
  4. render()

update() is NOT called here – call it yourself to read *_msr and apply *_cmd. Typical loop:

update(&robot); // seed initial sensor readings while (tick(&viewer, &robot)) { my_control_step(&robot); // reads *_msr, writes *_cmd update(&robot); // applies *_cmd, refreshes *_msr for next step }

Returns
true while the window is open; false once the user closes it.

Referenced by main().