-
Notifications
You must be signed in to change notification settings - Fork 234
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
PiperOrigin-RevId: 579929828 Change-Id: I4f7ee0464b14acae066367fc075544ec2f0dacd7
- Loading branch information
1 parent
cbbc575
commit 56c951b
Showing
28 changed files
with
340 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,27 @@ | ||
Copyright (c) 2016-2023 HangZhou YuShu TECHNOLOGY CO.,LTD. ("Unitree Robotics") | ||
All rights reserved. | ||
|
||
Redistribution and use in source and binary forms, with or without | ||
modification, are permitted provided that the following conditions are met: | ||
|
||
* Redistributions of source code must retain the above copyright notice, this | ||
list of conditions and the following disclaimer. | ||
|
||
* Redistributions in binary form must reproduce the above copyright notice, | ||
this list of conditions and the following disclaimer in the documentation | ||
and/or other materials provided with the distribution. | ||
|
||
* Neither the name of the copyright holder nor the names of its | ||
contributors may be used to endorse or promote products derived from | ||
this software without specific prior written permission. | ||
|
||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE | ||
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE | ||
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL | ||
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR | ||
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER | ||
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, | ||
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE | ||
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,28 @@ | ||
# Unitree H1 Description (MJCF) | ||
|
||
Requires MuJoCo 2.2.2 or later. | ||
|
||
## Overview | ||
|
||
This package contains a simplified robot description (MJCF) of the [H1 Humanoid | ||
Robot](https://www.unitree.com/h1/) developed by [Unitree | ||
Robotics](https://www.unitree.com/). The original URDF and assets were provided | ||
directly by [Unitree Robotics](https://www.unitree.com/) under a [BSD-3-Clause | ||
License](LICENSE). | ||
|
||
<p float="left"> | ||
<img src="h1.png" width="400"> | ||
</p> | ||
|
||
## URDF → MJCF derivation steps | ||
|
||
1. Added `<mujoco> <compiler discardvisual="false" strippath="false" fusestatic="false"/> </mujoco>` to the URDF's | ||
`<robot>` clause in order to preserve visual geometries. | ||
2. Loaded the URDF into MuJoCo and saved a corresponding MJCF. | ||
3. Manually edited the MJCF to extract common properties into the `<default>` section. | ||
4. Added actuators. | ||
5. Added `scene.xml` which includes the robot, with a textured groundplane, skybox, and haze. | ||
|
||
## License | ||
|
||
This model is released under a [BSD-3-Clause License](LICENSE). |
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,227 @@ | ||
<mujoco model="h1"> | ||
<compiler angle="radian" meshdir="assets" autolimits="true"/> | ||
|
||
<default> | ||
<default class="h1"> | ||
<geom type="mesh"/> | ||
<joint damping="1" armature="0.1"/> | ||
<default class="visual"> | ||
<geom contype="0" conaffinity="0" group="2" material="black"/> | ||
</default> | ||
<default class="collision"> | ||
<geom group="3" mass="0" density="0"/> | ||
</default> | ||
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/> | ||
</default> | ||
</default> | ||
|
||
<asset> | ||
<material name="black" rgba="0.1 0.1 0.1 1"/> | ||
<material name="white" rgba="1 1 1 1"/> | ||
|
||
<mesh file="pelvis.stl"/> | ||
<mesh file="left_hip_yaw_link.stl"/> | ||
<mesh file="left_hip_roll_link.stl"/> | ||
<mesh file="left_hip_pitch_link.stl"/> | ||
<mesh file="left_knee_link.stl"/> | ||
<mesh file="left_ankle_link.stl"/> | ||
<mesh file="right_hip_yaw_link.stl"/> | ||
<mesh file="right_hip_roll_link.stl"/> | ||
<mesh file="right_hip_pitch_link.stl"/> | ||
<mesh file="right_knee_link.stl"/> | ||
<mesh file="right_ankle_link.stl"/> | ||
<mesh file="torso_link.stl"/> | ||
<mesh file="left_shoulder_pitch_link.stl"/> | ||
<mesh file="left_shoulder_roll_link.stl"/> | ||
<mesh file="left_shoulder_yaw_link.stl"/> | ||
<mesh file="left_elbow_link.stl"/> | ||
<mesh file="right_shoulder_pitch_link.stl"/> | ||
<mesh file="right_shoulder_roll_link.stl"/> | ||
<mesh file="right_shoulder_yaw_link.stl"/> | ||
<mesh file="right_elbow_link.stl"/> | ||
<mesh file="logo_link.stl"/> | ||
</asset> | ||
|
||
<worldbody> | ||
<light mode="targetbodycom" target="torso_link" pos="1 0 2.5"/> | ||
<body name="pelvis" pos="0 0 1.1" childclass="h1"> | ||
<inertial pos="-0.0002 4e-05 -0.04522" quat="0.498303 0.499454 -0.500496 0.501741" mass="5.39" | ||
diaginertia="0.0490211 0.0445821 0.00824619"/> | ||
<freejoint/> | ||
<geom class="visual" mesh="pelvis"/> | ||
<geom class="collision" mesh="pelvis"/> | ||
<body name="left_hip_yaw_link" pos="0 0.0875 -0.1742"> | ||
<inertial pos="-0.04923 0.0001 0.0072" quat="0.69699 0.219193 0.233287 0.641667" mass="2.244" | ||
diaginertia="0.00304494 0.00296885 0.00189201"/> | ||
<joint name="left_hip_yaw" axis="0 0 1" range="-0.43 0.43"/> | ||
<geom class="visual" mesh="left_hip_yaw_link"/> | ||
<geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | ||
<body name="left_hip_roll_link" pos="0.039468 0 0"> | ||
<inertial pos="-0.0058 -0.00319 -9e-05" quat="0.0438242 0.70721 -0.0729075 0.701867" mass="2.232" | ||
diaginertia="0.00243264 0.00225325 0.00205492"/> | ||
<joint name="left_hip_roll" axis="1 0 0" range="-0.43 0.43"/> | ||
<geom class="visual" mesh="left_hip_roll_link"/> | ||
<geom class="collision" mesh="left_hip_roll_link"/> | ||
<body name="left_hip_pitch_link" pos="0 0.11536 0"> | ||
<inertial pos="0.00746 -0.02346 -0.08193" quat="0.979828 0.0513522 -0.0169854 -0.192382" mass="4.152" | ||
diaginertia="0.0829503 0.0821457 0.00510909"/> | ||
<joint name="left_hip_pitch" axis="0 1 0" range="-1.57 1.57"/> | ||
<geom class="visual" mesh="left_hip_pitch_link"/> | ||
<geom class="collision" mesh="left_hip_pitch_link"/> | ||
<body name="left_knee_link" pos="0 0 -0.4"> | ||
<inertial pos="-0.00136 -0.00512 -0.1384" quat="0.626132 -0.034227 -0.0416277 0.777852" mass="1.721" | ||
diaginertia="0.0125237 0.0123104 0.0019428"/> | ||
<joint name="left_knee" axis="0 1 0" range="-0.26 2.05"/> | ||
<geom class="visual" mesh="left_knee_link"/> | ||
<geom class="collision" mesh="left_knee_link"/> | ||
<body name="left_ankle_link" pos="0 0 -0.4"> | ||
<inertial pos="0.06722 0.00015 -0.04497" quat="0.489101 0.503197 0.565782 0.432972" mass="0.446" | ||
diaginertia="0.00220848 0.00218961 0.000214202"/> | ||
<joint name="left_ankle" axis="0 1 0" range="-0.87 0.52"/> | ||
<geom class="visual" mesh="left_ankle_link"/> | ||
<geom class="collision" mesh="left_ankle_link"/> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
<body name="right_hip_yaw_link" pos="0 -0.0875 -0.1742"> | ||
<inertial pos="-0.04923 -0.0001 0.0072" quat="0.641667 0.233287 0.219193 0.69699" mass="2.244" | ||
diaginertia="0.00304494 0.00296885 0.00189201"/> | ||
<joint name="right_hip_yaw" axis="0 0 1" range="-0.43 0.43"/> | ||
<geom class="visual" mesh="right_hip_yaw_link"/> | ||
<geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | ||
<body name="right_hip_roll_link" pos="0.039468 0 0"> | ||
<inertial pos="-0.0058 0.00319 -9e-05" quat="-0.0438242 0.70721 0.0729075 0.701867" mass="2.232" | ||
diaginertia="0.00243264 0.00225325 0.00205492"/> | ||
<joint name="right_hip_roll" axis="1 0 0" range="-0.43 0.43"/> | ||
<geom class="visual" mesh="right_hip_roll_link"/> | ||
<geom class="collision" mesh="right_hip_roll_link"/> | ||
<body name="right_hip_pitch_link" pos="0 -0.11536 0"> | ||
<inertial pos="0.00746 0.02346 -0.08193" quat="0.979828 -0.0513522 -0.0169854 0.192382" mass="4.152" | ||
diaginertia="0.0829503 0.0821457 0.00510909"/> | ||
<joint name="right_hip_pitch" axis="0 1 0" range="-1.57 1.57"/> | ||
<geom class="visual" mesh="right_hip_pitch_link"/> | ||
<geom class="collision" mesh="right_hip_pitch_link"/> | ||
<body name="right_knee_link" pos="0 0 -0.4"> | ||
<inertial pos="-0.00136 0.00512 -0.1384" quat="0.777852 -0.0416277 -0.034227 0.626132" mass="1.721" | ||
diaginertia="0.0125237 0.0123104 0.0019428"/> | ||
<joint name="right_knee" axis="0 1 0" range="-0.26 2.05"/> | ||
<geom class="visual" mesh="right_knee_link"/> | ||
<geom class="collision" mesh="right_knee_link"/> | ||
<body name="right_ankle_link" pos="0 0 -0.4"> | ||
<inertial pos="0.06722 -0.00015 -0.04497" quat="0.432972 0.565782 0.503197 0.489101" mass="0.446" | ||
diaginertia="0.00220848 0.00218961 0.000214202"/> | ||
<joint name="right_ankle" axis="0 1 0" range="-0.87 0.52"/> | ||
<geom class="visual" mesh="right_ankle_link"/> | ||
<geom class="collision" mesh="right_ankle_link"/> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
<body name="torso_link"> | ||
<inertial pos="0.000489 0.002797 0.20484" quat="0.999989 -0.00130808 -0.00282289 -0.00349105" mass="17.789" | ||
diaginertia="0.487315 0.409628 0.127837"/> | ||
<joint name="torso" axis="0 0 1" range="-2.35 2.35"/> | ||
<geom class="visual" mesh="torso_link"/> | ||
<geom class="collision" mesh="torso_link"/> | ||
<geom class="visual" material="white" mesh="logo_link"/> | ||
<site name="imu" size="0.01" pos="-0.04452 -0.01891 0.27756"/> | ||
<body name="left_shoulder_pitch_link" pos="0.0055 0.15535 0.42999" quat="0.976296 0.216438 0 0"> | ||
<inertial pos="0.005045 0.053657 -0.015715" quat="0.814858 0.579236 -0.0201072 -0.00936488" mass="1.033" | ||
diaginertia="0.00129936 0.000987113 0.000858198"/> | ||
<joint name="left_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/> | ||
<geom class="visual" mesh="left_shoulder_pitch_link"/> | ||
<geom class="collision" mesh="left_shoulder_pitch_link"/> | ||
<body name="left_shoulder_roll_link" pos="-0.0055 0.0565 -0.0165" quat="0.976296 -0.216438 0 0"> | ||
<inertial pos="0.000679 0.00115 -0.094076" quat="0.732491 0.00917179 0.0766656 0.676384" mass="0.793" | ||
diaginertia="0.00170388 0.00158256 0.00100336"/> | ||
<joint name="left_shoulder_roll" axis="1 0 0" range="-0.34 3.11"/> | ||
<geom class="visual" mesh="left_shoulder_roll_link"/> | ||
<geom class="collision" mesh="left_shoulder_roll_link"/> | ||
<body name="left_shoulder_yaw_link" pos="0 0 -0.1343"> | ||
<inertial pos="0.01365 0.002767 -0.16266" quat="0.703042 -0.0331229 -0.0473362 0.708798" mass="0.839" | ||
diaginertia="0.00408038 0.00370367 0.000622687"/> | ||
<joint name="left_shoulder_yaw" axis="0 0 1" range="-1.3 4.45"/> | ||
<geom class="visual" mesh="left_shoulder_yaw_link"/> | ||
<geom class="collision" mesh="left_shoulder_yaw_link"/> | ||
<body name="left_elbow_link" pos="0.0185 0 -0.198"> | ||
<inertial pos="0.15908 -0.000144 -0.015776" quat="0.0765232 0.720327 0.0853116 0.684102" mass="0.669" | ||
diaginertia="0.00601829 0.00600579 0.000408305"/> | ||
<joint name="left_elbow" axis="0 1 0" range="-1.25 2.61"/> | ||
<geom class="visual" mesh="left_elbow_link"/> | ||
<geom class="collision" mesh="left_elbow_link"/> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
<body name="right_shoulder_pitch_link" pos="0.0055 -0.15535 0.42999" quat="0.976296 -0.216438 0 0"> | ||
<inertial pos="0.005045 -0.053657 -0.015715" quat="0.579236 0.814858 0.00936488 0.0201072" mass="1.033" | ||
diaginertia="0.00129936 0.000987113 0.000858198"/> | ||
<joint name="right_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/> | ||
<geom class="visual" mesh="right_shoulder_pitch_link"/> | ||
<geom class="collision" mesh="right_shoulder_pitch_link"/> | ||
<body name="right_shoulder_roll_link" pos="-0.0055 -0.0565 -0.0165" quat="0.976296 0.216438 0 0"> | ||
<inertial pos="0.000679 -0.00115 -0.094076" quat="0.676384 0.0766656 0.00917179 0.732491" mass="0.793" | ||
diaginertia="0.00170388 0.00158256 0.00100336"/> | ||
<joint name="right_shoulder_roll" axis="1 0 0" range="-3.11 0.34"/> | ||
<geom class="visual" mesh="right_shoulder_roll_link"/> | ||
<geom class="collision" mesh="right_shoulder_roll_link"/> | ||
<body name="right_shoulder_yaw_link" pos="0 0 -0.1343"> | ||
<inertial pos="0.01365 -0.002767 -0.16266" quat="0.708798 -0.0473362 -0.0331229 0.703042" mass="0.839" | ||
diaginertia="0.00408038 0.00370367 0.000622687"/> | ||
<joint name="right_shoulder_yaw" axis="0 0 1" range="-4.45 1.3"/> | ||
<geom class="visual" mesh="right_shoulder_yaw_link"/> | ||
<geom class="collision" mesh="right_shoulder_yaw_link"/> | ||
<body name="right_elbow_link" pos="0.0185 0 -0.198"> | ||
<inertial pos="0.15908 0.000144 -0.015776" quat="-0.0765232 0.720327 -0.0853116 0.684102" mass="0.669" | ||
diaginertia="0.00601829 0.00600579 0.000408305"/> | ||
<joint name="right_elbow" axis="0 1 0" range="-1.25 2.61"/> | ||
<geom class="visual" mesh="right_elbow_link"/> | ||
<geom class="collision" mesh="right_elbow_link"/> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</worldbody> | ||
|
||
<actuator> | ||
<motor class="h1" name="left_hip_yaw" joint="left_hip_yaw" ctrlrange="-0.43 0.43" forcerange="-200 200"/> | ||
<motor class="h1" name="left_hip_roll" joint="left_hip_roll" ctrlrange="-0.43 0.43" forcerange="-200 200"/> | ||
<motor class="h1" name="left_hip_pitch" joint="left_hip_pitch" ctrlrange="-1.57 1.57" forcerange="-200 200"/> | ||
<motor class="h1" name="left_knee" joint="left_knee" ctrlrange="-0.26 2.05" forcerange="-300 300"/> | ||
<motor class="h1" name="left_ankle" joint="left_ankle" ctrlrange="-0.87 0.52" forcerange="-40 40"/> | ||
<motor class="h1" name="right_hip_yaw" joint="right_hip_yaw" ctrlrange="-0.43 0.43" forcerange="-200 200"/> | ||
<motor class="h1" name="right_hip_roll" joint="right_hip_roll" ctrlrange="-0.43 0.43" forcerange="-200 200"/> | ||
<motor class="h1" name="right_hip_pitch" joint="right_hip_pitch" ctrlrange="-1.57 1.57" forcerange="-200 200"/> | ||
<motor class="h1" name="right_knee" joint="right_knee" ctrlrange="-0.26 2.05" forcerange="-300 300"/> | ||
<motor class="h1" name="right_ankle" joint="right_ankle" ctrlrange="-0.87 0.52" forcerange="-40 40"/> | ||
<motor class="h1" name="torso" joint="torso" ctrlrange="-2.35 2.35" forcerange="-200 200"/> | ||
<motor class="h1" name="left_shoulder_pitch" joint="left_shoulder_pitch" ctrlrange="-2.87 2.87" | ||
forcerange="-40 40"/> | ||
<motor class="h1" name="left_shoulder_roll" joint="left_shoulder_roll" ctrlrange="-0.34 3.11" forcerange="-40 40"/> | ||
<motor class="h1" name="left_shoulder_yaw" joint="left_shoulder_yaw" ctrlrange="-1.3 4.45" forcerange="-18 18"/> | ||
<motor class="h1" name="left_elbow" joint="left_elbow" ctrlrange="-1.25 2.61" forcerange="-18 18"/> | ||
<motor class="h1" name="right_shoulder_pitch" joint="right_shoulder_pitch" ctrlrange="-2.87 2.87" | ||
forcerange="-40 40"/> | ||
<motor class="h1" name="right_shoulder_roll" joint="right_shoulder_roll" ctrlrange="-3.11 0.34" | ||
forcerange="-40 40"/> | ||
<motor class="h1" name="right_shoulder_yaw" joint="right_shoulder_yaw" ctrlrange="-4.45 1.3" forcerange="-18 18"/> | ||
<motor class="h1" name="right_elbow" joint="right_elbow" ctrlrange="-1.25 2.61" forcerange="-18 18"/> | ||
</actuator> | ||
|
||
<keyframe> | ||
<key name="home" | ||
qpos=" | ||
0 0 0.98 | ||
1 0 0 0 | ||
0 0 -0.4 0.8 -0.4 | ||
0 0 -0.4 0.8 -0.4 | ||
0 | ||
0 0 0 0 | ||
0 0 0 0"/> | ||
</keyframe> | ||
</mujoco> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,23 @@ | ||
<mujoco model="h1 scene"> | ||
<include file="h1.xml"/> | ||
|
||
<statistic center="0 0 1" extent="1.8"/> | ||
|
||
<visual> | ||
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/> | ||
<rgba haze="0.15 0.25 0.35 1"/> | ||
<global azimuth="160" elevation="-20"/> | ||
</visual> | ||
|
||
<asset> | ||
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/> | ||
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" | ||
markrgb="0.8 0.8 0.8" width="300" height="300"/> | ||
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/> | ||
</asset> | ||
|
||
<worldbody> | ||
<light pos="0 0 3.5" dir="0 0 -1" directional="true"/> | ||
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/> | ||
</worldbody> | ||
</mujoco> |