Skip to content

Commit 4a1f966

Browse files
authored
Merge pull request #277 from maxspahn/fix-realtime-mujoco
Fix realtime mujoco
2 parents d5c9879 + cc86ae7 commit 4a1f966

File tree

4 files changed

+31
-31
lines changed

4 files changed

+31
-31
lines changed

examples/mujoco_example.py

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -112,16 +112,14 @@ def run_generic_mujoco(
112112
t = 0.0
113113
history = []
114114
for i in range(n_steps):
115-
t0 = time.perf_counter()
116-
action = action_mag * np.cos(i/20)
115+
action = action_mag * np.cos(env.t)
117116
action[-1] = 0.02
118117
ob, _, terminated, _, info = env.step(action)
119118
#print(ob['robot_0'])
120119
history.append(ob)
121120
if terminated:
122121
print(info)
123122
break
124-
t1 = time.perf_counter()
125123

126124
env.close()
127125
return history

pyproject.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
[tool.poetry]
22
name = "urdfenvs"
3-
version = "0.10.1"
3+
version = "0.10.2"
44
description = "Simple simulation environment for robots, based on the urdf files."
55
authors = ["Max Spahn <[email protected]>"]
66
maintainers = [

urdfenvs/generic_mujoco/generic_mujoco_env.py

Lines changed: 29 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,6 @@ class GenericMujocoEnv(Env):
4141
"rgb_array",
4242
"depth_array",
4343
],
44-
"render_fps": 20,
4544
}
4645
_t: float
4746
_number_movable_obstacles: int
@@ -53,7 +52,8 @@ def __init__(
5352
goals: List[SubGoal],
5453
sensors: Optional[List[Sensor]] = None,
5554
render: Optional[Union[str, bool]] = None,
56-
frame_skip: int = 5,
55+
dt: float = 0.01,
56+
n_sub_steps: int = 1,
5757
width: int = DEFAULT_SIZE,
5858
height: int = DEFAULT_SIZE,
5959
camera_id: Optional[int] = None,
@@ -83,11 +83,13 @@ def __init__(
8383
self._enforce_real_time = True
8484
else:
8585
self._enforce_real_time = False
86+
self._sleep_offset = 0.0
8687

8788
self.width = width
8889
self.height = height
8990

90-
self.frame_skip = frame_skip
91+
self._dt = dt
92+
self._n_sub_steps = n_sub_steps
9193
self._initialize_simulation()
9294

9395
for sensor in self._sensors:
@@ -98,11 +100,6 @@ def __init__(
98100
"rgb_array",
99101
"depth_array",
100102
], self.metadata["render_modes"]
101-
if "render_fps" in self.metadata:
102-
assert (
103-
int(np.round(1.0 / self.dt)) == self.metadata["render_fps"]
104-
), f'Expected value: {int(np.round(1.0 / self.dt))}, Actual value: {self.metadata["render_fps"]}'
105-
106103
self.observation_space = self.get_observation_space()
107104
self.action_space = self.get_action_space()
108105

@@ -117,6 +114,7 @@ def __init__(
117114
height=DEFAULT_SIZE,
118115
width=DEFAULT_SIZE,
119116
)
117+
self._end_last_step_time = time.time()
120118

121119
def render(self):
122120
return self.mujoco_renderer.render(self.render_mode)
@@ -190,11 +188,12 @@ def _initialize_simulation(
190188
self.model.body_pos[0] = [0, 1, 1]
191189
self.model.vis.global_.offwidth = self.width
192190
self.model.vis.global_.offheight = self.height
191+
self.model.opt.timestep = self._dt / self._n_sub_steps
193192
self.data = mujoco.MjData(self.model)
194193

195194
@property
196195
def dt(self) -> float:
197-
return self.model.opt.timestep * self.frame_skip
196+
return self._dt
198197

199198
@property
200199
def t(self) -> float:
@@ -221,7 +220,8 @@ def update_goals_position(self):
221220
self.data.site_xpos[i] = goal.position(t=self.t)
222221

223222
def step(self, action: np.ndarray):
224-
step_start = time.perf_counter()
223+
target_end_step_time = self._end_last_step_time + self.dt
224+
225225
self._t += self.dt
226226
truncated = False
227227
info = {}
@@ -230,7 +230,7 @@ def step(self, action: np.ndarray):
230230
self._done = True
231231
info = {"action_limits": f"{action} not in {self.action_space}"}
232232

233-
self.do_simulation(action, self.frame_skip)
233+
self.do_simulation(action)
234234
for contact in self.data.contact:
235235
body1 = self.model.geom(contact.geom1).name
236236
body2 = self.model.geom(contact.geom2).name
@@ -256,15 +256,20 @@ def step(self, action: np.ndarray):
256256
except WrongObservationError as e:
257257
self._done = True
258258
info = {"observation_limits": str(e)}
259-
step_end = time.perf_counter()
260-
step_time = step_end - step_start
261-
if self._enforce_real_time:
262-
sleep_time = max(0.0, self.dt - step_time)
259+
time_before_sleep = time.time()
260+
sleep_time = target_end_step_time - time_before_sleep - self._sleep_offset
261+
if self._enforce_real_time and sleep_time > 0:
263262
time.sleep(sleep_time)
264-
step_final_end = time.perf_counter()
265-
total_step_time = step_final_end - step_start
266-
real_time_factor = self.dt / total_step_time
267-
logging.info(f"Real time factor {real_time_factor}")
263+
time_after_sleep = time.time()
264+
# Compute the real-time factor (RTF)
265+
real_time_step = time_after_sleep - self._end_last_step_time
266+
rtf = self.dt / (real_time_step)
267+
if real_time_step < self.dt:
268+
self._sleep_offset -= 0.0001
269+
else:
270+
self._sleep_offset += 0.0001
271+
logging.info(f"Real time factor {rtf:.4f}")
272+
self._end_last_step_time = time.time()
268273
return (
269274
ob,
270275
reward,
@@ -297,6 +302,7 @@ def reset(
297302
qvel = np.zeros(self.nv)
298303
self.set_state(qpos, qvel)
299304
self._t = 0.0
305+
self._end_last_step_time = time.time()
300306
return self._get_obs(), {}
301307

302308
def set_state(self, qpos, qvel):
@@ -319,21 +325,18 @@ def nq(self) -> int:
319325
def nv(self) -> int:
320326
return self.model.nv - 6 * self._number_movable_obstacles
321327

322-
def do_simulation(self, ctrl, n_frames) -> None:
323-
"""
324-
Step the simulation n number of frames and applying a control action.
325-
"""
328+
def do_simulation(self, ctrl) -> None:
326329
# Check control input is contained in the action space
327330
if np.array(ctrl).shape != (self.model.nu,):
328331
raise ValueError(
329332
f"Action dimension mismatch. Expected {(self.model.nu,)}, found {np.array(ctrl).shape}"
330333
)
331-
self._step_mujoco_simulation(ctrl, n_frames)
334+
self._step_mujoco_simulation(ctrl)
332335

333-
def _step_mujoco_simulation(self, ctrl, n_frames):
336+
def _step_mujoco_simulation(self, ctrl):
334337
self.data.ctrl[:] = ctrl
335338

336-
mujoco.mj_step(self.model, self.data, nstep=n_frames)
339+
mujoco.mj_step(self.model, self.data, nstep=self._n_sub_steps)
337340

338341
# As of MuJoCo 2.0, force-related quantities like cacc are not computed
339342
# unless there's a force sensor in the model.

urdfenvs/sensors/mujoco_interface.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,6 @@ def get_obstacle_pose(
3434
if movable:
3535

3636
free_joint_data = self._data.jnt(f"freejoint_{obst_name}").qpos
37-
print(free_joint_data)
3837
return free_joint_data[0:3].tolist(), free_joint_data[3:].tolist()
3938
pos = self._data.body(obst_name).xpos
4039
ori = self._data.body(obst_name).xquat

0 commit comments

Comments
 (0)