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

Add LEAP hand. #91

Merged
merged 6 commits into from
Sep 6, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,7 @@ Menagerie, see [CONTRIBUTING](CONTRIBUTING.md).
| Name | Maker | DoFs | License | MJX |
|------|-------|---------|---------|-----|
| Allegro Hand V3 | Wonik Robotics | 16 | [BSD-2-Clause](wonik_allegro/LICENSE) |✖️|
| LEAP Hand | Carnegie Mellon University | 16 | [MIT](leap_hand/LICENSE) |✖️|
| Robotiq 2F-85 | Robotiq | 8 | [BSD-2-Clause](robotiq_2f85/LICENSE) |✖️|
| Shadow Hand EM35 | Shadow Robot Company | 24 | [Apache-2.0](shadow_hand/LICENSE) |✖️|
| Shadow DEX-EE Hand | Shadow Robot Company | 12 | [Apache-2.0](shadow_dexee/LICENSE) |✖️|
Expand Down
7 changes: 7 additions & 0 deletions leap_hand/LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
Copyright 2023 Ananye Agarwal

Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the “Software”), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
48 changes: 48 additions & 0 deletions leap_hand/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
# Leap Hand Description (MJCF)

> [!IMPORTANT]
> Requires MuJoCo 3.1.3 or later.

## Overview

