Browse Source

g1(7 DoF arm) IK test.

main
silencht 2 years ago
parent
commit
68549a7920
  1. 2
      assets/g1/.gitignore
  2. 72
      assets/g1/README.md
  3. 1420
      assets/g1/g1_body29_hand14.urdf
  4. 401
      assets/g1/g1_body29_hand14.xml
  5. BIN
      assets/g1/meshes/head_link.STL
  6. BIN
      assets/g1/meshes/left_ankle_pitch_link.STL
  7. BIN
      assets/g1/meshes/left_ankle_roll_link.STL
  8. BIN
      assets/g1/meshes/left_elbow_link.STL
  9. BIN
      assets/g1/meshes/left_hand_five_link.STL
  10. BIN
      assets/g1/meshes/left_hand_four_link.STL
  11. BIN
      assets/g1/meshes/left_hand_one_link.STL
  12. BIN
      assets/g1/meshes/left_hand_palm_link.STL
  13. BIN
      assets/g1/meshes/left_hand_six_link.STL
  14. BIN
      assets/g1/meshes/left_hand_three_link.STL
  15. BIN
      assets/g1/meshes/left_hand_two_link.STL
  16. BIN
      assets/g1/meshes/left_hand_zero_link.STL
  17. BIN
      assets/g1/meshes/left_hip_pitch_link.STL
  18. BIN
      assets/g1/meshes/left_hip_roll_link.STL
  19. BIN
      assets/g1/meshes/left_hip_yaw_link.STL
  20. BIN
      assets/g1/meshes/left_knee_link.STL
  21. BIN
      assets/g1/meshes/left_shoulder_pitch_link.STL
  22. BIN
      assets/g1/meshes/left_shoulder_roll_link.STL
  23. BIN
      assets/g1/meshes/left_shoulder_yaw_link.STL
  24. BIN
      assets/g1/meshes/left_wrist_pitch_link.STL
  25. BIN
      assets/g1/meshes/left_wrist_roll_link.STL
  26. BIN
      assets/g1/meshes/left_wrist_yaw_link.STL
  27. BIN
      assets/g1/meshes/logo_link.STL
  28. BIN
      assets/g1/meshes/pelvis.STL
  29. BIN
      assets/g1/meshes/right_ankle_pitch_link.STL
  30. BIN
      assets/g1/meshes/right_ankle_roll_link.STL
  31. BIN
      assets/g1/meshes/right_elbow_link.STL
  32. BIN
      assets/g1/meshes/right_hand_five_link.STL
  33. BIN
      assets/g1/meshes/right_hand_four_link.STL
  34. BIN
      assets/g1/meshes/right_hand_one_link.STL
  35. BIN
      assets/g1/meshes/right_hand_palm_link.STL
  36. BIN
      assets/g1/meshes/right_hand_six_link.STL
  37. BIN
      assets/g1/meshes/right_hand_three_link.STL
  38. BIN
      assets/g1/meshes/right_hand_two_link.STL
  39. BIN
      assets/g1/meshes/right_hand_zero_link.STL
  40. BIN
      assets/g1/meshes/right_hip_pitch_link.STL
  41. BIN
      assets/g1/meshes/right_hip_roll_link.STL
  42. BIN
      assets/g1/meshes/right_hip_yaw_link.STL
  43. BIN
      assets/g1/meshes/right_knee_link.STL
  44. BIN
      assets/g1/meshes/right_shoulder_pitch_link.STL
  45. BIN
      assets/g1/meshes/right_shoulder_roll_link.STL
  46. BIN
      assets/g1/meshes/right_shoulder_yaw_link.STL
  47. BIN
      assets/g1/meshes/right_wrist_pitch_link.STL
  48. BIN
      assets/g1/meshes/right_wrist_roll_link.STL
  49. BIN
      assets/g1/meshes/right_wrist_yaw_link.STL
  50. BIN
      assets/g1/meshes/torso_constraint_L_link.STL
  51. BIN
      assets/g1/meshes/torso_constraint_L_rod_link.STL
  52. BIN
      assets/g1/meshes/torso_constraint_R_link.STL
  53. BIN
      assets/g1/meshes/torso_constraint_R_rod_link.STL
  54. BIN
      assets/g1/meshes/torso_link.STL
  55. BIN
      assets/g1/meshes/waist_constraint_L.STL
  56. BIN
      assets/g1/meshes/waist_constraint_R.STL
  57. BIN
      assets/g1/meshes/waist_roll_link.STL
  58. BIN
      assets/g1/meshes/waist_support_link.STL
  59. BIN
      assets/g1/meshes/waist_yaw_link.STL
  60. 13
      assets/h1_description/CMakeLists.txt
  61. 58
      assets/h1_description/README.md
  62. 239
      assets/h1_description/launch/check_joint.rviz
  63. 20
      assets/h1_description/launch/display.launch
  64. 12
      assets/h1_description/launch/gazebo.launch
  65. BIN
      assets/h1_description/meshes/L_hand_base_link.STL
  66. 89
      assets/h1_description/meshes/L_hand_base_link.dae
  67. BIN
      assets/h1_description/meshes/Link11_L.STL
  68. 89
      assets/h1_description/meshes/Link11_L.dae
  69. BIN
      assets/h1_description/meshes/Link11_R.STL
  70. 89
      assets/h1_description/meshes/Link11_R.dae
  71. BIN
      assets/h1_description/meshes/Link12_L.STL
  72. 89
      assets/h1_description/meshes/Link12_L.dae
  73. BIN
      assets/h1_description/meshes/Link12_R.STL
  74. 89
      assets/h1_description/meshes/Link12_R.dae
  75. BIN
      assets/h1_description/meshes/Link13_L.STL
  76. 89
      assets/h1_description/meshes/Link13_L.dae
  77. BIN
      assets/h1_description/meshes/Link13_R.STL
  78. 89
      assets/h1_description/meshes/Link13_R.dae
  79. BIN
      assets/h1_description/meshes/Link14_L.STL
  80. 89
      assets/h1_description/meshes/Link14_L.dae
  81. BIN
      assets/h1_description/meshes/Link14_R.STL
  82. 89
      assets/h1_description/meshes/Link14_R.dae
  83. BIN
      assets/h1_description/meshes/Link15_L.STL
  84. 89
      assets/h1_description/meshes/Link15_L.dae
  85. BIN
      assets/h1_description/meshes/Link15_R.STL
  86. 89
      assets/h1_description/meshes/Link15_R.dae
  87. BIN
      assets/h1_description/meshes/Link16_L.STL
  88. 89
      assets/h1_description/meshes/Link16_L.dae
  89. BIN
      assets/h1_description/meshes/Link16_R.STL
  90. 89
      assets/h1_description/meshes/Link16_R.dae
  91. BIN
      assets/h1_description/meshes/Link17_L.STL
  92. 89
      assets/h1_description/meshes/Link17_L.dae
  93. BIN
      assets/h1_description/meshes/Link17_R.STL
  94. 89
      assets/h1_description/meshes/Link17_R.dae
  95. BIN
      assets/h1_description/meshes/Link18_L.STL
  96. 89
      assets/h1_description/meshes/Link18_L.dae
  97. BIN
      assets/h1_description/meshes/Link18_R.STL
  98. 89
      assets/h1_description/meshes/Link18_R.dae
  99. BIN
      assets/h1_description/meshes/Link19_L.STL
  100. 89
      assets/h1_description/meshes/Link19_L.dae

