Skip to content

Commit

Permalink
minor tweaks to simulator
Browse files Browse the repository at this point in the history
  • Loading branch information
budzianowski committed May 16, 2024
1 parent 98e55ca commit bc97be0
Showing 1 changed file with 23 additions and 18 deletions.
41 changes: 23 additions & 18 deletions sim/scripts/simulate_mjcf.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
"""Defines a simple demo script for simulating a MJCF to observe the physics.
Run with mjpython:
mjpython mjpython sim/scripts/simulate_mjcf.py
mjpython sim/scripts/simulate_mjcf.py --record
"""

import time
Expand All @@ -11,37 +11,42 @@
import mediapy as media
import argparse

from sim.env import stompy_mjcf_path


def simulate(model_path, duration, framerate, record_video):
frames = []
model = mujoco.MjModel.from_xml_path(model_path)
data = mujoco.MjData(model)
renderer = mujoco.Renderer(model)

while data.time < duration:
step_start = time.time()
mujoco.mj_step(model, data)

time_until_next_step = model.opt.timestep - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step)
with mujoco.viewer.launch_passive(model, data) as viewer:
while data.time < duration:
step_start = time.time()
mujoco.mj_step(model, data)
viewer.sync()
time_until_next_step = model.opt.timestep - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step)

if record_video and len(frames) < data.time * framerate:
renderer.update_scene(data)
pixels = renderer.render()
frames.append(pixels)
if record_video and len(frames) < data.time * framerate:
renderer.update_scene(data)
pixels = renderer.render()
frames.append(pixels)

if record_video:
video_path = "mjcf_simulation.mp4"
media.write_video(video_path, frames, fps=framerate)
print(f"Video saved to {video_path}")
if record_video:
video_path = "mjcf_simulation.mp4"
media.write_video(video_path, frames, fps=framerate)
print(f"Video saved to {video_path}")


if __name__ == "__main__":
parser = argparse.ArgumentParser(description="MuJoCo Simulation")
parser.add_argument("--model_path", type=str, required=True, help="Path to the MuJoCo XML model file")
parser.add_argument(
"--model_path", type=str, default=str(stompy_mjcf_path()), help="Path to the MuJoCo XML model file"
)
parser.add_argument("--duration", type=int, default=3, help="Duration of the simulation in seconds")
parser.add_argument("--framerate", type=int, default=60, help="Frame rate for video recording")
parser.add_argument("--framerate", type=int, default=30, help="Frame rate for video recording")
parser.add_argument("--record", action="store_true", help="Flag to record video")

args = parser.parse_args()
Expand Down

0 comments on commit bc97be0

Please sign in to comment.