99sys .path .append (os .path .abspath (os .path .join (dir_path , ".." )))
1010os .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+
1218import jax
1319import jax .numpy as jnp
1420import 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
314369def 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
0 commit comments