2
assets/g1/.gitignore

@ -0,0 +1,2 @@
*.gv
*.pdf

72
assets/g1/README.md

@ -0,0 +1,72 @@
# Unitree G1 Description (URDF & MJCF)
## Overview
This package includes a streamlined robot description (URDF & MJCF) for the [Unitree G1](https://www.unitree.com/g1/), developed by [Unitree Robotics](https://www.unitree.com/).
<p align="center"><img src="g1.png" width="500"/></p>
Unitree G1 have 43 DOFs:
```text
root [⚓] => /pelvis/
left_hip_pitch_joint [⚙+Y] => /left_hip_pitch_link/
left_hip_roll_joint [⚙+X] => /left_hip_roll_link/
left_hip_yaw_joint [⚙+Z] => /left_hip_yaw_link/
left_knee_joint [⚙+Y] => /left_knee_link/
left_ankle_pitch_joint [⚙+Y] => /left_ankle_pitch_link/
left_ankle_roll_joint [⚙+X] => /left_ankle_roll_link/
right_hip_pitch_joint [⚙+Y] => /right_hip_pitch_link/
right_hip_roll_joint [⚙+X] => /right_hip_roll_link/
right_hip_yaw_joint [⚙+Z] => /right_hip_yaw_link/
right_knee_joint [⚙+Y] => /right_knee_link/
right_ankle_pitch_joint [⚙+Y] => /right_ankle_pitch_link/
right_ankle_roll_joint [⚙+X] => /right_ankle_roll_link/
waist_yaw_joint [⚙+Z] => /waist_yaw_link/
waist_roll_joint [⚙+X] => /waist_roll_link/
waist_pitch_joint [⚙+Y] => /torso_link/
logo_joint [⚓] => /logo_link/
head_joint [⚓] => /head_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/
left_wrist_roll_joint [⚙+X] => /left_wrist_roll_link/
left_wrist_pitch_joint [⚙+Y] => /left_wrist_pitch_link/
left_wrist_yaw_joint [⚙+Z] => /left_wrist_yaw_link/
left_hand_palm_joint [⚓] => /left_hand_palm_link/
left_hand_zero_joint [⚙+Y] => /left_hand_zero_link/
left_hand_one_joint [⚙+Z] => /left_hand_one_link/
left_hand_two_joint [⚙+Z] => /left_hand_two_link/
left_hand_three_joint [⚙+Z] => /left_hand_three_link/
left_hand_four_joint [⚙+Z] => /left_hand_four_link/
left_hand_five_joint [⚙+Z] => /left_hand_five_link/
left_hand_six_joint [⚙+Z] => /left_hand_six_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/
right_wrist_roll_joint [⚙+X] => /right_wrist_roll_link/
right_wrist_pitch_joint [⚙+Y] => /right_wrist_pitch_link/
right_wrist_yaw_joint [⚙+Z] => /right_wrist_yaw_link/
right_hand_palm_joint [⚓] => /right_hand_palm_link/
right_hand_zero_joint [⚙+Y] => /right_hand_zero_link/
right_hand_one_joint [⚙+Z] => /right_hand_one_link/
right_hand_two_joint [⚙+Z] => /right_hand_two_link/
right_hand_three_joint [⚙+Z] => /right_hand_three_link/
right_hand_four_joint [⚙+Z] => /right_hand_four_link/
right_hand_five_joint [⚙+Z] => /right_hand_five_link/
right_hand_six_joint [⚙+Z] => /right_hand_six_link/
```
## Visulization with [MuJoCo](https://github.com/google-deepmind/mujoco)
1. Open MuJoCo Viewer
```bash
pip install mujoco
python -m mujoco.viewer
```
2. Drag and drop the MJCF/URDF model file (`g1_body29_hand14.xml`/`g1_body29_hand14.urdf`) to the MuJoCo Viewer.

1420
assets/g1/g1_body29_hand14.urdf
File diff suppressed because it is too large
View File

401
assets/g1/g1_body29_hand14.xml

@ -0,0 +1,401 @@
<mujoco model="g1">
<compiler angle="radian" meshdir="meshes"/>
<asset>
<mesh name="pelvis" file="pelvis.STL"/>
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
<mesh name="left_knee_link" file="left_knee_link.STL"/>
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
<mesh name="right_knee_link" file="right_knee_link.STL"/>
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
<mesh name="torso_link" file="torso_link.STL"/>
<mesh name="logo_link" file="logo_link.STL"/>
<mesh name="head_link" file="head_link.STL"/>
<mesh name="waist_support_link" file="waist_support_link.STL"/>
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
<mesh name="left_hand_palm_link" file="left_hand_palm_link.STL"/>
<mesh name="left_hand_zero_link" file="left_hand_zero_link.STL"/>
<mesh name="left_hand_one_link" file="left_hand_one_link.STL"/>
<mesh name="left_hand_two_link" file="left_hand_two_link.STL"/>
<mesh name="left_hand_three_link" file="left_hand_three_link.STL"/>
<mesh name="left_hand_four_link" file="left_hand_four_link.STL"/>
<mesh name="left_hand_five_link" file="left_hand_five_link.STL"/>
<mesh name="left_hand_six_link" file="left_hand_six_link.STL"/>
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
<mesh name="right_hand_palm_link" file="right_hand_palm_link.STL"/>
<mesh name="right_hand_zero_link" file="right_hand_zero_link.STL"/>
<mesh name="right_hand_one_link" file="right_hand_one_link.STL"/>
<mesh name="right_hand_two_link" file="right_hand_two_link.STL"/>
<mesh name="right_hand_three_link" file="right_hand_three_link.STL"/>
<mesh name="right_hand_four_link" file="right_hand_four_link.STL"/>
<mesh name="right_hand_five_link" file="right_hand_five_link.STL"/>
<mesh name="right_hand_six_link" file="right_hand_six_link.STL"/>
</asset>
<worldbody>
<body name="pelvis" pos="0 0 0.793">
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis"/>
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="waist_yaw_link">
<inertial pos="0.003964 0 0.018769" quat="-0.0178291 0.628464 0.0282471 0.777121" mass="0.244" diaginertia="0.000158561 0.000124229 9.67669e-05"/>
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
<body name="waist_roll_link" pos="-0.0039635 0 0.035">
<inertial pos="0 -0.000236 0.010111" quat="0.99979 0.020492 0 0" mass="0.047" diaginertia="7.515e-06 6.40206e-06 3.98394e-06"/>
<joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
<body name="torso_link" pos="0 0 0.019">
<inertial pos="0.00331122 0.00027687 0.180534" quat="0.999833 0.000360976 0.0180196 -0.00292551" mass="9.7741" diaginertia="0.124509 0.112709 0.0332404"/>
<joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
<site name="imu" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
<body name="left_wrist_pitch_link" pos="0.038 0 0">
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
<body name="left_wrist_yaw_link" pos="0.046 0 0">
<inertial pos="0.0885506 0.00212216 -0.000374562" quat="0.487149 0.493844 0.513241 0.505358" mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
<body name="left_hand_zero_link" pos="0.0695 0.003 0">
<inertial pos="-0.000354413 -0.0132989 0.000412362" quat="0.385163 0.591021 -0.567321 0.424842" mass="0.0803302" diaginertia="1.39245e-05 1.32309e-05 1.19138e-05"/>
<joint name="left_hand_zero_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_zero_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_zero_link"/>
<body name="left_hand_one_link" pos="0 -0.0246 0">
<inertial pos="0.0036206 -0.040444 -0.000297711" quat="0.696371 0.699653 0.125539 -0.0989605" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="left_hand_one_joint" pos="0 0 0" axis="0 0 1" range="-0.724312 1.0472" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_one_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_one_link"/>
<body name="left_hand_two_link" pos="0.0055 -0.0528 0">
<inertial pos="-0.00081406 -0.0345621 0.000129799" quat="0.701976 0.711984 0.0160342 0.00721768" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="left_hand_two_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_two_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_two_link"/>
</body>
</body>
</body>
<body name="left_hand_three_link" pos="0.1415 0.0013 -0.0285">
<inertial pos="0.040444 -0.0036206 0.000287711" quat="0.583499 0.422433 0.562384 0.40596" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="left_hand_three_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_three_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_three_link"/>
<body name="left_hand_four_link" pos="0.0528 -0.0055 0">
<inertial pos="0.0345621 0.00081406 -0.000129799" quat="0.514787 0.501475 0.491268 0.492111" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="left_hand_four_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_four_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_four_link"/>
</body>
</body>
<body name="left_hand_five_link" pos="0.1415 0.0013 0.0285">
<inertial pos="0.040444 -0.0036206 0.000287711" quat="0.583499 0.422433 0.562384 0.40596" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="left_hand_five_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_five_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_five_link"/>
<body name="left_hand_six_link" pos="0.0528 -0.0055 0">
<inertial pos="0.0345621 0.00081406 -0.000129799" quat="0.514787 0.501475 0.491268 0.492111" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="left_hand_six_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_six_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_six_link"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
<body name="right_wrist_pitch_link" pos="0.038 0 0">
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
<body name="right_wrist_yaw_link" pos="0.046 0 0">
<inertial pos="0.0885506 -0.00212216 0.000573742" quat="0.507224 0.511377 0.494292 0.486717" mass="0.457415" diaginertia="0.0010598 0.000895373 0.0003238"/>
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
<body name="right_hand_zero_link" pos="0.0695 -0.003 0">
<inertial pos="-0.000354413 0.0132989 -0.000412362" quat="0.424842 0.567321 -0.591021 0.385163" mass="0.0803302" diaginertia="1.39245e-05 1.32309e-05 1.19138e-05"/>
<joint name="right_hand_zero_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_zero_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_zero_link"/>
<body name="right_hand_one_link" pos="0 0.0246 0">
<inertial pos="0.0036206 0.040444 0.000297711" quat="0.696371 0.699653 -0.125539 0.0989605" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="right_hand_one_joint" pos="0 0 0" axis="0 0 1" range="-1.0472 0.724312" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_one_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_one_link"/>
<body name="right_hand_two_link" pos="0.0055 0.0528 0">
<inertial pos="-0.00081406 0.0345621 -0.000129799" quat="0.701976 0.711984 -0.0160342 -0.00721768" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="right_hand_two_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_two_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_two_link"/>
</body>
</body>
</body>
<body name="right_hand_three_link" pos="0.1415 -0.0013 0.0285">
<inertial pos="0.040444 0.0036206 -0.000287711" quat="0.562384 0.40596 0.583499 0.422433" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="right_hand_three_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_three_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_three_link"/>
<body name="right_hand_four_link" pos="0.0528 0.0055 0">
<inertial pos="0.0345621 -0.00081406 0.000129799" quat="0.491268 0.492111 0.514787 0.501475" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="right_hand_four_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_four_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_four_link"/>
</body>
</body>
<body name="right_hand_five_link" pos="0.1415 -0.0013 -0.0285">
<inertial pos="0.040444 0.0036206 -0.000287711" quat="0.562384 0.40596 0.583499 0.422433" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="right_hand_five_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_five_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_five_link"/>
<body name="right_hand_six_link" pos="0.0528 0.0055 0">
<inertial pos="0.0345621 -0.00081406 0.000129799" quat="0.491268 0.492111 0.514787 0.501475" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="right_hand_six_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_six_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_six_link"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
<motor name="left_knee_joint" joint="left_knee_joint"/>
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
<motor name="right_knee_joint" joint="right_knee_joint"/>
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
<motor name="waist_roll_joint" joint="waist_roll_joint"/>
<motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
<motor name="left_hand_zero_joint" joint="left_hand_zero_joint"/>
<motor name="left_hand_one_joint" joint="left_hand_one_joint"/>
<motor name="left_hand_two_joint" joint="left_hand_two_joint"/>
<motor name="left_hand_three_joint" joint="left_hand_three_joint"/>
<motor name="left_hand_four_joint" joint="left_hand_four_joint"/>
<motor name="left_hand_five_joint" joint="left_hand_five_joint"/>
<motor name="left_hand_six_joint" joint="left_hand_six_joint"/>
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
<motor name="right_hand_zero_joint" joint="right_hand_zero_joint"/>
<motor name="right_hand_one_joint" joint="right_hand_one_joint"/>
<motor name="right_hand_two_joint" joint="right_hand_two_joint"/>
<motor name="right_hand_three_joint" joint="right_hand_three_joint"/>
<motor name="right_hand_four_joint" joint="right_hand_four_joint"/>
<motor name="right_hand_five_joint" joint="right_hand_five_joint"/>
<motor name="right_hand_six_joint" joint="right_hand_six_joint"/>
</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>
<!-- setup scene -->
<statistic center="1.0 0.7 1.0" extent="0.8"/>
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="-140" elevation="-20"/>
</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="1 0 3.5" dir="0 0 -1" directional="true" castshadow="false"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
</worldbody>
</mujoco>

BIN
assets/g1/meshes/head_link.STL

BIN
assets/g1/meshes/left_ankle_pitch_link.STL

BIN
assets/g1/meshes/left_ankle_roll_link.STL

BIN
assets/g1/meshes/left_elbow_link.STL

BIN
assets/g1/meshes/left_hand_five_link.STL

BIN
assets/g1/meshes/left_hand_four_link.STL

BIN
assets/g1/meshes/left_hand_one_link.STL

BIN
assets/g1/meshes/left_hand_palm_link.STL

BIN
assets/g1/meshes/left_hand_six_link.STL

BIN
assets/g1/meshes/left_hand_three_link.STL

BIN
assets/g1/meshes/left_hand_two_link.STL

BIN
assets/g1/meshes/left_hand_zero_link.STL

BIN
assets/g1/meshes/left_hip_pitch_link.STL

BIN
assets/g1/meshes/left_hip_roll_link.STL

BIN
assets/g1/meshes/left_hip_yaw_link.STL

BIN
assets/g1/meshes/left_knee_link.STL

BIN
assets/g1/meshes/left_shoulder_pitch_link.STL

BIN
assets/g1/meshes/left_shoulder_roll_link.STL

BIN
assets/g1/meshes/left_shoulder_yaw_link.STL

BIN
assets/g1/meshes/left_wrist_pitch_link.STL

BIN
assets/g1/meshes/left_wrist_roll_link.STL

BIN
assets/g1/meshes/left_wrist_yaw_link.STL

BIN
assets/g1/meshes/logo_link.STL

BIN
assets/g1/meshes/pelvis.STL

BIN
assets/g1/meshes/right_ankle_pitch_link.STL

BIN
assets/g1/meshes/right_ankle_roll_link.STL

BIN
assets/g1/meshes/right_elbow_link.STL

BIN
assets/g1/meshes/right_hand_five_link.STL

BIN
assets/g1/meshes/right_hand_four_link.STL

BIN
assets/g1/meshes/right_hand_one_link.STL

BIN
assets/g1/meshes/right_hand_palm_link.STL

BIN
assets/g1/meshes/right_hand_six_link.STL

BIN
assets/g1/meshes/right_hand_three_link.STL

BIN
assets/g1/meshes/right_hand_two_link.STL

BIN
assets/g1/meshes/right_hand_zero_link.STL

BIN
assets/g1/meshes/right_hip_pitch_link.STL

BIN
assets/g1/meshes/right_hip_roll_link.STL

BIN
assets/g1/meshes/right_hip_yaw_link.STL

BIN
assets/g1/meshes/right_knee_link.STL

BIN
assets/g1/meshes/right_shoulder_pitch_link.STL

BIN
assets/g1/meshes/right_shoulder_roll_link.STL

BIN
assets/g1/meshes/right_shoulder_yaw_link.STL

BIN
assets/g1/meshes/right_wrist_pitch_link.STL

BIN
assets/g1/meshes/right_wrist_roll_link.STL

BIN
assets/g1/meshes/right_wrist_yaw_link.STL

BIN
assets/g1/meshes/torso_constraint_L_link.STL

BIN
assets/g1/meshes/torso_constraint_L_rod_link.STL

BIN
assets/g1/meshes/torso_constraint_R_link.STL

BIN
assets/g1/meshes/torso_constraint_R_rod_link.STL

BIN
assets/g1/meshes/torso_link.STL

BIN
assets/g1/meshes/waist_constraint_L.STL

BIN
assets/g1/meshes/waist_constraint_R.STL

BIN
assets/g1/meshes/waist_roll_link.STL

BIN
assets/g1/meshes/waist_support_link.STL

BIN
assets/g1/meshes/waist_yaw_link.STL

13
assets/h1_description/CMakeLists.txt

@ -1,13 +0,0 @@
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)

