add h1_description

This commit is contained in:
matheecs 2023-12-07 11:26:48 +08:00
parent 69795ef9df
commit e197ae10d3
31 changed files with 1810 additions and 0 deletions

View File

@ -0,0 +1,13 @@
cmake_minimum_required(VERSION 2.8.3)
project(h1_description)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@ -0,0 +1,56 @@
# Unitree H1 Description (URDF & MJCF)
## Overview
This package includes a streamlined robot description (URDF & MJCF) for the [H1 Humanoid
Robot](https://www.unitree.com/h1), developed by [Unitree Robotics](https://www.unitree.com/).
<p align="center">
<img src="doc/H1.png" width="500"/>
</p>
H1 Humanoid have 19 joints:
```text
root [⚓] => /pelvis/
left_hip_yaw_joint [⚙+Z] => /left_hip_yaw_link/
left_hip_roll_joint [⚙+X] => /left_hip_roll_link/
left_hip_pitch_joint [⚙+Y] => /left_hip_pitch_link/
left_knee_joint [⚙+Y] => /left_knee_link/
left_ankle_joint [⚙+Y] => /left_ankle_link/
right_hip_yaw_joint [⚙+Z] => /right_hip_yaw_link/
right_hip_roll_joint [⚙+X] => /right_hip_roll_link/
right_hip_pitch_joint [⚙+Y] => /right_hip_pitch_link/
right_knee_joint [⚙+Y] => /right_knee_link/
right_ankle_joint [⚙+Y] => /right_ankle_link/
torso_joint [⚙+Z] => /torso_link/
left_shoulder_pitch_joint [⚙+Y] => /left_shoulder_pitch_link/
left_shoulder_roll_joint [⚙+X] => /left_shoulder_roll_link/
left_shoulder_yaw_joint [⚙+Z] => /left_shoulder_yaw_link/
left_elbow_joint [⚙+Y] => /left_elbow_link/
right_shoulder_pitch_joint [⚙+Y] => /right_shoulder_pitch_link/
right_shoulder_roll_joint [⚙+X] => /right_shoulder_roll_link/
right_shoulder_yaw_joint [⚙+Z] => /right_shoulder_yaw_link/
right_elbow_joint [⚙+Y] => /right_elbow_link/
```
## Usages
### [MuJoCo](https://github.com/google-deepmind/mujoco)(recommend)
```bash
pip install mujoco
python -m mujoco.viewer --mjcf=mjcf/scene.xml
```
### RViz
```bash
roslaunch h1_description display.launch
```
### Gazebo
```bash
roslaunch h1_description gazebo.launch
```

Binary file not shown.

After

Width:  |  Height:  |  Size: 843 KiB

View File

@ -0,0 +1,239 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 719
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
pelvis:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
hip_rotation_link_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
hip_abduction_link_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
hip_flexion_link_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
knee_link_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ankle_link_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Link Tree Style: Links in Alphabetic Order
hip_rotation_link_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
hip_abduction_link_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
hip_flexion_link_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
knee_link_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ankle_link_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
pelvis:
Value: true
hip_rotation_link_left:
Value: true
hip_abduction_link_left:
Value: true
hip_flexion_link_left:
Value: true
knee_link_left:
Value: true
ankle_link_left:
Value: true
hip_rotation_link_right:
Value: true
hip_abduction_link_right:
Value: true
hip_flexion_link_right:
Value: true
knee_link_right:
Value: true
ankle_link_right:
Value: true
Marker Alpha: 1
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
pelvis:
hip_rotation_link_left:
hip_abduction_link_left:
hip_flexion_link_left:
knee_link_left:
ankle_link_left:
{}
hip_rotation_link_right:
hip_abduction_link_right:
hip_flexion_link_right:
knee_link_right:
ankle_link_right:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: pelvis
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 1.6701574325561523
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0.11145864427089691
Y: 0.10033124685287476
Z: -0.35909000039100647
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.5303982496261597
Target Frame: <Fixed Frame>
Yaw: 0.8653979301452637
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1016
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001560000035afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000035afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000035a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000074c0000003efc0100000002fb0000000800540069006d006501000000000000074c000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000004db0000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1868
X: 52
Y: 27

View File

@ -0,0 +1,20 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find h1_description)/urdf/h1.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find h1_description)/launch/check_joint.rviz" />
</launch>

