| import numpy as np |
| import gymnasium as gym |
| import gymnasium_robotics |
| import mujoco |
|
|
| class CustomFetchWrapper(gym.Wrapper): |
| def __init__(self, env, block_xy=None, goal_xyz=None): |
| super().__init__(env) |
| self.u = env.unwrapped |
| |
| self.default_block_xy = (np.array(block_xy, dtype=float) |
| if block_xy is not None else None) |
| self.default_goal_xyz = (np.array(goal_xyz, dtype=float) |
| if goal_xyz is not None else None) |
|
|
| def reset(self, *args, **kwargs): |
| |
| obs, info = super().reset(*args, **kwargs) |
| u = self.unwrapped |
| model = u.model |
| data = u.data |
| utils = u._utils |
| rng = u.np_random |
|
|
| |
| for name, val in zip( |
| ["robot0:slide0","robot0:slide1","robot0:slide2"], |
| [0.405, 0.48, 0.0], |
| ): |
| utils.set_joint_qpos(model, data, name, val) |
|
|
| |
| if self.default_block_xy is None: |
| |
| home_xy = u.initial_gripper_xpos[:2] |
| obj_range = u.obj_range |
| min_dist = u.distance_threshold |
| while True: |
| offset = rng.uniform(-obj_range, obj_range, size=2) |
| if np.linalg.norm(offset) < min_dist: |
| continue |
| cand = home_xy + offset |
| if np.linalg.norm(cand - obs["desired_goal"][:2]) < min_dist: |
| continue |
| break |
| block_xy = cand |
| else: |
| block_xy = self.default_block_xy |
|
|
| |
| blk_qpos = utils.get_joint_qpos(model, data, "object0:joint") |
| blk_qpos[0:2] = block_xy |
| blk_qpos[2] = 0.42 |
| utils.set_joint_qpos(model, data, "object0:joint", blk_qpos) |
|
|
| |
| if self.default_goal_xyz is None: |
| |
| raise_z = 0.1 + rng.uniform(0, 0.2) |
| new_goal = obs["desired_goal"].copy() |
| new_goal[2] = blk_qpos[2] + raise_z |
| else: |
| new_goal = self.default_goal_xyz |
|
|
| |
| u.goal = new_goal |
| sid = mujoco.mj_name2id(model, |
| mujoco.mjtObj.mjOBJ_SITE, |
| "target0") |
| data.site_xpos[sid] = new_goal |
|
|
| |
| u._mujoco.mj_forward(model, data) |
| obs = u._get_obs() |
|
|
| return obs, info |
|
|
|
|
| def create_env(render_mode=None, block_xy=None, goal_xyz=None): |
| gym.register_envs(gymnasium_robotics) |
| base_env = gym.make("FetchPickAndPlace-v3", render_mode=render_mode) |
| u = base_env.unwrapped |
|
|
| |
| |
| |
| center_xy = u.initial_gripper_xpos[:2] |
| table_z = 0.42 |
| table_center = np.array([*center_xy, table_z]) |
|
|
| |
| if block_xy is not None: |
| rel = np.array(block_xy, dtype=float) |
| abs_block_xy = center_xy + rel |
| else: |
| abs_block_xy = None |
|
|
| |
| if goal_xyz is not None: |
| rel = np.array(goal_xyz, dtype=float) |
| abs_goal_xyz = table_center + rel |
| else: |
| abs_goal_xyz = None |
|
|
| |
| env = CustomFetchWrapper( |
| base_env, |
| block_xy=abs_block_xy, |
| goal_xyz=abs_goal_xyz |
| ) |
| return env |