58
assets/h1_description/README.md

@ -1,58 +0,0 @@
# 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/).
The file `urdf/h1.urdf` is description for H1 without hands, and `urdf/h1_with_hand.urdf` for H1 with dexterous hands. For IsaacGym users, please the file with `_isaacgym.urdf` to avoid some visualization issues.
<p align="center">
<img src="doc/H1.png" width="500"/>
</p>
Basic 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
```

239
assets/h1_description/launch/check_joint.rviz

@ -1,239 +0,0 @@
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

20
assets/h1_description/launch/display.launch

@ -1,20 +0,0 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find h1_description)/urdf/h1_with_hand.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>

12
assets/h1_description/launch/gazebo.launch

@ -1,12 +0,0 @@
<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>

BIN
assets/h1_description/meshes/L_hand_base_link.STL

89
assets/h1_description/meshes/L_hand_base_link.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link11_L.STL

89
assets/h1_description/meshes/Link11_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link11_R.STL

89
assets/h1_description/meshes/Link11_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link12_L.STL

89
assets/h1_description/meshes/Link12_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link12_R.STL

89
assets/h1_description/meshes/Link12_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link13_L.STL

89
assets/h1_description/meshes/Link13_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link13_R.STL

89
assets/h1_description/meshes/Link13_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link14_L.STL

89
assets/h1_description/meshes/Link14_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link14_R.STL

89
assets/h1_description/meshes/Link14_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link15_L.STL

89
assets/h1_description/meshes/Link15_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link15_R.STL

89
assets/h1_description/meshes/Link15_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link16_L.STL

89
assets/h1_description/meshes/Link16_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link16_R.STL

89
assets/h1_description/meshes/Link16_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link17_L.STL

89
assets/h1_description/meshes/Link17_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link17_R.STL

89
assets/h1_description/meshes/Link17_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link18_L.STL

89
assets/h1_description/meshes/Link18_L.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link18_R.STL

89
assets/h1_description/meshes/Link18_R.dae
File diff suppressed because it is too large
View File

BIN
assets/h1_description/meshes/Link19_L.STL

89
assets/h1_description/meshes/Link19_L.dae
File diff suppressed because it is too large
View File

Some files were not shown because too many files changed in this diff

Loading…
Cancel
Save