Skip to content

Commit 4f40512

Browse files
committed
Add real-time mp4 recording for offline OCP runs
Adds `--video PATH` to `offline_task.py`, with playback fps defaulted to `1/config.dt` so trajectories play at wall-clock speed. The three LIPA configs switch to sequential LQR so offline runs converge bit-deterministically.
1 parent 6ef875b commit 4f40512

8 files changed

Lines changed: 99 additions & 15 deletions

File tree

mpx/config/config_aliengo_trot_two_step.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -78,8 +78,8 @@ def _lipa_settings():
7878
µ_update_factor=0.9,
7979
cost_improvement_threshold=1e-3,
8080
primal_violation_threshold=1e-5,
81-
use_parallel_lqr=True,
82-
num_parallel_line_search_steps=8,
81+
use_parallel_lqr=False,
82+
num_parallel_line_search_steps=1,
8383
)
8484

8585
lipa_settings = _lipa_settings()

mpx/config/config_barrel_roll.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -122,8 +122,8 @@ def _lipa_settings():
122122
µ_update_factor=0.9,
123123
cost_improvement_threshold=1e-3,
124124
primal_violation_threshold=1e-5,
125-
use_parallel_lqr=True,
126-
num_parallel_line_search_steps=8,
125+
use_parallel_lqr=False,
126+
num_parallel_line_search_steps=1,
127127
)
128128

129129
lipa_settings = _lipa_settings()

mpx/config/config_h1_jump_forward.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -73,8 +73,8 @@ def _lipa_settings():
7373
cost_improvement_threshold=1e-3,
7474
primal_violation_threshold=1e-5,
7575
num_iterative_refinement_steps=2,
76-
use_parallel_lqr=True,
77-
num_parallel_line_search_steps=8,
76+
use_parallel_lqr=False,
77+
num_parallel_line_search_steps=1,
7878
)
7979

8080
lipa_settings = _lipa_settings()
@@ -89,8 +89,8 @@ def _lipa_settings_enforce():
8989
cost_improvement_threshold=1e-3,
9090
primal_violation_threshold=1e-5,
9191
num_iterative_refinement_steps=2,
92-
use_parallel_lqr=True,
93-
num_parallel_line_search_steps=8,
92+
use_parallel_lqr=False,
93+
num_parallel_line_search_steps=1,
9494
)
9595

9696
lipa_settings_enforce = _lipa_settings_enforce()

mpx/data/acrobot/scene.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<option timestep="0.01" gravity="0 0 -9.81"/>
44

55
<visual>
6-
<global azimuth="135" elevation="-20"/>
6+
<global azimuth="135" elevation="-20" offwidth="1920" offheight="1080"/>
77
<headlight ambient="0.35 0.35 0.35" diffuse="0.75 0.75 0.75" specular="0.2 0.2 0.2"/>
88
<rgba haze="1 1 1 1"/>
99
</visual>

mpx/data/aliengo/scene_flat.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
<visual>
2323
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
2424
<rgba haze="0.15 0.25 0.35 1"/>
25-
<global azimuth="-130" elevation="-20"/>
25+
<global azimuth="-130" elevation="-20" offwidth="1920" offheight="1080"/>
2626
</visual>
2727

2828
<asset>

mpx/data/unitree_h1/mjx_scene_h1_walk.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
<visual>
77
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
88
<rgba haze="0.15 0.25 0.35 1"/>
9-
<global azimuth="160" elevation="-20"/>
9+
<global azimuth="160" elevation="-20" offwidth="1920" offheight="1080"/>
1010
</visual>
1111

1212
<asset>

mpx/examples/offline_task.py

Lines changed: 67 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,12 @@
99
sys.path.append(os.path.abspath(os.path.join(dir_path, "..")))
1010
os.environ.setdefault("XLA_FLAGS", "--xla_gpu_enable_command_buffer=")
1111

12+
# Headless video recording uses `mujoco.Renderer`, which requires an OpenGL
13+
# backend to be configured before the first `import mujoco` in the process.
14+
if "--video" in sys.argv:
15+
os.environ.setdefault("MUJOCO_GL", "egl")
16+
os.environ.setdefault("PYOPENGL_PLATFORM", "egl")
17+
1218
import jax
1319
import jax.numpy as jnp
1420
import mujoco
@@ -217,7 +223,52 @@ def _predicted_base_positions(config, model, qpos_sequence):
217223
return base_positions
218224

219225

