reacher updates
This commit is contained in:
parent
8fc1210f1e
commit
d9f52194f7
@ -6,6 +6,27 @@ register(
|
||||
max_episode_steps=200,
|
||||
kwargs={
|
||||
"steps_before_reward": 0,
|
||||
"n_links": 5,
|
||||
}
|
||||
)
|
||||
|
||||
register(
|
||||
id='ALRReacherShort-v0',
|
||||
entry_point='alr_envs.mujoco:ALRReacherEnv',
|
||||
max_episode_steps=50,
|
||||
kwargs={
|
||||
"steps_before_reward": 50,
|
||||
"n_links": 5,
|
||||
}
|
||||
)
|
||||
|
||||
register(
|
||||
id='ALRReacherSparse-v0',
|
||||
entry_point='alr_envs.mujoco:ALRReacherEnv',
|
||||
max_episode_steps=200,
|
||||
kwargs={
|
||||
"steps_before_reward": 200,
|
||||
"n_links": 5,
|
||||
}
|
||||
)
|
||||
|
||||
@ -15,6 +36,7 @@ register(
|
||||
max_episode_steps=200,
|
||||
kwargs={
|
||||
"steps_before_reward": 100,
|
||||
"n_links": 5,
|
||||
}
|
||||
)
|
||||
|
||||
@ -24,6 +46,7 @@ register(
|
||||
max_episode_steps=200,
|
||||
kwargs={
|
||||
"steps_before_reward": 180,
|
||||
"n_links": 5,
|
||||
}
|
||||
)
|
||||
|
||||
|
@ -5,19 +5,42 @@ from gym.envs.mujoco import mujoco_env
|
||||
|
||||
|
||||
class ALRReacherEnv(mujoco_env.MujocoEnv, utils.EzPickle):
|
||||
def __init__(self):
|
||||
def __init__(self, steps_before_reward=200, n_links=5):
|
||||
self._steps = 0
|
||||
self.steps_before_reward = steps_before_reward
|
||||
self.n_links = n_links
|
||||
|
||||
self.reward_weight = 1 if self.steps_before_reward != 200 and self.steps_before_reward != 50 else 200
|
||||
|
||||
if n_links == 5:
|
||||
file_name = 'reacher_5links.xml'
|
||||
elif n_links == 7:
|
||||
file_name = 'reacher_7links.xml'
|
||||
else:
|
||||
raise ValueError(f"Invalid number of links {n_links}, only 5 or 7 allowed.")
|
||||
|
||||
utils.EzPickle.__init__(self)
|
||||
mujoco_env.MujocoEnv.__init__(self, os.path.join(os.path.dirname(__file__), "assets", 'reacher_5links.xml'), 2)
|
||||
mujoco_env.MujocoEnv.__init__(self, os.path.join(os.path.dirname(__file__), "assets", file_name), 2)
|
||||
|
||||
def step(self, a):
|
||||
self._steps += 1
|
||||
|
||||
reward_dist = 0
|
||||
angular_vel = 0
|
||||
if self._steps >= self.steps_before_reward:
|
||||
vec = self.get_body_com("fingertip") - self.get_body_com("target")
|
||||
reward_dist = - np.linalg.norm(vec)
|
||||
reward_dist -= self.reward_weight * np.linalg.norm(vec)
|
||||
angular_vel -= np.linalg.norm(self.sim.data.qvel.flat[:self.n_links])
|
||||
reward_ctrl = - np.square(a).sum()
|
||||
reward = reward_dist + reward_ctrl
|
||||
|
||||
reward = reward_dist + reward_ctrl + angular_vel
|
||||
self.do_simulation(a, self.frame_skip)
|
||||
ob = self._get_obs()
|
||||
done = False
|
||||
return ob, reward, done, dict(reward_dist=reward_dist, reward_ctrl=reward_ctrl)
|
||||
return ob, reward, done, dict(reward_dist=reward_dist, reward_ctrl=reward_ctrl,
|
||||
velocity=angular_vel,
|
||||
end_effector=self.get_body_com("fingertip").copy(),
|
||||
goal=self.goal if hasattr(self, "goal") else None)
|
||||
|
||||
def viewer_setup(self):
|
||||
self.viewer.cam.trackbodyid = 0
|
||||
@ -25,22 +48,25 @@ class ALRReacherEnv(mujoco_env.MujocoEnv, utils.EzPickle):
|
||||
def reset_model(self):
|
||||
qpos = self.np_random.uniform(low=-0.1, high=0.1, size=self.model.nq) + self.init_qpos
|
||||
while True:
|
||||
self.goal = self.np_random.uniform(low=-.2, high=.2, size=2)
|
||||
if np.linalg.norm(self.goal) < 0.2:
|
||||
self.goal = self.np_random.uniform(low=-self.n_links / 10, high=self.n_links / 10, size=2)
|
||||
if np.linalg.norm(self.goal) < self.n_links / 10:
|
||||
break
|
||||
qpos[-2:] = self.goal
|
||||
qvel = self.init_qvel + self.np_random.uniform(low=-.005, high=.005, size=self.model.nv)
|
||||
qvel[-2:] = 0
|
||||
self.set_state(qpos, qvel)
|
||||
self._steps = 0
|
||||
|
||||
return self._get_obs()
|
||||
|
||||
def _get_obs(self):
|
||||
theta = self.sim.data.qpos.flat[:5]
|
||||
theta = self.sim.data.qpos.flat[:self.n_links]
|
||||
return np.concatenate([
|
||||
np.cos(theta),
|
||||
np.sin(theta),
|
||||
self.sim.data.qpos.flat[5:], # this is goal position
|
||||
self.sim.data.qvel.flat[:5], # this is angular velocity
|
||||
self.get_body_com("fingertip") - self.get_body_com("target")
|
||||
self.sim.data.qpos.flat[self.n_links:], # this is goal position
|
||||
self.sim.data.qvel.flat[:self.n_links], # this is angular velocity
|
||||
self.get_body_com("fingertip") - self.get_body_com("target"),
|
||||
# self.get_body_com("target"), # only return target to make problem harder
|
||||
[self._steps],
|
||||
])
|
||||
|
75
alr_envs/mujoco/assets/reacher_7links.xml
Normal file
75
alr_envs/mujoco/assets/reacher_7links.xml
Normal file
@ -0,0 +1,75 @@
|
||||
<mujoco model="reacher">
|
||||
<compiler angle="radian" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
</default>
|
||||
<option gravity="0 0 -9.81" integrator="RK4" timestep="0.01"/>
|
||||
<worldbody>
|
||||
<!-- Arena -->
|
||||
<geom conaffinity="0" contype="0" name="ground" pos="0 0 0" rgba="0.9 0.9 0.9 1" size="1 1 10" type="plane"/>
|
||||
<geom conaffinity="0" fromto="-.8 -.8 .01 .8 -.8 .01" name="sideS" rgba="0.9 0.4 0.6 1" size=".02"
|
||||
type="capsule"/>
|
||||
<geom conaffinity="0" fromto=" .8 -.8 .01 .8 .8 .01" name="sideE" rgba="0.9 0.4 0.6 1" size=".02"
|
||||
type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.8 .8 .01 .8 .8 .01" name="sideN" rgba="0.9 0.4 0.6 1" size=".02"
|
||||
type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.8 -.8 .01 -.8 .8 .01" name="sideW" rgba="0.9 0.4 0.6 1" size=".02"
|
||||
type="capsule"/>
|
||||
<!-- Arm -->
|
||||
<geom conaffinity="0" contype="0" fromto="0 0 0 0 0 0.02" name="root" rgba="0.9 0.4 0.6 1" size=".011"
|
||||
type="cylinder"/>
|
||||
<body name="body0" pos="0 0 .01">
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link0" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<joint axis="0 0 1" limited="false" name="joint0" pos="0 0 0" type="hinge"/>
|
||||
<body name="body1" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="false" name="joint1" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link1" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<body name="body2" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="false" name="joint2" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link2" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<body name="body3" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="false" name="joint3" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link3" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<body name="body4" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="false" name="joint4" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link4" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<body name="body5" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="false" name="joint5" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link5" rgba="0.0 0.4 0.6 1" size=".01"
|
||||
type="capsule"/>
|
||||
<body name="body6" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="true" name="joint6" pos="0 0 0" range="-3.0 3.0"
|
||||
type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link6" rgba="0.0 0.4 0.6 1" size=".01"
|
||||
type="capsule"/>
|
||||
<body name="fingertip" pos="0.11 0 0">
|
||||
<geom contype="0" name="fingertip" pos="0 0 0" rgba="0.0 0.8 0.6 1" size=".01"
|
||||
type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<!-- Target -->
|
||||
<body name="target" pos=".1 -.1 .01">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="true" name="target_x" pos="0 0 0" range="-.27 .27"
|
||||
ref=".1" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="true" name="target_y" pos="0 0 0" range="-.27 .27"
|
||||
ref="-.1" stiffness="0" type="slide"/>
|
||||
<geom conaffinity="0" contype="0" name="target" pos="0 0 0" rgba="0.9 0.2 0.2 1" size=".009" type="sphere"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint0"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint2"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint3"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint4"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint5"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint6"/>
|
||||
</actuator>
|
||||
</mujoco>
|
Loading…
Reference in New Issue
Block a user