|
mj-kdl-wrapper
0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
|
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) |
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.
| void mj_kdl::cleanup | ( | Viewer * | v | ) |
Release the GLFW window and MuJoCo visualization contexts owned by v.
| [in,out] | v | Viewer to tear down; all pointers set to null afterwards. |
| 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().
| [out] | v | Viewer to initialise; must be zero-initialised before call. |
| [in] | r | Robot whose model drives the rendering context. |
| [in] | title | Window title string. |
| [in] | width | Window width in pixels. |
| [in] | height | Window height in pixels. |
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.
| [out] | v | Viewer to initialise; freed by cleanup(Viewer *). |
| [in] | r | Robot to simulate. |
| [in] | title | Label shown in the window title bar (default "MuJoCo"). |
Referenced by main().
| bool mj_kdl::is_running | ( | const Viewer * | v | ) |
Returns true if the viewer window is open and not scheduled for closing.
| [in] | v | Viewer created by init_window(). |
Render the current simulation frame to the viewer window.
| [in,out] | v | Viewer created by init_window(). |
| [in] | r | Robot whose model and data are rendered. |
| 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).
| [in,out] | v | Viewer created by init_window(). |
| [in] | m | MuJoCo model. |
| [in] | d | MuJoCo data. |
| 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).
| [in,out] | v | Viewer initialised by init_window() or init_window_sim(). |
| [in] | m | Shared MuJoCo model. |
| [in] | d | Shared MuJoCo data. |
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():
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 }
Referenced by main().