Skip to content
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

Control Hopper Env, Stand + Hop #440

Merged
merged 18 commits into from
Jul 26, 2024
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
42 changes: 42 additions & 0 deletions docs/source/tasks/control/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,4 +45,46 @@ Use the Cartpole robot to swing up a pole on a cart.

**Success Conditions:**
- No specific success conditions. The task is considered successful if the pole is upright for the whole episode. We can threshold the episode accumulated reward to determine success.
:::

## MS-HopperHop-v1
![dense-reward][reward-badge]

:::{dropdown} Task Card
:icon: note
:color: primary

**Task Description:**
Hopper robot stays upright and moves in positive x direction with hopping motion


**Supported Robots: Hopper**

**Randomizations:**
- Hopper robot is randomly rotated [-pi, pi] radians about y axis.
- Hopper qpos are uniformly sampled within their allowed ranges

**Success Conditions:**
- No specific success conditions. The task is considered successful if the pole is upright for the whole episode. We can threshold the episode accumulated reward to determine success.
:::

## MS-HopperStand-v1
![dense-reward][reward-badge]

:::{dropdown} Task Card
:icon: note
:color: primary

**Task Description:**
Hopper robot stands upright


**Supported Robots: Hopper**

**Randomizations:**
- Hopper robot is randomly rotated [-pi, pi] radians about y axis.
- Hopper qpos are uniformly sampled within their allowed ranges

**Success Conditions:**
- No specific success conditions. We can threshold the episode accumulated reward to determine success.
:::
5 changes: 5 additions & 0 deletions mani_skill/envs/sapien_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -620,9 +620,14 @@ def _setup_sensors(self, options: dict):
# Cameras for rendering only
self._human_render_cameras = dict()
for uid, camera_cfg in self._human_render_camera_configs.items():
if uid in self._agent_sensor_configs:
articulation = self.agent.robot
else:
articulation = None
self._human_render_cameras[uid] = Camera(
camera_cfg,
self.scene,
articulation=articulation,
Xander-Hinrichsen marked this conversation as resolved.
Show resolved Hide resolved
)

self.scene.sensors = self._sensors
Expand Down
1 change: 1 addition & 0 deletions mani_skill/envs/tasks/control/__init__.py
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
from .cartpole import CartpoleBalanceEnv, CartpoleSwingUpEnv
from .hopper import HopperHopEnv, HopperStandEnv
70 changes: 70 additions & 0 deletions mani_skill/envs/tasks/control/assets/hopper.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
<mujoco model="planar hopper">
<include file="./common/skybox.xml"/>
<include file="./common/visual.xml"/>
<include file="./common/materials.xml"/>

<statistic extent="2" center="0 0 .5"/>

<default>
<default class="hopper">
<joint type="hinge" axis="0 1 0" limited="true" damping=".05" armature=".2"/>
<geom type="capsule" material="self"/>
<site type="sphere" size="0.05" group="3"/>
</default>
<default class="free">
<joint limited="false" damping="0" armature="0" stiffness="0"/>
</default>
<motor ctrlrange="-1 1" ctrllimited="true"/>
</default>

<option timestep="0.005"/>

<worldbody>
<camera name="cam0" pos="0 -2.8 0.8" euler="90 0 0" mode="trackcom"/>
<camera name="back" pos="-2 -.2 1.2" xyaxes="0.2 -1 0 .5 0 2" mode="trackcom"/>
<geom name="floor" type="plane" conaffinity="1" pos="48 0 0" size="50 1 .2" material="grid"/>
<body name="torso" pos="0 0 1" childclass="hopper">
<light name="top" pos="0 0 2" mode="trackcom"/>
<joint name="rootx" type="slide" axis="1 0 0" class="free"/>
<joint name="rootz" type="slide" axis="0 0 1" class="free"/>
<joint name="rooty" type="hinge" axis="0 1 0" class="free"/>
<geom name="torso" fromto="0 0 -.05 0 0 .2" size="0.0653"/>
<geom name="nose" fromto=".08 0 .13 .15 0 .14" size="0.03"/>
<body name="pelvis" pos="0 0 -.05">
<joint name="waist" range="-30 30"/>
<geom name="pelvis" fromto="0 0 0 0 0 -.15" size="0.065"/>
<body name="thigh" pos="0 0 -.2">
<joint name="hip" range="-170 10"/>
<geom name="thigh" fromto="0 0 0 0 0 -.33" size="0.04"/>
<body name="calf" pos="0 0 -.33">
<joint name="knee" range="5 150"/>
<geom name="calf" fromto="0 0 0 0 0 -.32" size="0.03"/>
<!-- foot slightly modified from original mjcf
split into heel and toe for force calculation convienence -->
<body name="foot_heel" pos="0 0 -.32">
<joint name="ankle" range="-45 45"/>
<geom name="foot_heel" fromto="-.08 0 0 .11 0 0" size="0.04"/>
<body name="foot_toe">
<joint name="fix_toe2heel" type="fixed"/>
<geom name="foot_toe" fromto=".11 0 0 .17 0 0" size="0.04"/>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<sensor>
<subtreelinvel name="torso_subtreelinvel" body="torso"/>
<touch name="touch_toe" site="touch_toe"/>
<touch name="touch_heel" site="touch_heel"/>
</sensor>

<actuator>
<motor name="waist" joint="waist" gear="30"/>
<motor name="hip" joint="hip" gear="40"/>
<motor name="knee" joint="knee" gear="30"/>
<motor name="ankle" joint="ankle" gear="10"/>
</actuator>
</mujoco>
Loading