This package contains a simplified robot description (MJCF) of the (left and right) [LEAP Hand](https://leaphand.com/) developed by Carnegie Mellon University. It is derived from the [publicly available URDF description](https://github.com/leap-hand/LEAP_Hand_Sim/blob/master/assets/leap_hand/robot.urdf).

<p float="left">
<img src="leap_hand_left.png" width="400">
<img src="leap_hand_right.png" width="400">
</p>

## URDF → MJCF derivation steps

1. Added `<mujoco> <compiler discardvisual="false" strippath="false" fusestatic="false" balanceinertia="true"/> </mujoco>` to the URDF's
`<robot>` clause in order to preserve visual geometries.
2. Removed `package://` shortcuts in the URDF.
3. Loaded the URDF into MuJoCo and saved a corresponding MJCF.
4. Manually edited the MJCF to extract common properties into the `<default>` section.
5. Added `exclude` clause to prevent collisions between the palm and the base of each finger as well as the mcp and dip joint of each finger.
6. Added position controlled actuators.
7. Added `impratio=10` and `cone=elliptic` for better noslip.
8. Added `scene.xml` which includes the robot, with a textured groundplane, skybox, and haze.

Extra steps taken for the left hand:

- Renamed `palm_lower_left` to `palm_lower`.
- Replaced `thumb_left_temp_base` mesh with `pip` to match the right hand.
- Reordered the joints of the thumb to match that of the right hand.

## License

This model is released under an [MIT License](LICENSE).

## Publications

The LEAP Hand is described in the following publication:

```bibtex
@article{shaw2023leaphand,
title = {LEAP Hand: Low-Cost, Efficient, and Anthropomorphic Hand for Robot Learning},
author = {Shaw, Kenneth and Agarwal, Ananye and Pathak, Deepak},
journal = {Robotics: Science and Systems (RSS)},
year = {2023}
}
```
Binary file added leap_hand/assets/dip.stl
Binary file not shown.
Binary file added leap_hand/assets/fingertip.stl
Binary file not shown.
Binary file added leap_hand/assets/mcp_joint.stl
Binary file not shown.
Binary file added leap_hand/assets/palm_lower.stl
Binary file not shown.
Binary file added leap_hand/assets/palm_lower_left.stl
Binary file not shown.
Binary file added leap_hand/assets/pip.stl
Binary file not shown.
Binary file added leap_hand/assets/thumb_dip.stl
Binary file not shown.
Binary file added leap_hand/assets/thumb_fingertip.stl
Binary file not shown.
Binary file added leap_hand/assets/thumb_pip.stl
Binary file not shown.
Binary file added leap_hand/leap_hand_left.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added leap_hand/leap_hand_right.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
184 changes: 184 additions & 0 deletions leap_hand/left_hand.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,184 @@
<mujoco model="left leap hand">
<compiler angle="radian" autolimits="true" meshdir="assets"/>

<option integrator="implicitfast" cone="elliptic" impratio="10"/>

<default>
<default class="left_leap">
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
<joint axis="0 0 -1" armature="0.01"/>
<position inheritrange="1" kp="20" dampratio="1"/>
<default class="visual">
<geom group="2" type="mesh" contype="0" conaffinity="0" density="0" material="black"/>
</default>
<default class="collision">
<geom group="3" type="mesh"/>
</default>
</default>
</default>

<asset>
<material name="black" rgba=".2 .2 .2 1"/>

<mesh name="palm_lower" file="palm_lower_left.stl"/>
<mesh file="mcp_joint.stl"/>
<mesh file="pip.stl"/>
<mesh file="dip.stl"/>
<mesh file="fingertip.stl"/>
<mesh file="thumb_pip.stl"/>
<mesh file="thumb_dip.stl"/>
<mesh file="thumb_fingertip.stl"/>
</asset>

<worldbody>
<light pos="0 0 2"/>
<body name="palm_lower" childclass="left_leap" pos="0 0 .1" quat="0 1 0 0">
<inertial pos="0 0 0" quat="0.704257 -0.0014136 0.00678547 0.709911" mass="0.235"
diaginertia="0.000523252 0.000351001 0.000256955"/>
<geom pos="-0.0955742 -0.11704 0.0207796" quat="0 0 1 1" mesh="palm_lower" class="visual"/>
<geom pos="-0.0955742 -0.11704 0.0207796" quat="0 0 1 1" mesh="palm_lower" class="collision"/>
<body name="mcp_joint" pos="-0.0825742 -0.08574 0.00780089" quat="1 1 1 -1">
<inertial pos="0 0 0" quat="0.388585 0.626468 -0.324549 0.592628" mass="0.044"
diaginertia="1.47756e-05 1.31982e-05 6.0802e-06"/>
<joint name="1" range="-0.314 2.23" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0084069 0.00776624 0.0146574" quat="1 0 0 0" mesh="mcp_joint" class="visual"/>
<geom pos="0.0084069 0.00776624 0.0146574" quat="1 0 0 0" mesh="mcp_joint" class="collision"/>
<body name="pip" pos="-0.0122 0.0381 0.0145" quat="1 -1 -1 1">
<inertial pos="0 0 0" quat="0.709913 0.704273 -0.000363156 0.00475427" mass="0.032"
diaginertia="4.7981e-06 4.23406e-06 2.86184e-06"/>
<joint name="0" range="-1.047 1.047" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.00964336 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="visual"/>
<geom pos="0.00964336 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="collision"/>
<body name="dip" pos="0.015 0.0143 -0.013" quat="1 1 -1 1">
<inertial pos="0 0 0" quat="-0.252689 0.659216 0.238844 0.666735" mass="0.037"
diaginertia="6.68256e-06 6.24841e-06 5.02002e-06"/>
<joint name="2" range="-0.506 1.885" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0211334 -0.00843212 0.00978509" quat="0 -1 0 0" mesh="dip" class="visual"/>
<geom pos="0.0211334 -0.00843212 0.00978509" quat="0 -1 0 0" mesh="dip" class="collision"/>
<body name="fingertip" pos="-4.08806e-09 -0.0361 0.0002">
<inertial pos="0 0 0" quat="0.706755 0.706755 0.0223155 0.0223155" mass="0.016"
diaginertia="3.37527e-06 2.863e-06 1.54873e-06"/>
<joint name="3" range="-0.366 2.042" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0132864 -0.00611424 0.0145" quat="0 1 0 0" mesh="fingertip" class="visual"/>
<geom pos="0.0132864 -0.00611424 0.0145" quat="0 1 0 0" mesh="fingertip" class="collision"/>
</body>
</body>
</body>
</body>
<body name="mcp_joint_2" pos="-0.0825742 -0.04029 0.00780089" quat="1 1 1 -1">
<inertial pos="0 0 0" quat="0.388585 0.626468 -0.324549 0.592628" mass="0.044"
diaginertia="1.47756e-05 1.31982e-05 6.0802e-06"/>
<joint name="5" range="-0.314 2.23" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0084069 0.00776624 0.0146574" quat="1 0 0 0" mesh="mcp_joint" class="visual"/>
<geom pos="0.0084069 0.00776624 0.0146574" quat="1 0 0 0" mesh="mcp_joint" class="collision"/>
<body name="pip_2" pos="-0.0122 0.0381 0.0145" quat="1 -1 -1 1">
<inertial pos="0 0 0" quat="0.709913 0.704273 -0.000363156 0.00475427" mass="0.032"
diaginertia="4.7981e-06 4.23406e-06 2.86184e-06"/>
<joint name="4" range="-1.047 1.047" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.00964336 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="visual"/>
<geom pos="0.00964336 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="collision"/>
<body name="dip_2" pos="0.015 0.0143 -0.013" quat="1 1 -1 1">
<inertial pos="0 0 0" quat="-0.252689 0.659216 0.238844 0.666735" mass="0.037"
diaginertia="6.68256e-06 6.24841e-06 5.02002e-06"/>
<joint name="6" range="-0.506 1.885" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0211334 -0.00843212 0.00978509" quat="0 -1 0 0" mesh="dip" class="visual"/>
<geom pos="0.0211334 -0.00843212 0.00978509" quat="0 -1 0 0" mesh="dip" class="collision"/>
<body name="fingertip_2" pos="0 -0.0361 0.0002">
<inertial pos="0 0 0" quat="0.706755 0.706755 0.0223155 0.0223155" mass="0.016"
diaginertia="3.37527e-06 2.863e-06 1.54873e-06"/>
<joint name="7" range="-0.366 2.042" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0132864 -0.00611424 0.0145" quat="0 1 0 0" mesh="fingertip" class="visual"/>
<geom pos="0.0132864 -0.00611424 0.0145" quat="0 1 0 0" mesh="fingertip" class="collision"/>
</body>
</body>
</body>
</body>
<body name="mcp_joint_3" pos="-0.0825742 0.00515999 0.00780089" quat="1 1 1 -1">
<inertial pos="0 0 0" quat="0.388585 0.626468 -0.324549 0.592628" mass="0.044"
diaginertia="1.47756e-05 1.31982e-05 6.0802e-06"/>
<joint name="9" range="-0.314 2.23" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0084069 0.00776624 0.0146574" quat="1 0 0 0" mesh="mcp_joint" class="visual"/>
<geom pos="0.0084069 0.00776624 0.0146574" quat="1 0 0 0" mesh="mcp_joint" class="collision"/>
<body name="pip_3" pos="-0.0122 0.0381 0.0145" quat="1 -1 -1 1">
<inertial pos="0 0 0" quat="0.709913 0.704273 -0.000363156 0.00475427" mass="0.032"
diaginertia="4.7981e-06 4.23406e-06 2.86184e-06"/>
<joint name="8" range="-1.047 1.047" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.00964336 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="visual"/>
<geom pos="0.00964336 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="collision"/>
<body name="dip_3" pos="0.015 0.0143 -0.013" quat="1 1 -1 1">
<inertial pos="0 0 0" quat="-0.252689 0.659216 0.238844 0.666735" mass="0.037"
diaginertia="6.68256e-06 6.24841e-06 5.02002e-06"/>
<joint name="10" range="-0.506 1.885" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0211334 -0.00843212 0.00978509" quat="0 -1 0 0" mesh="dip" class="visual"/>
<geom pos="0.0211334 -0.00843212 0.00978509" quat="0 -1 0 0" mesh="dip" class="collision"/>
<body name="fingertip_3" pos="0 -0.0361 0.0002">
<inertial pos="0 0 0" quat="0.706755 0.706755 0.0223155 0.0223155" mass="0.016"
diaginertia="3.37527e-06 2.863e-06 1.54873e-06"/>
<joint name="11" range="-0.366 2.042" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0132864 -0.00611424 0.0145" quat="0 1 0 0" mesh="fingertip" class="visual"/>
<geom pos="0.0132864 -0.00611424 0.0145" quat="0 1 0 0" mesh="fingertip" class="collision"/>
</body>
</body>
</body>
</body>
<body name="pip_4" pos="-0.144874 -0.09004 0.00490089" quat="1 0 1 0">
<inertial pos="0 0 0" quat="0.709913 0.704273 -0.000363156 0.00475427" mass="0.032"
diaginertia="4.7981e-06 4.23406e-06 2.86184e-06"/>
<joint name="12" range="-2.094 0.349" actuatorfrcrange="-0.95 0.95"/>
<geom pos="-0.00535664 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="visual"/>
<geom pos="-0.00535664 0.0003 0.000784034" quat="1 -1 -1 -1" mesh="pip" class="collision"/>
<body name="thumb_pip" pos="0 -0.0141 -0.013" quat="1 -1 -1 -1">
<inertial pos="0 0 0" mass="0.003" diaginertia="5.93e-07 5.49e-07 2.24e-07"/>
<joint name="13" range="-2.443 0.47" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0119619 0 -0.0158526" quat="1 1 0 0" mesh="thumb_pip" class="visual"/>
<geom pos="0.0119619 0 -0.0158526" quat="1 1 0 0" mesh="thumb_pip" class="collision"/>
<body name="thumb_dip" pos="0 0.0145 -0.017" quat="1 -1 0 0">
<inertial pos="0 0 0" quat="0.708624 0.704906 0.00637342 0.0303153" mass="0.038"
diaginertia="8.48742e-06 7.67823e-06 3.82835e-06"/>
<joint name="14" range="-1.2 1.9" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0439687 0.057953 -0.00862868" quat="1 0 0 0" mesh="thumb_dip" class="visual"/>
<geom pos="0.0439687 0.057953 -0.00862868" quat="1 0 0 0" mesh="thumb_dip" class="collision"/>
<body name="thumb_fingertip" pos="0 0.0466 0.0002" quat="0 0 0 -1">
<inertial pos="0 0 0" quat="0.704307 0.709299 0.006848 -0.0282727" mass="0.049"
diaginertia="2.03882e-05 1.98443e-05 4.32049e-06"/>
<joint name="15" range="-1.34 1.88" actuatorfrcrange="-0.95 0.95"/>
<geom pos="0.0625595 0.0784597 0.0489929" quat="1 0 0 0" mesh="thumb_fingertip" class="visual"/>
<geom pos="0.0625595 0.0784597 0.0489929" quat="1 0 0 0" mesh="thumb_fingertip" class="collision"/>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<contact>
<exclude body1="palm_lower" body2="mcp_joint"/>
<exclude body1="palm_lower" body2="mcp_joint_2"/>
<exclude body1="palm_lower" body2="mcp_joint_3"/>
<exclude body1="palm_lower" body2="thumb_dip"/>
<exclude body1="palm_lower" body2="thumb_pip"/>
<exclude body1="palm_lower" body2="pip_4"/>
<exclude body1="mcp_joint" body2="dip"/>
<exclude body1="mcp_joint_3" body2="dip_3"/>
<exclude body1="mcp_joint_2" body2="dip_2"/>
</contact>

<actuator>
<position class="left_leap" name="1" joint="1"/>
<position class="left_leap" name="0" joint="0"/>
<position class="left_leap" name="2" joint="2"/>
<position class="left_leap" name="3" joint="3"/>
<position class="left_leap" name="5" joint="5"/>
<position class="left_leap" name="4" joint="4"/>
<position class="left_leap" name="6" joint="6"/>
<position class="left_leap" name="7" joint="7"/>
<position class="left_leap" name="9" joint="9"/>
<position class="left_leap" name="8" joint="8"/>
<position class="left_leap" name="10" joint="10"/>
<position class="left_leap" name="11" joint="11"/>
<position class="left_leap" name="12" joint="12"/>
<position class="left_leap" name="13" joint="13"/>
<position class="left_leap" name="14" joint="14"/>
<position class="left_leap" name="15" joint="15"/>
</actuator>
</mujoco>
Loading
Loading