-
Notifications
You must be signed in to change notification settings - Fork 8.7k
Support MuJoCo 1.5 #767
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Support MuJoCo 1.5 #767
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -11,22 +11,22 @@ def __init__(self): | |
def _step(self, action): | ||
self.do_simulation(action, self.frame_skip) | ||
ob = self._get_obs() | ||
x, _, y = self.model.data.site_xpos[0] | ||
x, _, y = self.sim.data.site_xpos[0] | ||
dist_penalty = 0.01 * x ** 2 + (y - 2) ** 2 | ||
v1, v2 = self.model.data.qvel[1:3] | ||
v1, v2 = self.sim.data.qvel[1:3] | ||
vel_penalty = 1e-3 * v1**2 + 5e-3 * v2**2 | ||
alive_bonus = 10 | ||
r = (alive_bonus - dist_penalty - vel_penalty)[0] | ||
r = alive_bonus - dist_penalty - vel_penalty | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Not sure why |
||
done = bool(y <= 1) | ||
return ob, r, done, {} | ||
|
||
def _get_obs(self): | ||
return np.concatenate([ | ||
self.model.data.qpos[:1], # cart x pos | ||
np.sin(self.model.data.qpos[1:]), # link angles | ||
np.cos(self.model.data.qpos[1:]), | ||
np.clip(self.model.data.qvel, -10, 10), | ||
np.clip(self.model.data.qfrc_constraint, -10, 10) | ||
self.sim.data.qpos[:1], # cart x pos | ||
np.sin(self.sim.data.qpos[1:]), # link angles | ||
np.cos(self.sim.data.qpos[1:]), | ||
np.clip(self.sim.data.qvel, -10, 10), | ||
np.clip(self.sim.data.qfrc_constraint, -10, 10) | ||
]).ravel() | ||
|
||
def reset_model(self): | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -9,7 +9,6 @@ | |
|
||
try: | ||
import mujoco_py | ||
from mujoco_py.mjlib import mjlib | ||
except ImportError as e: | ||
raise error.DependencyNotInstalled("{}. (HINT: you need to install mujoco_py, and also perform the setup instructions here: https://github.com/openai/mujoco-py/.)".format(e)) | ||
|
||
|
@@ -25,17 +24,18 @@ def __init__(self, model_path, frame_skip): | |
if not path.exists(fullpath): | ||
raise IOError("File %s does not exist" % fullpath) | ||
self.frame_skip = frame_skip | ||
self.model = mujoco_py.MjModel(fullpath) | ||
self.data = self.model.data | ||
self.model = mujoco_py.load_model_from_path(fullpath) | ||
self.sim = mujoco_py.MjSim(self.model) | ||
self.data = self.sim.data | ||
self.viewer = None | ||
|
||
self.metadata = { | ||
'render.modes': ['human', 'rgb_array'], | ||
'video.frames_per_second': int(np.round(1.0 / self.dt)) | ||
} | ||
|
||
self.init_qpos = self.model.data.qpos.ravel().copy() | ||
self.init_qvel = self.model.data.qvel.ravel().copy() | ||
self.init_qpos = self.sim.data.qpos.ravel().copy() | ||
self.init_qvel = self.sim.data.qvel.ravel().copy() | ||
observation, _reward, done, _info = self._step(np.zeros(self.model.nu)) | ||
assert not done | ||
self.obs_dim = observation.size | ||
|
@@ -76,33 +76,33 @@ def viewer_setup(self): | |
# ----------------------------- | ||
|
||
def _reset(self): | ||
mjlib.mj_resetData(self.model.ptr, self.data.ptr) | ||
self.sim.reset() | ||
ob = self.reset_model() | ||
if self.viewer is not None: | ||
self.viewer.autoscale() | ||
self.viewer_setup() | ||
return ob | ||
|
||
def set_state(self, qpos, qvel): | ||
assert qpos.shape == (self.model.nq,) and qvel.shape == (self.model.nv,) | ||
self.model.data.qpos = qpos | ||
self.model.data.qvel = qvel | ||
self.model._compute_subtree() # pylint: disable=W0212 | ||
self.model.forward() | ||
old_state = self.sim.get_state() | ||
new_state = mujoco_py.MjSimState(old_state.time, qpos, qvel, | ||
old_state.act, old_state.udd_state) | ||
self.sim.set_state(new_state) | ||
self.sim.forward() | ||
|
||
@property | ||
def dt(self): | ||
return self.model.opt.timestep * self.frame_skip | ||
|
||
def do_simulation(self, ctrl, n_frames): | ||
self.model.data.ctrl = ctrl | ||
self.sim.data.ctrl[:] = ctrl | ||
for _ in range(n_frames): | ||
self.model.step() | ||
self.sim.step() | ||
|
||
def _render(self, mode='human', close=False): | ||
if close: | ||
if self.viewer is not None: | ||
self._get_viewer().finish() | ||
self._get_viewer() | ||
self.viewer = None | ||
return | ||
|
||
|
@@ -111,30 +111,19 @@ def _render(self, mode='human', close=False): | |
data, width, height = self._get_viewer().get_image() | ||
return np.fromstring(data, dtype='uint8').reshape(height, width, 3)[::-1, :, :] | ||
elif mode == 'human': | ||
self._get_viewer().loop_once() | ||
self._get_viewer().render() | ||
|
||
def _get_viewer(self): | ||
if self.viewer is None: | ||
self.viewer = mujoco_py.MjViewer() | ||
self.viewer.start() | ||
self.viewer.set_model(self.model) | ||
self.viewer = mujoco_py.MjViewer(self.sim) | ||
self.viewer_setup() | ||
return self.viewer | ||
|
||
def get_body_com(self, body_name): | ||
idx = self.model.body_names.index(six.b(body_name)) | ||
return self.model.data.com_subtree[idx] | ||
|
||
def get_body_comvel(self, body_name): | ||
idx = self.model.body_names.index(six.b(body_name)) | ||
return self.model.body_comvels[idx] | ||
|
||
def get_body_xmat(self, body_name): | ||
idx = self.model.body_names.index(six.b(body_name)) | ||
return self.model.data.xmat[idx].reshape((3, 3)) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. These methods don't have obvious implementations in mujoco 1.5 and they aren't used anywhere so I deleted them. |
||
return self.data.get_body_xpos(body_name) | ||
|
||
def state_vector(self): | ||
return np.concatenate([ | ||
self.model.data.qpos.flat, | ||
self.model.data.qvel.flat | ||
self.sim.data.qpos.flat, | ||
self.sim.data.qvel.flat | ||
]) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
My understanding is that
qpos
lists joint angles. Inhalf_cheetah.xml
, it looks like the first joint is "rootx", a slide joint that should give displacement in the x direction. Soqpos[0]
should give the desired value.