mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
mj_kdl_wrapper.hpp
Go to the documentation of this file.
1/* SPDX-License-Identifier: MIT
2 * Copyright (c) 2026 Vamsi Kalagaturu
3 * See LICENSE for details. */
4
5#pragma once
6
7#include <mujoco/mujoco.h>
8#include <GLFW/glfw3.h>
9#include <kdl/chain.hpp>
10#include <kdl/jntarray.hpp>
11#include <functional>
12#include <string>
13#include <vector>
14#include <chrono>
15#include <thread>
16#include <cstdio>
17#include <cstring>
18#include <sstream>
19
20namespace mj_kdl {
21
22/**
23 * @ingroup grp_logging
24 * Log verbosity level. Each level includes all levels below it:
25 * NONE - nothing printed.
26 * INFO - informational messages only (scene/chain construction progress).
27 * WARN - INFO + recoverable warnings (e.g. fallback to headless mode).
28 * ERROR - all messages, including errors that cause functions to fail. Default.
29 */
30enum class LogLevel { NONE = 0, INFO = 1, WARN = 2, ERROR = 3 };
31
32/** @ingroup grp_logging
33 * Library-wide log verbosity (inline so one shared instance across all TUs). */
35
36/** @ingroup grp_logging
37 * Set the library-wide log verbosity. */
38inline void set_log_level(LogLevel level) { g_log_level = level; }
39/** @ingroup grp_logging
40 * Get the library-wide log verbosity. */
42
43/* Logging macros - emit to stderr with colour, file:line, and function name. */
44#define MJ_FILENAME_ (::strrchr(__FILE__, '/') ? ::strrchr(__FILE__, '/') + 1 : __FILE__)
45
46#define MJ_LOG_(lvl_enum, color, label, expr) \
47 do { \
48 if (::mj_kdl::g_log_level >= ::mj_kdl::LogLevel::lvl_enum) { \
49 std::ostringstream _mj_oss; \
50 _mj_oss << expr; \
51 std::fprintf( \
52 stderr, \
53 color "[mj_kdl " label "] %s:%d (%s): %s\033[0m\n", \
54 MJ_FILENAME_, \
55 __LINE__, \
56 __func__, \
57 _mj_oss.str().c_str() \
58 ); \
59 } \
60 } while (0)
61
62#define LOG_INFO(expr) MJ_LOG_(INFO, "", "INFO ", expr)
63#define LOG_WARN(expr) MJ_LOG_(WARN, "\033[33m", "WARN ", expr)
64#define LOG_ERROR(expr) MJ_LOG_(ERROR, "\033[31m", "ERROR", expr)
65
66/**
67 * @ingroup grp_types
68 * One link in an ordered attachment chain for a robot.
69 * An attachment is any MJCF body (end effector, mount, FT sensor, tool, additional arm
70 * on a mobile base, etc.) attached under a named body in the accumulated robot spec.
71 * Attachments are applied in declaration order; attach_to may reference any body present
72 * after all prior attachments have been applied.
73 */
75{
76 const char *mjcf_path = nullptr; // MJCF file for this attachment
77 const char *attach_to = nullptr; // body to attach under (in root or prior attachment)
78 double pos[3] = { 0, 0, 0 }; // position offset [m]
79 double euler[3] = { 0, 0, 0 }; // extrinsic XYZ Euler offset [degrees]
80 const char *prefix = ""; // element name prefix (avoids name conflicts)
81
82 /* Contact exclusion pairs registered by attach_to_spec(). */
83 std::vector<std::pair<std::string, std::string>> contact_exclusions; // (body1, body2) pairs
84};
85
86/**
87 * @ingroup grp_types
88 * One robot in a scene: a root MJCF (arm, mobile base, ...) with an ordered attachment
89 * chain and world-frame placement.
90 *
91 * attachments is applied in order by build_scene() / attach_to_spec(): each entry's
92 * attach_to may reference any body in the accumulated spec (root + all prior attachments).
93 * This naturally supports: fixed arm, arm+gripper, arm+mount+FT+gripper, mobile base,
94 * mobile manipulator (base root, arm as first attachment), and so on.
95 *
96 * path is the root MJCF passed to build_scene(). prefix must be unique per robot
97 * in multi-robot scenes.
98 */
100{
101 const char *path = nullptr; // root MJCF path
102 std::vector<AttachmentSpec> attachments; // ordered attachment chain; empty = none
103 const char *prefix = ""; // element name prefix
104 double pos[3] = { 0, 0, 0 }; // world-frame position [m]
105 double euler[3] = { 0, 0, 0 }; // extrinsic XYZ Euler angles [degrees]
106};
107
108/**
109 * @ingroup grp_types
110 * Optional table to include in the scene.
111 * pos[2] is the table TOP SURFACE height (where robots and objects rest).
112 * Legs extend from the bottom of the tabletop panel down to z = 0.
113 */
115{
116 bool enabled = false;
117 double pos[3] = { 0.0, 0.0, 0.7 }; // (x, y, surface_z)
118 double top_size[2] = { 0.6, 0.4 }; // tabletop half-extents in x, y
119 double thickness = 0.04; // full thickness of tabletop panel
120 double leg_radius = 0.025; // leg cylinder radius
121 float rgba[4] = { 0.45f, 0.28f, 0.12f, 1.0f }; // tabletop colour (warm walnut)
122 float leg_rgba[4] = { 0.35f, 0.35f, 0.35f, 1.0f }; // leg colour (dark gray metal)
123};
124
125/** @ingroup grp_types
126 * Shape type for scene objects. */
127enum class Shape { BOX, SPHERE, CYLINDER };
128
129/**
130 * @ingroup grp_types
131 * A free-floating or fixed rigid body to place in the scene.
132 *
133 * size:
134 * BOX - half-extents (x, y, z)
135 * SPHERE - {radius, 0, 0}
136 * CYLINDER - {radius, half-length, 0}
137 *
138 * pos:
139 * World-frame position. To rest on the table set
140 * pos[2] = table.pos[2] + half-height (e.g. box: pos[2] = surface_z + size[2]).
141 *
142 * fixed:
143 * If true the body is welded to the world (no freejoint); useful for
144 * static obstacles or fixtures on the table.
145 */
147{
148 std::string name;
150 double size[3] = { 0.03, 0.03, 0.03 };
151 double pos[3] = { 0.0, 0.0, 0.0 };
152 float rgba[4] = { 1.0f, 0.0f, 0.0f, 1.0f };
153 bool fixed = false;
154 double mass = 0.1;
155 int condim = 3;
156 double friction[3] = { 0.5, 0.005, 0.0001 }; // MuJoCo defaults
157};
158
159/** @ingroup grp_types
160 * Full scene description passed to build_scene(). */
162{
163 std::vector<RobotSpec> robots;
164 double timestep = 0.002;
165 double gravity_z = -9.81;
166 bool add_floor = true; // checker groundplane geom
167 bool add_skybox = true; // gradient sky texture + directional light
169 std::vector<SceneObject> objects;
170};
171
172/**
173 * @ingroup grp_types
174 * Joint-space control mode for update().
175 * POSITION - writes jnt_pos_cmd to actuator ctrl inputs.
176 * TORQUE - writes jnt_trq_cmd to qfrc_applied (generalized forces).
177 */
178enum class CtrlMode { POSITION, TORQUE };
179
180/**
181 * @ingroup grp_types
182 * Runtime handle for one KDL-tracked articulation inside a MuJoCo scene.
183 * model/data are borrowed (never freed by cleanup()); call destroy_scene() separately.
184 *
185 * Workflow:
186 * 1. Call init_robot_from_mjcf() - populates configuration and sizes port vectors to n_joints.
187 * 2. Each control step: read *_msr ports (updated by update()), fill *_cmd ports,
188 * call update() to apply commands to MuJoCo and read back sensor state.
189 */
190struct Robot
191{
192 /* Configuration - set once by init_robot() / init_from_mjcf(). */
193 mjModel *model = nullptr;
194 mjData *data = nullptr;
195 KDL::Chain chain;
196 int n_joints = 0;
197 std::vector<std::string> joint_names;
198 std::vector<std::pair<double, double>> joint_limits;
199
200 /* Ports - read/written each control cycle. */
202 bool paused = false;
203 std::vector<double> jnt_pos_msr; // [rad] - measured joint positions (written by update())
204 std::vector<double> jnt_vel_msr; // [rad/s] - measured joint velocities (written by update())
205 std::vector<double> jnt_trq_msr; // [Nm] - bias torques (grav+Cor) (written by update())
206 std::vector<double> jnt_pos_cmd; // [rad] - position setpoints (POSITION mode)
207 std::vector<double> jnt_trq_cmd; // [Nm] - torque commands (TORQUE mode)
208
209 /* Internal state - populated by init_robot() / init_from_mjcf(). */
210 std::vector<int> kdl_to_mj_qpos; // KDL index -> MuJoCo qpos address
211 std::vector<int> kdl_to_mj_dof; // KDL index -> MuJoCo dof address
212 std::vector<int> kdl_to_mj_ctrl; // KDL index -> MuJoCo ctrl index (-1 if none)
213};
214
215/**
216 * @ingroup grp_viewer
217 * GLFW window and MuJoCo visualization state for the manual render loop.
218 * Created by init_window(); freed by cleanup(Viewer *).
219 */
220struct Viewer
221{
222 GLFWwindow *window = nullptr;
223 mjvScene scn{};
224 mjvCamera cam{};
225 mjvOption opt{};
226 mjvPerturb pert{};
227 mjrContext con{};
228 /* internal: real-time pacing state used by tick(). */
229 std::chrono::steady_clock::time_point _tick_t{};
230 /* internal: non-null when init_window_sim() is used; holds SimUiState*. */
231 void *_sim_ui = nullptr;
232};
233
234/**
235 * @ingroup grp_recorder
236 * Standard output resolution presets for init_video_recorder().
237 * Each maps to a 16:9 frame size at the named quality level.
238 */
239enum class VideoResolution {
240 R360p = 360, // 640 x 360
241 R480p = 480, // 854 x 480
242 R720p = 720, // 1280 x 720
243 R1080p = 1080, // 1920 x 1080
244 R2K = 1440, // 2560 x 1440
245 R4K = 2160, // 3840 x 2160
246};
247
248/**
249 * @ingroup grp_recorder
250 * Headless video recorder. Renders frames to an EGL offscreen buffer and
251 * pipes raw RGB data to an ffmpeg process, producing an H.264 MP4 without a
252 * display server or GLFW window.
253 *
254 * Requirements: EGL (libegl-dev) and ffmpeg available in PATH.
255 *
256 * Typical usage:
257 *
258 * VideoRecorder vr;
259 * init_video_recorder(&vr, model, "sim.mp4", VideoResolution::R1080p);
260 * vr.cam.azimuth = 135; vr.cam.elevation = -20; vr.cam.distance = 2.5;
261 *
262 * for (int i = 0; i < steps; ++i) {
263 * mj_step(model, data);
264 * record_frame(&vr, model, data);
265 * }
266 *
267 * cleanup(&vr);
268 */
270{
271 mjvCamera cam{}; // camera configuration; modify freely between frames
272 mjvOption opt{}; // rendering options; modify freely between frames
273 void *_impl = nullptr; // opaque EGL + ffmpeg state
274};
275
276/**
277 * @ingroup grp_scene
278 * Save the compiled model to an MJCF XML file for later reloading via build_scene().
279 * Must be called with the model returned by the most recent build_scene() call -
280 * MuJoCo only retains the last compiled model's XML internally.
281 * Typical use: build a combined scene (dual-arm, arm+gripper, ...) once, save it,
282 * then reload via build_scene() in subsequent runs to skip all build steps.
283 * @param model Model to save; must be the most recently compiled model.
284 * @param path Output path for the MJCF XML file.
285 * @return true on success.
286 */
287bool save_model_xml(const mjModel *model, const char *path);
288
289/**
290 * @ingroup grp_robot
291 * Build KDL chain from a compiled MuJoCo model (no URDF required).
292 * Traverses the body tree from base_body to tip_body.
293 *
294 * When tool_body is provided, all bodies in the subtree rooted at tool_body are
295 * collected and their mass/inertia is lumped into a single fixed KDL segment
296 * appended to the chain. This makes KDL dynamics (ChainDynParam::JntToGravity,
297 * JntToMass, etc.) account for the tool's full inertia without adding any
298 * controllable joints. n_joints remains equal to the number of hinge/slide
299 * joints between base_body and tip_body.
300 *
301 * @param[out] r Robot populated with chain, joint_names, joint_limits, index maps.
302 * @param[in] model Compiled MuJoCo model.
303 * @param[in] data MuJoCo data pointer (mj_forward is called internally if tool_body is set).
304 * @param[in] base_body Name of the chain root body (not included as a segment).
305 * @param[in] tip_body Name of the chain end body (last controllable link).
306 * @param[in] prefix Optional body/joint name prefix for multi-robot disambiguation.
307 * @param[in] tool_body Optional root of the tool subtree whose inertia is appended as a
308 * fixed segment. Pass the gripper base body (e.g. "g_base") so that
309 * KDL dynamics include the full gripper mass.
310 * @return true on success.
311 */
313 Robot *r,
314 mjModel *model,
315 mjData *data,
316 const char *base_body,
317 const char *tip_body,
318 const char *prefix = "",
319 const char *tool_body = nullptr
320);
321
322/**
323 * @ingroup grp_scene
324 * Apply one attachment to an arm spec using the MuJoCo spec API (mjs_attach).
325 * Parses a->mjcf_path, attaches its first root body under a->attach_to with the given
326 * pos/euler offset, prefixes all element names with a->prefix, and registers contact
327 * exclusions via mjs_addExclude. Can be called repeatedly to build a chain: each
328 * subsequent a->attach_to may reference any body added by prior calls.
329 * @param[in,out] robot_spec Accumulated robot spec to attach into.
330 * @param[in] a Attachment; a->mjcf_path must not be null.
331 * @return true on success.
332 */
333bool attach_to_spec(mjSpec *robot_spec, const AttachmentSpec *a);
334
335/**
336 * @ingroup grp_scene
337 * Build a MuJoCo scene from one or more robots using the MuJoCo spec API.
338 * This is the primary scene-building function.
339 *
340 * For each RobotSpec: mj_parseXML loads the root MJCF, then attach_to_spec() applies
341 * each entry in RobotSpec::attachments in order (mount, sensor, gripper, etc.),
342 * and mjs_attach places the complete robot spec at the given position. A single
343 * mj_compile produces the final model -- no intermediate XML files are written.
344 *
345 * @param[out] out_model Newly allocated MuJoCo model; caller frees via destroy_scene().
346 * @param[out] out_data Newly allocated MuJoCo data; caller frees via destroy_scene().
347 * @param[in] spec Scene description: robots (with attachment chains), table,
348 * objects, timestep, gravity, floor, skybox.
349 * @return true on success.
350 */
351bool build_scene(mjModel **out_model, mjData **out_data, const SceneSpec *spec);
352
353/**
354 * @ingroup grp_scene
355 * Free a model/data pair allocated by any scene-building function.
356 * @param[in] model Model to free (may be null).
357 * @param[in] data Data to free (may be null).
358 */
359void destroy_scene(mjModel *model, mjData *data);
360
361
362/**
363 * @ingroup grp_viewer
364 * Open a GLFW window and initialise MuJoCo visualization contexts.
365 * Must be called after init_robot() or init_from_mjcf().
366 * @param[out] v Viewer to initialise; must be zero-initialised before call.
367 * @param[in] r Robot whose model drives the rendering context.
368 * @param[in] title Window title string.
369 * @param[in] width Window width in pixels.
370 * @param[in] height Window height in pixels.
371 * @return true on success, false if GLFW or MuJoCo context creation fails.
372 */
374 Viewer *v,
375 Robot *r,
376 const char *title = "MuJoCo",
377 int width = 1280,
378 int height = 720
379);
380
381/**
382 * @ingroup grp_viewer
383 * Open the full MuJoCo simulate UI (panels, physics controls, joint viewer)
384 * in a background render thread, then return so the caller can drive the
385 * physics loop with tick().
386 *
387 * Use this instead of init_window() when you want the simulate UI panels
388 * alongside a user-owned loop. tick() automatically acquires the render
389 * mutex, steps physics, and handles pause / perturbation / speed controls.
390 *
391 * Note: the render thread owns the GLFW window; on Linux (X11 / Wayland)
392 * this works correctly. Not supported on macOS.
393 *
394 * @param[out] v Viewer to initialise; freed by cleanup(Viewer *).
395 * @param[in] r Robot to simulate.
396 * @param[in] title Label shown in the window title bar (default "MuJoCo").
397 * @return true on success.
398 */
399bool init_window_sim(Viewer *v, Robot *r, const char *title = "MuJoCo");
400
401/**
402 * @ingroup grp_robot
403 * Zero all Robot fields. Does not free model or data; call destroy_scene() for that.
404 * @param[in,out] r Robot to tear down.
405 */
406void cleanup(Robot *r);
407
408/**
409 * @ingroup grp_viewer
410 * Release the GLFW window and MuJoCo visualization contexts owned by v.
411 * @param[in,out] v Viewer to tear down; all pointers set to null afterwards.
412 */
414
415/**
416 * @ingroup grp_recorder
417 * Initialise a headless EGL video recorder.
418 * Creates an EGL context, an offscreen render target, and launches an ffmpeg
419 * process (H.264/MP4) via a pipe. The MuJoCo model is used to size the scene
420 * and initialise the rendering context; it must remain valid until cleanup().
421 *
422 * @param vr VideoRecorder to initialise; freed by cleanup(VideoRecorder*).
423 * @param model MuJoCo model for the rendering context.
424 * @param out_path Output MP4 path (e.g. "sim.mp4").
425 * @param width Frame width in pixels (default 1280).
426 * @param height Frame height in pixels (default 720).
427 * @param fps Playback frame rate (default 60).
428 * @return true on success; false if EGL init or ffmpeg launch fails.
429 */
431 VideoRecorder *vr,
432 mjModel *model,
433 const char *out_path,
434 int width = 1280,
435 int height = 720,
436 int fps = 60
437);
438
439/**
440 * @ingroup grp_recorder
441 * Convenience overload: initialise a VideoRecorder using a named resolution preset.
442 * Frame width is derived from the preset at 16:9 aspect ratio.
443 *
444 * @param vr VideoRecorder to initialise.
445 * @param model MuJoCo model.
446 * @param out_path Output MP4 path.
447 * @param resolution VideoResolution preset (e.g. VideoResolution::R1080p).
448 * @param fps Playback frame rate (default 60).
449 * @return true on success.
450 */
452 VideoRecorder *vr,
453 mjModel *model,
454 const char *out_path,
455 VideoResolution resolution,
456 int fps = 60
457);
458
459/**
460 * @ingroup grp_recorder
461 * Render the current simulation state and write one frame to the video stream.
462 * Call mj_step() (or equivalent) before each record_frame() call.
463 *
464 * @param vr VideoRecorder initialised by init_video_recorder().
465 * @param model MuJoCo model.
466 * @param data MuJoCo data (current state).
467 * @return true on success; false on render or pipe write error.
468 */
469bool record_frame(VideoRecorder *vr, mjModel *model, mjData *data);
470
471/**
472 * @ingroup grp_recorder
473 * Flush the ffmpeg pipe, finalise the MP4, and release all EGL resources.
474 * After this call vr->_impl is null and the VideoRecorder may be discarded.
475 *
476 * @param vr VideoRecorder to tear down.
477 */
479
480/**
481 * @ingroup grp_robot
482 * Advance the simulation by one timestep and call mj_forward().
483 * @param[in,out] s Simulation state.
484 */
485void step(Robot *s);
486
487/**
488 * @ingroup grp_robot
489 * Advance the simulation by n timesteps.
490 * @param[in,out] s Simulation state.
491 * @param[in] n Number of steps.
492 */
493void step_n(Robot *s, int n);
494
495/**
496 * @ingroup grp_robot
497 * Reset simulation to the model's keyframe 0 (or default pose).
498 * @param[in,out] s Simulation state.
499 */
500void reset(Robot *s);
501
502/**
503 * @ingroup grp_viewer
504 * Returns true if the viewer window is open and not scheduled for closing.
505 * @param[in] v Viewer created by init_window().
506 */
507bool is_running(const Viewer *v);
508
509/**
510 * @ingroup grp_viewer
511 * Render the current simulation frame to the viewer window.
512 * @param[in,out] v Viewer created by init_window().
513 * @param[in] r Robot whose model and data are rendered.
514 * @return true if the window is still open after rendering.
515 */
516bool render(Viewer *v, const Robot *r);
517
518/**
519 * @ingroup grp_viewer
520 * Render the current simulation frame to the viewer window.
521 * Model/data overload -- use when no single Robot owns the scene (e.g. multi-robot).
522 * @param[in,out] v Viewer created by init_window().
523 * @param[in] m MuJoCo model.
524 * @param[in] d MuJoCo data.
525 * @return true if the window is still open after rendering.
526 */
527bool render(Viewer *v, mjModel *m, mjData *d);
528
529/**
530 * @ingroup grp_viewer
531 * Advance one physics step, render, sync to real time, and poll GLFW events.
532 * Intended for user-owned control loops; call once per control cycle.
533 *
534 * Sequence inside tick():
535 * 1. glfwPollEvents() -- fires keyboard / mouse callbacks
536 * 2. real-time sleep -- paces the loop to model->opt.timestep wall time
537 * 3. if (!r->paused):
538 * apply mouse perturbation forces (if active)
539 * mj_step()
540 * 4. render()
541 *
542 * update() is NOT called here -- call it yourself to read *_msr and apply *_cmd.
543 * Typical loop:
544 *
545 * update(&robot); // seed initial sensor readings
546 * while (tick(&viewer, &robot)) {
547 * my_control_step(&robot); // reads *_msr, writes *_cmd
548 * update(&robot); // applies *_cmd, refreshes *_msr for next step
549 * }
550 *
551 * @return true while the window is open; false once the user closes it.
552 */
553bool tick(Viewer *v, Robot *r);
554
555/**
556 * @ingroup grp_viewer
557 * Model/data overload of tick() for multi-robot or model-owned loops where no
558 * single Robot is the canonical owner of the scene. Physics always runs
559 * (paused state is not tracked; use the sim UI pause button when using
560 * init_window_sim, or manage it externally for init_window).
561 *
562 * @param[in,out] v Viewer initialised by init_window() or init_window_sim().
563 * @param[in] m Shared MuJoCo model.
564 * @param[in] d Shared MuJoCo data.
565 * @return true while the window is open; false once the user closes it.
566 */
567bool tick(Viewer *v, mjModel *m, mjData *d);
568
569/**
570 * @ingroup grp_robot
571 * One control cycle: read MuJoCo into *_msr, then apply *_cmd to MuJoCo.
572 * Read step: qpos -> jnt_pos_msr, qvel -> jnt_vel_msr, qfrc_bias -> jnt_trq_msr.
573 * Apply step: POSITION -> data->ctrl,
574 * TORQUE -> qfrc_applied; also sets ctrl = qpos to neutralize
575 * position actuators (zeroes kp*(ctrl-qpos) restoring force).
576 * Joints with kdl_to_mj_ctrl[i] == -1 are skipped for ctrl writes.
577 */
578void update(Robot *r);
579
580/**
581 * @ingroup grp_robot
582 * Write KDL joint positions into MuJoCo qpos (KDL chain order -> MuJoCo addresses).
583 * @param[in,out] r Robot with a valid data pointer.
584 * @param[in] q Joint positions in KDL chain order; size must equal r->n_joints.
585 * @param[in] call_forward If true (default), calls mj_forward() after writing qpos
586 * so that body poses and sensor data are updated immediately.
587 */
588void set_joint_pos(Robot *r, const KDL::JntArray &q, bool call_forward = true);
589
590/**
591 * @ingroup grp_scene
592 * Add an object to the scene by appending it to spec->objects and rebuilding
593 * the model. The old model/data are freed; new ones replace them.
594 * Any Robot handles sharing the old model/data become stale - call init_robot()
595 * again on the new model/data after this call.
596 * @param[in,out] model Current model pointer; updated to new model on success.
597 * @param[in,out] data Current data pointer; updated to new data on success.
598 * @param[in,out] spec Scene spec; obj is appended to spec->objects.
599 * @param[in] obj Object to add.
600 * @return true on success; model/data and spec->objects unchanged on failure.
601 */
602bool scene_add_object(mjModel **model, mjData **data, SceneSpec *spec, const SceneObject &obj);
603
604/**
605 * @ingroup grp_scene
606 * Remove a named object from the scene by erasing it from spec->objects and
607 * rebuilding the model. The old model/data are freed; new ones replace them.
608 * Any Robot handles sharing the old model/data become stale - call init_robot()
609 * again on the new model/data after this call.
610 * @param[in,out] model Current model pointer; updated to new model on success.
611 * @param[in,out] data Current data pointer; updated to new data on success.
612 * @param[in,out] spec Scene spec; named object removed from spec->objects.
613 * @param[in] name Name of the object to remove.
614 * @return true on success; false if name not found or rebuild fails.
615 */
616bool scene_remove_object(mjModel **model, mjData **data, SceneSpec *spec, const std::string &name);
617
618/* Control callback: called each physics step while the simulation is running.
619 * Apply custom forces/torques (ctrl, qfrc_applied) here before mj_step().
620 * Mouse perturbation forces are applied automatically by run_simulate_ui(). */
621using ControlCb = std::function<void(mjModel *m, mjData *d)>;
622
623/* Run the MuJoCo simulate UI with a real-time physics loop (mirrors the
624 * PhysicsLoop pattern from mujoco/simulate/main.cc).
625 * Blocks until the window is closed.
626 *
627 * Deprecated: prefer init_window_sim() + tick() so examples and applications own
628 * the control loop and can handle reset-aware state explicitly.
629 *
630 * @param m MuJoCo model (caller owns; not freed by this function).
631 * @param d MuJoCo data (caller owns; not freed by this function).
632 * @param path Filename shown in the title bar (pass "" if not applicable).
633 * @param physics_cb Called each physics step; may be nullptr. */
634[[deprecated("prefer init_window_sim() + tick()")]] void
635 run_simulate_ui(mjModel *m, mjData *d, const char *path, ControlCb physics_cb = nullptr);
636
637/**
638 * Internal spec-building helpers.
639 *
640 * These are used internally by build_scene() and configure_spec(), but are
641 * exposed here for advanced callers that construct mjSpec objects directly.
642 * They are not part of the stable public API and may change between releases.
643 */
644
645/**
646 * @ingroup grp_advanced
647 * Add a sky gradient texture and overhead directional light to spec.
648 * Corresponds to SceneSpec::add_skybox.
649 */
650void add_skybox_to_spec(mjSpec *spec);
651
652/**
653 * @ingroup grp_advanced
654 * Add a checker groundplane texture, material, and floor plane geom to spec.
655 * Corresponds to SceneSpec::add_floor.
656 */
657void add_floor_to_spec(mjSpec *spec);
658
659/**
660 * @ingroup grp_advanced
661 * Add a table (tabletop + four legs) to the world body of spec.
662 * @param spec MuJoCo spec to modify.
663 * @param t Table geometry, size, and colour.
664 */
665void add_table_to_spec(mjSpec *spec, const TableSpec &t);
666
667/**
668 * @ingroup grp_advanced
669 * Add free-floating or fixed rigid bodies to the world body of spec.
670 * @param spec MuJoCo spec to modify.
671 * @param objects List of objects to add.
672 */
673void add_objects_to_spec(mjSpec *spec, const std::vector<SceneObject> &objects);
674
675/**
676 * @ingroup grp_advanced
677 * Apply all SceneSpec settings to a parsed mjSpec:
678 * physics options (timestep, gravity), compiler flags, and scene decorations
679 * (skybox, floor, table, objects) according to the flags in sc.
680 */
681void configure_spec(mjSpec *spec, const SceneSpec *sc);
682
683/**
684 * @ingroup grp_advanced
685 * Compile spec into a model and create its data buffer.
686 * spec is always deleted (on success and failure).
687 * @param[in] spec MuJoCo spec to compile; always freed by this call.
688 * @param[out] out_model Newly allocated model on success; null on failure.
689 * @param[out] out_data Newly allocated data on success; null on failure.
690 * @return true on success.
691 */
692bool compile_and_make_data(mjSpec *spec, mjModel **out_model, mjData **out_data);
693
694/**
695 * @ingroup grp_advanced
696 * Load MuJoCo decoder plugins (STL, OBJ, ...) once at first use.
697 * Required since MuJoCo 3.6.0 moved mesh decoders to plugin libraries.
698 * Called automatically by all scene-building functions; call explicitly only
699 * when building a scene via raw mjSpec APIs without going through the library.
700 */
702
703} // namespace mj_kdl
void add_skybox_to_spec(mjSpec *spec)
void add_table_to_spec(mjSpec *spec, const TableSpec &t)
bool compile_and_make_data(mjSpec *spec, mjModel **out_model, mjData **out_data)
void add_objects_to_spec(mjSpec *spec, const std::vector< SceneObject > &objects)
void add_floor_to_spec(mjSpec *spec)
void ensure_plugins_loaded()
void configure_spec(mjSpec *spec, const SceneSpec *sc)
void set_log_level(LogLevel level)
LogLevel get_log_level()
LogLevel g_log_level
bool init_video_recorder(VideoRecorder *vr, mjModel *model, const char *out_path, int width=1280, int height=720, int fps=60)
bool record_frame(VideoRecorder *vr, mjModel *model, mjData *data)
void step(Robot *s)
void reset(Robot *s)
bool init_robot_from_mjcf(Robot *r, mjModel *model, mjData *data, const char *base_body, const char *tip_body, const char *prefix="", const char *tool_body=nullptr)
void cleanup(Robot *r)
void step_n(Robot *s, int n)
void set_joint_pos(Robot *r, const KDL::JntArray &q, bool call_forward=true)
void update(Robot *r)
bool build_scene(mjModel **out_model, mjData **out_data, const SceneSpec *spec)
bool attach_to_spec(mjSpec *robot_spec, const AttachmentSpec *a)
bool scene_add_object(mjModel **model, mjData **data, SceneSpec *spec, const SceneObject &obj)
bool scene_remove_object(mjModel **model, mjData **data, SceneSpec *spec, const std::string &name)
void destroy_scene(mjModel *model, mjData *data)
bool save_model_xml(const mjModel *model, const char *path)
bool init_window_sim(Viewer *v, Robot *r, const char *title="MuJoCo")
bool tick(Viewer *v, Robot *r)
bool init_window(Viewer *v, Robot *r, const char *title="MuJoCo", int width=1280, int height=720)
bool render(Viewer *v, const Robot *r)
bool is_running(const Viewer *v)
void run_simulate_ui(mjModel *m, mjData *d, const char *path, ControlCb physics_cb=nullptr)
std::function< void(mjModel *m, mjData *d)> ControlCb
std::vector< std::pair< std::string, std::string > > contact_exclusions
std::vector< AttachmentSpec > attachments
std::vector< int > kdl_to_mj_ctrl
std::vector< int > kdl_to_mj_qpos
std::vector< int > kdl_to_mj_dof
std::vector< double > jnt_pos_msr
std::vector< double > jnt_pos_cmd
std::vector< std::pair< double, double > > joint_limits
std::vector< double > jnt_vel_msr
std::vector< double > jnt_trq_cmd
std::vector< double > jnt_trq_msr
std::vector< std::string > joint_names
std::vector< RobotSpec > robots
std::vector< SceneObject > objects
GLFWwindow * window
std::chrono::steady_clock::time_point _tick_t