|
mj-kdl-wrapper
0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
|
Headless H.264 video recording via EGL offscreen rendering and ffmpeg. More...
Classes | |
| struct | mj_kdl::VideoRecorder |
Enumerations | |
| enum class | mj_kdl::VideoResolution { mj_kdl::VideoResolution::R360p = 360 , mj_kdl::VideoResolution::R480p = 480 , mj_kdl::VideoResolution::R720p = 720 , mj_kdl::VideoResolution::R1080p = 1080 , mj_kdl::VideoResolution::R2K = 1440 , mj_kdl::VideoResolution::R4K = 2160 } |
Functions | |
| bool | mj_kdl::init_video_recorder (VideoRecorder *vr, mjModel *model, const char *out_path, int width=1280, int height=720, int fps=60) |
| bool | mj_kdl::init_video_recorder (VideoRecorder *vr, mjModel *model, const char *out_path, VideoResolution resolution, int fps=60) |
| bool | mj_kdl::record_frame (VideoRecorder *vr, mjModel *model, mjData *data) |
| void | mj_kdl::cleanup (VideoRecorder *vr) |
Headless H.264 video recording via EGL offscreen rendering and ffmpeg.
No display or GLFW window is needed. Requires EGL (libegl-dev) and ffmpeg in PATH. Enable with -DBUILD_RECORDER=ON (default).
|
strong |
Standard output resolution presets for init_video_recorder(). Each maps to a 16:9 frame size at the named quality level.
| Enumerator | |
|---|---|
| R360p | |
| R480p | |
| R720p | |
| R1080p | |
| R2K | |
| R4K | |
Definition at line 239 of file mj_kdl_wrapper.hpp.
| void mj_kdl::cleanup | ( | VideoRecorder * | vr | ) |
Flush the ffmpeg pipe, finalise the MP4, and release all EGL resources. After this call vr->_impl is null and the VideoRecorder may be discarded.
| vr | VideoRecorder to tear down. |
| bool mj_kdl::init_video_recorder | ( | VideoRecorder * | vr, |
| mjModel * | model, | ||
| const char * | out_path, | ||
| int | width = 1280, |
||
| int | height = 720, |
||
| int | fps = 60 |
||
| ) |
Initialise a headless EGL video recorder. Creates an EGL context, an offscreen render target, and launches an ffmpeg process (H.264/MP4) via a pipe. The MuJoCo model is used to size the scene and initialise the rendering context; it must remain valid until cleanup().
| vr | VideoRecorder to initialise; freed by cleanup(VideoRecorder*). |
| model | MuJoCo model for the rendering context. |
| out_path | Output MP4 path (e.g. "sim.mp4"). |
| width | Frame width in pixels (default 1280). |
| height | Frame height in pixels (default 720). |
| fps | Playback frame rate (default 60). |
Referenced by main().
| bool mj_kdl::init_video_recorder | ( | VideoRecorder * | vr, |
| mjModel * | model, | ||
| const char * | out_path, | ||
| VideoResolution | resolution, | ||
| int | fps = 60 |
||
| ) |
Convenience overload: initialise a VideoRecorder using a named resolution preset. Frame width is derived from the preset at 16:9 aspect ratio.
| vr | VideoRecorder to initialise. |
| model | MuJoCo model. |
| out_path | Output MP4 path. |
| resolution | VideoResolution preset (e.g. VideoResolution::R1080p). |
| fps | Playback frame rate (default 60). |
| bool mj_kdl::record_frame | ( | VideoRecorder * | vr, |
| mjModel * | model, | ||
| mjData * | data | ||
| ) |
Render the current simulation state and write one frame to the video stream. Call mj_step() (or equivalent) before each record_frame() call.
| vr | VideoRecorder initialised by init_video_recorder(). |
| model | MuJoCo model. |
| data | MuJoCo data (current state). |
Referenced by main().