-
-
Notifications
You must be signed in to change notification settings - Fork 75
/
fetch_env.py
425 lines (361 loc) · 15.7 KB
/
fetch_env.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
from typing import Union
import numpy as np
from gymnasium_robotics.envs.robot_env import MujocoPyRobotEnv, MujocoRobotEnv
from gymnasium_robotics.utils import rotations
DEFAULT_CAMERA_CONFIG = {
"distance": 2.5,
"azimuth": 132.0,
"elevation": -14.0,
"lookat": np.array([1.3, 0.75, 0.55]),
}
def goal_distance(goal_a, goal_b):
assert goal_a.shape == goal_b.shape
return np.linalg.norm(goal_a - goal_b, axis=-1)
def get_base_fetch_env(RobotEnvClass: Union[MujocoPyRobotEnv, MujocoRobotEnv]):
"""Factory function that returns a BaseFetchEnv class that inherits
from MujocoPyRobotEnv or MujocoRobotEnv depending on the mujoco python bindings.
"""
class BaseFetchEnv(RobotEnvClass):
"""Superclass for all Fetch environments."""
def __init__(
self,
gripper_extra_height,
block_gripper,
has_object: bool,
target_in_the_air,
target_offset,
obj_range,
target_range,
distance_threshold,
reward_type,
**kwargs
):
"""Initializes a new Fetch environment.
Args:
model_path (string): path to the environments XML file
n_substeps (int): number of substeps the simulation runs on every call to step
gripper_extra_height (float): additional height above the table when positioning the gripper
block_gripper (boolean): whether or not the gripper is blocked (i.e. not movable) or not
has_object (boolean): whether or not the environment has an object
target_in_the_air (boolean): whether or not the target should be in the air above the table or on the table surface
target_offset (float or array with 3 elements): offset of the target
obj_range (float): range of a uniform distribution for sampling initial object positions
target_range (float): range of a uniform distribution for sampling a target
distance_threshold (float): the threshold after which a goal is considered achieved
initial_qpos (dict): a dictionary of joint names and values that define the initial configuration
reward_type ('sparse' or 'dense'): the reward type, i.e. sparse or dense
"""
self.gripper_extra_height = gripper_extra_height
self.block_gripper = block_gripper
self.has_object = has_object
self.target_in_the_air = target_in_the_air
self.target_offset = target_offset
self.obj_range = obj_range
self.target_range = target_range
self.distance_threshold = distance_threshold
self.reward_type = reward_type
super().__init__(n_actions=4, **kwargs)
# GoalEnv methods
# ----------------------------
def compute_reward(self, achieved_goal, goal, info):
# Compute distance between goal and the achieved goal.
d = goal_distance(achieved_goal, goal)
if self.reward_type == "sparse":
return -(d > self.distance_threshold).astype(np.float32)
else:
return -d
# RobotEnv methods
# ----------------------------
def _set_action(self, action):
assert action.shape == (4,)
action = (
action.copy()
) # ensure that we don't change the action outside of this scope
pos_ctrl, gripper_ctrl = action[:3], action[3]
pos_ctrl *= 0.05 # limit maximum change in position
rot_ctrl = [
1.0,
0.0,
1.0,
0.0,
] # fixed rotation of the end effector, expressed as a quaternion
gripper_ctrl = np.array([gripper_ctrl, gripper_ctrl])
assert gripper_ctrl.shape == (2,)
if self.block_gripper:
gripper_ctrl = np.zeros_like(gripper_ctrl)
action = np.concatenate([pos_ctrl, rot_ctrl, gripper_ctrl])
return action
def _get_obs(self):
(
grip_pos,
object_pos,
object_rel_pos,
gripper_state,
object_rot,
object_velp,
object_velr,
grip_velp,
gripper_vel,
) = self.generate_mujoco_observations()
if not self.has_object:
achieved_goal = grip_pos.copy()
else:
achieved_goal = np.squeeze(object_pos.copy())
obs = np.concatenate(
[
grip_pos,
object_pos.ravel(),
object_rel_pos.ravel(),
gripper_state,
object_rot.ravel(),
object_velp.ravel(),
object_velr.ravel(),
grip_velp,
gripper_vel,
]
)
return {
"observation": obs.copy(),
"achieved_goal": achieved_goal.copy(),
"desired_goal": self.goal.copy(),
}
def generate_mujoco_observations(self):
raise NotImplementedError
def _get_gripper_xpos(self):
raise NotImplementedError
def _sample_goal(self):
if self.has_object:
goal = self.initial_gripper_xpos[:3] + self.np_random.uniform(
-self.target_range, self.target_range, size=3
)
goal += self.target_offset
goal[2] = self.height_offset
if self.target_in_the_air and self.np_random.uniform() < 0.5:
goal[2] += self.np_random.uniform(0, 0.45)
else:
goal = self.initial_gripper_xpos[:3] + self.np_random.uniform(
-self.target_range, self.target_range, size=3
)
return goal.copy()
def _is_success(self, achieved_goal, desired_goal):
d = goal_distance(achieved_goal, desired_goal)
return (d < self.distance_threshold).astype(np.float32)
return BaseFetchEnv
class MujocoPyFetchEnv(get_base_fetch_env(MujocoPyRobotEnv)):
def _step_callback(self):
if self.block_gripper:
self.sim.data.set_joint_qpos("robot0:l_gripper_finger_joint", 0.0)
self.sim.data.set_joint_qpos("robot0:r_gripper_finger_joint", 0.0)
self.sim.forward()
def _set_action(self, action):
action = super()._set_action(action)
# Apply action to simulation.
self._utils.ctrl_set_action(self.sim, action)
self._utils.mocap_set_action(self.sim, action)
def generate_mujoco_observations(self):
# positions
grip_pos = self.sim.data.get_site_xpos("robot0:grip")
dt = self.sim.nsubsteps * self.sim.model.opt.timestep
grip_velp = self.sim.data.get_site_xvelp("robot0:grip") * dt
robot_qpos, robot_qvel = self._utils.robot_get_obs(self.sim)
if self.has_object:
object_pos = self.sim.data.get_site_xpos("object0")
# rotations
object_rot = rotations.mat2euler(self.sim.data.get_site_xmat("object0"))
# velocities
object_velp = self.sim.data.get_site_xvelp("object0") * dt
object_velr = self.sim.data.get_site_xvelr("object0") * dt
# gripper state
object_rel_pos = object_pos - grip_pos
object_velp -= grip_velp
else:
object_pos = (
object_rot
) = object_velp = object_velr = object_rel_pos = np.zeros(0)
gripper_state = robot_qpos[-2:]
gripper_vel = (
robot_qvel[-2:] * dt
) # change to a scalar if the gripper is made symmetric
return (
grip_pos,
object_pos,
object_rel_pos,
gripper_state,
object_rot,
object_velp,
object_velr,
grip_velp,
gripper_vel,
)
def _get_gripper_xpos(self):
body_id = self.sim.model.body_name2id("robot0:gripper_link")
return self.sim.data.body_xpos[body_id]
def _render_callback(self):
# Visualize target.
sites_offset = (self.sim.data.site_xpos - self.sim.model.site_pos).copy()
site_id = self.sim.model.site_name2id("target0")
self.sim.model.site_pos[site_id] = self.goal - sites_offset[0]
self.sim.forward()
def _viewer_setup(self):
lookat = self._get_gripper_xpos()
for idx, value in enumerate(lookat):
self.viewer.cam.lookat[idx] = value
assert self.viewer is not None
for key, value in DEFAULT_CAMERA_CONFIG.items():
if isinstance(value, np.ndarray):
getattr(self.viewer.cam, key)[:] = value
else:
setattr(self.viewer.cam, key, value)
def _reset_sim(self):
self.sim.set_state(self.initial_state)
# Randomize start position of object.
if self.has_object:
object_xpos = self.initial_gripper_xpos[:2]
while np.linalg.norm(object_xpos - self.initial_gripper_xpos[:2]) < 0.1:
object_xpos = self.initial_gripper_xpos[:2] + self.np_random.uniform(
-self.obj_range, self.obj_range, size=2
)
object_qpos = self.sim.data.get_joint_qpos("object0:joint")
assert object_qpos.shape == (7,)
object_qpos[:2] = object_xpos
self.sim.data.set_joint_qpos("object0:joint", object_qpos)
self.sim.forward()
return True
def _env_setup(self, initial_qpos):
for name, value in initial_qpos.items():
self.sim.data.set_joint_qpos(name, value)
self._utils.reset_mocap_welds(self.sim)
self.sim.forward()
# Move end effector into position.
gripper_target = np.array(
[-0.498, 0.005, -0.431 + self.gripper_extra_height]
) + self.sim.data.get_site_xpos("robot0:grip")
gripper_rotation = np.array([1.0, 0.0, 1.0, 0.0])
self.sim.data.set_mocap_pos("robot0:mocap", gripper_target)
self.sim.data.set_mocap_quat("robot0:mocap", gripper_rotation)
for _ in range(10):
self.sim.step()
# Extract information for sampling goals.
self.initial_gripper_xpos = self.sim.data.get_site_xpos("robot0:grip").copy()
if self.has_object:
self.height_offset = self.sim.data.get_site_xpos("object0")[2]
class MujocoFetchEnv(get_base_fetch_env(MujocoRobotEnv)):
def __init__(self, default_camera_config: dict = DEFAULT_CAMERA_CONFIG, **kwargs):
super().__init__(default_camera_config=default_camera_config, **kwargs)
def _step_callback(self):
if self.block_gripper:
self._utils.set_joint_qpos(
self.model, self.data, "robot0:l_gripper_finger_joint", 0.0
)
self._utils.set_joint_qpos(
self.model, self.data, "robot0:r_gripper_finger_joint", 0.0
)
self._mujoco.mj_forward(self.model, self.data)
def _set_action(self, action):
action = super()._set_action(action)
# Apply action to simulation.
self._utils.ctrl_set_action(self.model, self.data, action)
self._utils.mocap_set_action(self.model, self.data, action)
def generate_mujoco_observations(self):
# positions
grip_pos = self._utils.get_site_xpos(self.model, self.data, "robot0:grip")
dt = self.n_substeps * self.model.opt.timestep
grip_velp = (
self._utils.get_site_xvelp(self.model, self.data, "robot0:grip") * dt
)
robot_qpos, robot_qvel = self._utils.robot_get_obs(
self.model, self.data, self._model_names.joint_names
)
if self.has_object:
object_pos = self._utils.get_site_xpos(self.model, self.data, "object0")
# rotations
object_rot = rotations.mat2euler(
self._utils.get_site_xmat(self.model, self.data, "object0")
)
# velocities
object_velp = (
self._utils.get_site_xvelp(self.model, self.data, "object0") * dt
)
object_velr = (
self._utils.get_site_xvelr(self.model, self.data, "object0") * dt
)
# gripper state
object_rel_pos = object_pos - grip_pos
object_velp -= grip_velp
else:
object_pos = (
object_rot
) = object_velp = object_velr = object_rel_pos = np.zeros(0)
gripper_state = robot_qpos[-2:]
gripper_vel = (
robot_qvel[-2:] * dt
) # change to a scalar if the gripper is made symmetric
return (
grip_pos,
object_pos,
object_rel_pos,
gripper_state,
object_rot,
object_velp,
object_velr,
grip_velp,
gripper_vel,
)
def _get_gripper_xpos(self):
body_id = self._model_names.body_name2id["robot0:gripper_link"]
return self.data.xpos[body_id]
def _render_callback(self):
# Visualize target.
sites_offset = (self.data.site_xpos - self.model.site_pos).copy()
site_id = self._mujoco.mj_name2id(
self.model, self._mujoco.mjtObj.mjOBJ_SITE, "target0"
)
self.model.site_pos[site_id] = self.goal - sites_offset[0]
self._mujoco.mj_forward(self.model, self.data)
def _reset_sim(self):
self.data.time = self.initial_time
self.data.qpos[:] = np.copy(self.initial_qpos)
self.data.qvel[:] = np.copy(self.initial_qvel)
if self.model.na != 0:
self.data.act[:] = None
# Randomize start position of object.
if self.has_object:
object_xpos = self.initial_gripper_xpos[:2]
while np.linalg.norm(object_xpos - self.initial_gripper_xpos[:2]) < 0.1:
object_xpos = self.initial_gripper_xpos[:2] + self.np_random.uniform(
-self.obj_range, self.obj_range, size=2
)
object_qpos = self._utils.get_joint_qpos(
self.model, self.data, "object0:joint"
)
assert object_qpos.shape == (7,)
object_qpos[:2] = object_xpos
self._utils.set_joint_qpos(
self.model, self.data, "object0:joint", object_qpos
)
self._mujoco.mj_forward(self.model, self.data)
return True
def _env_setup(self, initial_qpos):
for name, value in initial_qpos.items():
self._utils.set_joint_qpos(self.model, self.data, name, value)
self._utils.reset_mocap_welds(self.model, self.data)
self._mujoco.mj_forward(self.model, self.data)
# Move end effector into position.
gripper_target = np.array(
[-0.498, 0.005, -0.431 + self.gripper_extra_height]
) + self._utils.get_site_xpos(self.model, self.data, "robot0:grip")
gripper_rotation = np.array([1.0, 0.0, 1.0, 0.0])
self._utils.set_mocap_pos(self.model, self.data, "robot0:mocap", gripper_target)
self._utils.set_mocap_quat(
self.model, self.data, "robot0:mocap", gripper_rotation
)
for _ in range(10):
self._mujoco.mj_step(self.model, self.data, nstep=self.n_substeps)
# Extract information for sampling goals.
self.initial_gripper_xpos = self._utils.get_site_xpos(
self.model, self.data, "robot0:grip"
).copy()
if self.has_object:
self.height_offset = self._utils.get_site_xpos(
self.model, self.data, "object0"
)[2]