View File

@ -0,0 +1,12 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="paused" value="true" />
</include>
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find h1_description)/urdf/h1.urdf -urdf -z 1.05 -model h1_description"
output="screen" />
</launch>

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.

View File

@ -0,0 +1,228 @@
<mujoco model="h1">
<compiler angle="radian" meshdir="../meshes" 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>
<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_joint" 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_joint" 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_joint" 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_joint" 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.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
diaginertia="0.00362 0.00355701 0.000149987"/>
<joint name="left_ankle_joint" 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_joint" 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_joint" 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_joint" 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_joint" 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.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
diaginertia="0.00362 0.00355701 0.000149987"/>
<joint name="right_ankle_joint" 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_joint" 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_joint" 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_joint" 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_joint" 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_joint" 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_joint" 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_joint" 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_joint" 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_joint" 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" joint="left_hip_yaw_joint" ctrlrange="-200 200"/>
<motor class="h1" name="left_hip_roll_joint" joint="left_hip_roll_joint" ctrlrange="-200 200"/>
<motor class="h1" name="left_hip_pitch_joint" joint="left_hip_pitch_joint" ctrlrange="-200 200"/>
<motor class="h1" name="left_knee_joint" joint="left_knee_joint" ctrlrange="-300 300"/>
<motor class="h1" name="left_ankle_joint" joint="left_ankle_joint" ctrlrange="-40 40"/>
<motor class="h1" name="right_hip_yaw_joint" joint="right_hip_yaw_joint" ctrlrange="-200 200"/>
<motor class="h1" name="right_hip_roll_joint" joint="right_hip_roll_joint" ctrlrange="-200 200"/>
<motor class="h1" name="right_hip_pitch_joint" joint="right_hip_pitch_joint" ctrlrange="-200 200"/>
<motor class="h1" name="right_knee_joint" joint="right_knee_joint" ctrlrange="-300 300"/>
<motor class="h1" name="right_ankle_joint" joint="right_ankle_joint" ctrlrange="-40 40"/>
<motor class="h1" name="torso_joint" joint="torso_joint" ctrlrange="-200 200"/>
<motor class="h1" name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint" ctrlrange="-40 40"/>
<motor class="h1" name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint" ctrlrange="-40 40"/>
<motor class="h1" name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint" ctrlrange="-18 18"/>
<motor class="h1" name="left_elbow_joint" joint="left_elbow_joint" ctrlrange="-18 18"/>
<motor class="h1" name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint" ctrlrange="-40 40"/>
<motor class="h1" name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint" ctrlrange="-40 40"/>
<motor class="h1" name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint" ctrlrange="-18 18"/>
<motor class="h1" name="right_elbow_joint" joint="right_elbow_joint" ctrlrange="-18 18"/>
</actuator>
<sensor>
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
</sensor>
<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>

View File

@ -0,0 +1,20 @@
<mujoco model="Unitree H1">
<include file="h1.xml" />
<statistic center="1 0.7 1.5" extent="0.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="-140" elevation="-30" />
</visual>
<asset>
<texture type="skybox" builtin="flat" rgb1="0 0 0" 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 1.5" dir="0 0 -1" directional="true" />
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane" />
</worldbody>
</mujoco>

View File

@ -0,0 +1,17 @@
<?xml version="1.0"?>
<package format="2">
<name>h1_description</name>
<version>1.0.0</version>
<description>The Unitree H1 Description Package</description>
<maintainer email="TODO@email.com" />
<license>TODO</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
</package>

File diff suppressed because it is too large Load Diff