Skip to content

Commit bce984a

Browse files
JeanElsnercopybara-github
authored andcommitted
dm_control: Import of refs/pull/440/head
PiperOrigin-RevId: 587271240 Change-Id: I3d11b15a295076a536c73c9919babdbc706b2f3f
1 parent a883b77 commit bce984a

1 file changed

Lines changed: 5 additions & 5 deletions

File tree

dm_control/viewer/renderer.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -237,6 +237,11 @@ def start_move(self, action, grab_pos):
237237
if action is None or grab_pos is None:
238238
return
239239

240+
body_pos = self._data.xpos[self._body_id]
241+
body_mat = self._data.xmat[self._body_id].reshape(3, 3)
242+
grab_local_pos = body_mat.T.dot(grab_pos - body_pos)
243+
self._perturb.localpos[:] = grab_local_pos
244+
240245
mujoco.mjv_initPerturb(self._model.ptr, self._data.ptr, self._scene.ptr,
241246
self._perturb.ptr)
242247
self._action = action
@@ -247,11 +252,6 @@ def start_move(self, action, grab_pos):
247252
else:
248253
self._perturb.active = mujoco.mjtPertBit.mjPERT_ROTATE
249254

250-
body_pos = self._data.xpos[self._body_id]
251-
body_mat = self._data.xmat[self._body_id].reshape(3, 3)
252-
grab_local_pos = body_mat.T.dot(grab_pos - body_pos)
253-
self._perturb.localpos[:] = grab_local_pos
254-
255255
def tick_move(self, viewport_offset):
256256
"""Transforms object's location/rotation by the specified amount."""
257257
if self._action and self._action != mujoco.mjtMouse.mjMOUSE_NONE:

0 commit comments

Comments
 (0)