220-
def _play_mujoco_trajectory(result, headless=False, loop=True, ghost_stride=1):
226+
def _record_offline_trajectory_video(result, video_path, fps=None, loop_count=1, width=1280, height=720):
227+
"""Render the optimised offline trajectory `X` to an mp4 via offscreen GL.
228+
229+
No viewer involved. Uses `MUJOCO_GL=egl` (auto-set when the example sees
230+
`--video` in argv) and the shared `sim_utils.VideoRecorder`. One frame per
231+
state in `X`, optionally repeated `loop_count` times so short trajectories
232+
aren't blink-and-miss-it. Playback is real-time by default (fps = 1/config.dt).
233+
"""
234+
config = result["config"]
235+
scene_path = result["scene_path"]
236+
X = np.asarray(result["X"])
237+
model = mujoco.MjModel.from_xml_path(scene_path)
238+
data = mujoco.MjData(model)
239+
os.makedirs(os.path.dirname(os.path.abspath(video_path)) or ".", exist_ok=True)
240+
241+
config_fps = 1.0 / float(config.dt)
242+
if fps is None:
243+
fps = int(round(config_fps))
244+
subsample = 1
245+
else:
246+
subsample = max(1, int(round(config_fps / fps)))
247+
fps = int(round(config_fps / subsample))
248+
249+
recorder = sim_utils.VideoRecorder(model, video_path, fps=fps, width=width, height=height)
250+
try:
251+
for _ in range(loop_count):
252+
for i, state in enumerate(X):
253+
if i % subsample != 0:
254+
continue
255+
qpos, qvel = _state_to_mujoco(config, state)
256+
data.qpos = np.asarray(qpos)
257+
data.qvel = np.asarray(qvel)
258+
mujoco.mj_forward(model, data)
259+
recorder.capture(data)
260+
finally:
261+
recorder.close()
262+
print(f"Wrote video: {video_path} at {fps} fps (subsample {subsample}), {width}x{height}")
263+
264+
265+
def _play_mujoco_trajectory(result, headless=False, loop=True, ghost_stride=1, video=None, fps=None, width=None, height=None):
266+
if video is not None:
267+
# Recording mode: render trajectory frames to mp4 instead of opening
268+
# the viewer. Implies headless.
269+
_record_offline_trajectory_video(result, video, fps=fps, width=width or 1280, height=height or 720)
270+
return
271+
221272
config = result["config"]
222273
scene_path = result["scene_path"]
223274
X = np.asarray(result["X"])
@@ -292,6 +343,10 @@ def run_task(
292343
verbose=True,
293344
loop=True,
294345
lipa_enforce_inequalities=None,
346+
video=None,
347+
fps=None,
348+
width=None,
349+
height=None,
295350
):
296351
result = solve_task(
297352
task_name,
@@ -308,7 +363,7 @@ def run_task(
308363
f"iterations {stats['n_iterations']} | "
309364
f"avg iter time {stats['average_iteration_time_ms']:.3f} ms"
310365
)
311-
_play_mujoco_trajectory(result, headless=headless, loop=loop)
366+
_play_mujoco_trajectory(result, headless=headless, loop=loop, video=video, fps=fps, width=width, height=height)
312367

313368

314369
def build_parser(default_task=None):
@@ -327,6 +382,12 @@ def build_parser(default_task=None):
327382
parser.add_argument("--max-iter", type=int, default=100)
328383
parser.add_argument("--quiet", action="store_true")
329384
parser.add_argument("--no-loop", action="store_true")
385+
parser.add_argument("--video", type=str, default=None,
386+
help="Render the optimised trajectory to this mp4 path (forces headless).")
387+
parser.add_argument("--fps", type=int, default=None,
388+
help="Target FPS for video recording (e.g. 50 or 60). Subsamples the trajectory.")
389+
parser.add_argument("--width", type=int, default=1280, help="Video width (default: 1280).")
390+
parser.add_argument("--height", type=int, default=720, help="Video height (default: 720).")
330391
enforce_group = parser.add_mutually_exclusive_group()
331392
enforce_group.add_argument(
332393
"--lipa-enforce-inequalities",
@@ -358,6 +419,10 @@ def main(default_task=None):
358419
verbose=not args.quiet,
359420
loop=not args.no_loop,
360421
lipa_enforce_inequalities=args.lipa_enforce_inequalities,
422+
video=args.video,
423+
fps=args.fps,
424+
width=args.width,
425+
height=args.height,
361426
)
362427

363428

mpx/utils/sim.py

Lines changed: 21 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -418,16 +418,22 @@ def __init__(
418418
distance: float = 3.0,
419419
azimuth: float = 90.0,
420420
elevation: float = -20.0,
421+
bit_depth: int = 10,
421422
):
422423
import imageio # late import: only needed when recording
423424

424425
self._renderer = mujoco.Renderer(model, height=height, width=width)
426+
427+
# Pick pixel format based on bit depth
428+
pix_fmt = "yuv420p10le" if bit_depth == 10 else "yuv420p"
429+
425430
self._writer = imageio.get_writer(
426431
path,
427432
format="FFMPEG",
428433
codec="libx264",
429434
fps=fps,
430435
macro_block_size=1,
436+
output_params=["-pix_fmt", pix_fmt],
431437
)
432438
self._cam = mujoco.MjvCamera()
433439
self._cam.distance = float(distance)
@@ -436,10 +442,23 @@ def __init__(
436442
self._cam.lookat[:] = [0.0, 0.0, 0.0]
437443

438444
def capture(self, data: mujoco.MjData, lookat: np.ndarray | None = None) -> None:
439-
"""Render and append one frame; lookat defaults to the floating-base position."""
445+
"""Render and append one frame.
446+
447+
Default `lookat` is the floating-base world position (`qpos[:3]`) when
448+
the model has at least 3 generalised coords — the typical case for
449+
legged-robot configs. For low-dimensional models (e.g. acrobot's
450+
2-DOF qpos), falls back to the world body's xpos so the camera stays
451+
pointed at something sensible instead of crashing on the reshape.
452+
"""
440453

441454
if lookat is None:
442-
lookat = np.asarray(data.qpos[:3], dtype=np.float64)
455+
qpos = np.asarray(data.qpos, dtype=np.float64)
456+
if qpos.size >= 3:
457+
lookat = qpos[:3]
458+
else:
459+
# Centre on the first non-world body's world position. Always 3D.
460+
lookat = np.asarray(data.xpos[1] if data.xpos.shape[0] > 1 else data.xpos[0],
461+
dtype=np.float64)
443462
self._cam.lookat[:] = np.asarray(lookat, dtype=np.float64).reshape(3)
444463
self._renderer.update_scene(data, self._cam)
445464
self._writer.append_data(self._renderer.render())

0 commit comments

Comments
 (0)