Upload mjx_h1.xml (#12)
Browse files- Upload mjx_h1.xml (f182b2de3503a3da435f6d32ec1b2a6f2e8800a6)
Co-authored-by: Mengfei Zhao <[email protected]>
- robots/h1/mjcf/mjx_h1.xml +226 -0
robots/h1/mjcf/mjx_h1.xml
ADDED
|
@@ -0,0 +1,226 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<mujoco model="h1">
|
| 2 |
+
<compiler angle="radian" meshdir="assets" autolimits="true"/>
|
| 3 |
+
|
| 4 |
+
<default>
|
| 5 |
+
<default class="h1">
|
| 6 |
+
<geom type="mesh"/>
|
| 7 |
+
<joint damping="1" armature="0.1"/>
|
| 8 |
+
<default class="visual">
|
| 9 |
+
<geom contype="0" conaffinity="0" group="2" material="black"/>
|
| 10 |
+
</default>
|
| 11 |
+
<default class="collision">
|
| 12 |
+
<geom group="3" mass="0" density="0"/>
|
| 13 |
+
</default>
|
| 14 |
+
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
|
| 15 |
+
<default class="hip">
|
| 16 |
+
<position forcerange="-200 200" kp="200" kv="5"/>
|
| 17 |
+
</default>
|
| 18 |
+
<default class="knee">
|
| 19 |
+
<position forcerange="-300 300" kp="300" kv="6"/>
|
| 20 |
+
</default>
|
| 21 |
+
<default class="ankle">
|
| 22 |
+
<position forcerange="-40 40" kp="40" kv="2"/>
|
| 23 |
+
</default>
|
| 24 |
+
<default class="torso">
|
| 25 |
+
<position forcerange="-200 200" kp="300" kv="6"/>
|
| 26 |
+
</default>
|
| 27 |
+
<default class="shoulder1">
|
| 28 |
+
<position forcerange="-40 40" kp="100" kv="2"/>
|
| 29 |
+
</default>
|
| 30 |
+
<default class="shoulder2">
|
| 31 |
+
<position forcerange="-18 18" kp="100" kv="2"/>
|
| 32 |
+
</default>
|
| 33 |
+
<default class="elbow">
|
| 34 |
+
<position forcerange="-18 18" kp="100" kv="2"/>
|
| 35 |
+
</default>
|
| 36 |
+
</default>
|
| 37 |
+
</default>
|
| 38 |
+
|
| 39 |
+
<asset>
|
| 40 |
+
<material name="black" rgba="0.1 0.1 0.1 1"/>
|
| 41 |
+
<material name="white" rgba="1 1 1 1"/>
|
| 42 |
+
|
| 43 |
+
<mesh file="pelvis.stl"/>
|
| 44 |
+
<mesh file="left_hip_yaw_link.stl"/>
|
| 45 |
+
<mesh file="left_hip_roll_link.stl"/>
|
| 46 |
+
<mesh file="left_hip_pitch_link.stl"/>
|
| 47 |
+
<mesh file="left_knee_link.stl"/>
|
| 48 |
+
<mesh file="left_ankle_link.stl"/>
|
| 49 |
+
<mesh file="right_hip_yaw_link.stl"/>
|
| 50 |
+
<mesh file="right_hip_roll_link.stl"/>
|
| 51 |
+
<mesh file="right_hip_pitch_link.stl"/>
|
| 52 |
+
<mesh file="right_knee_link.stl"/>
|
| 53 |
+
<mesh file="right_ankle_link.stl"/>
|
| 54 |
+
<mesh file="torso_link.stl"/>
|
| 55 |
+
<mesh file="left_shoulder_pitch_link.stl"/>
|
| 56 |
+
<mesh file="left_shoulder_roll_link.stl"/>
|
| 57 |
+
<mesh file="left_shoulder_yaw_link.stl"/>
|
| 58 |
+
<mesh file="left_elbow_link.stl"/>
|
| 59 |
+
<mesh file="right_shoulder_pitch_link.stl"/>
|
| 60 |
+
<mesh file="right_shoulder_roll_link.stl"/>
|
| 61 |
+
<mesh file="right_shoulder_yaw_link.stl"/>
|
| 62 |
+
<mesh file="right_elbow_link.stl"/>
|
| 63 |
+
<mesh file="logo_link.stl"/>
|
| 64 |
+
</asset>
|
| 65 |
+
|
| 66 |
+
<worldbody>
|
| 67 |
+
<light pos="0 0 10" castshadow="false" directional="true"
|
| 68 |
+
ambient="0.3 0.3 0.3" diffuse="0.7 0.7 0.7" specular="0.1 0.1 0.1"/>
|
| 69 |
+
<body name="pelvis" pos="0 0 0" childclass="h1">
|
| 70 |
+
<camera name="cam_default" pos="2 3 0" mode="trackcom" xyaxes="-1 0.5 0 0 0 1"/>
|
| 71 |
+
<inertial pos="-0.0002 4e-05 -0.04522" quat="0.498303 0.499454 -0.500496 0.501741" mass="5.39"
|
| 72 |
+
diaginertia="0.0490211 0.0445821 0.00824619"/>
|
| 73 |
+
<geom class="visual" mesh="pelvis"/>
|
| 74 |
+
<body name="left_hip_yaw_link" pos="0 0.0875 -0.1742">
|
| 75 |
+
<inertial pos="-0.04923 0.0001 0.0072" quat="0.69699 0.219193 0.233287 0.641667" mass="2.244"
|
| 76 |
+
diaginertia="0.00304494 0.00296885 0.00189201"/>
|
| 77 |
+
<joint name="left_hip_yaw" axis="0 0 1" range="-0.43 0.43"/>
|
| 78 |
+
<geom class="visual" mesh="left_hip_yaw_link"/>
|
| 79 |
+
<body name="left_hip_roll_link" pos="0.039468 0 0">
|
| 80 |
+
<inertial pos="-0.0058 -0.00319 -9e-05" quat="0.0438242 0.70721 -0.0729075 0.701867" mass="2.232"
|
| 81 |
+
diaginertia="0.00243264 0.00225325 0.00205492"/>
|
| 82 |
+
<joint name="left_hip_roll" axis="1 0 0" range="-0.43 0.43"/>
|
| 83 |
+
<geom class="visual" mesh="left_hip_roll_link"/>
|
| 84 |
+
<body name="left_hip_pitch_link" pos="0 0.11536 0">
|
| 85 |
+
<inertial pos="0.00746 -0.02346 -0.08193" quat="0.979828 0.0513522 -0.0169854 -0.192382" mass="4.152"
|
| 86 |
+
diaginertia="0.0829503 0.0821457 0.00510909"/>
|
| 87 |
+
<joint name="left_hip_pitch" axis="0 1 0" range="-3.14 2.53"/>
|
| 88 |
+
<geom class="visual" mesh="left_hip_pitch_link"/>
|
| 89 |
+
<body name="left_knee_link" pos="0 0 -0.4">
|
| 90 |
+
<inertial pos="-0.00136 -0.00512 -0.1384" quat="0.626132 -0.034227 -0.0416277 0.777852" mass="1.721"
|
| 91 |
+
diaginertia="0.0125237 0.0123104 0.0019428"/>
|
| 92 |
+
<joint name="left_knee" axis="0 1 0" range="-0.26 2.05"/>
|
| 93 |
+
<geom class="visual" mesh="left_knee_link"/>
|
| 94 |
+
<body name="left_ankle_link" pos="0 0 -0.4">
|
| 95 |
+
<inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
|
| 96 |
+
diaginertia="0.00362 0.00355701 0.000149987"/>
|
| 97 |
+
<joint name="left_ankle" axis="0 1 0" range="-0.87 0.52"/>
|
| 98 |
+
<geom class="visual" mesh="left_ankle_link"/>
|
| 99 |
+
<geom size="0.15 0.015 0.015" pos="0.05 0 -0.055" type="box" class="collision"/>
|
| 100 |
+
<site name="left_foot" pos="0. 0 -0.05" rgba="0 1 0 1" size="0.2"/>
|
| 101 |
+
</body>
|
| 102 |
+
</body>
|
| 103 |
+
</body>
|
| 104 |
+
</body>
|
| 105 |
+
</body>
|
| 106 |
+
<body name="right_hip_yaw_link" pos="0 -0.0875 -0.1742">
|
| 107 |
+
<inertial pos="-0.04923 -0.0001 0.0072" quat="0.641667 0.233287 0.219193 0.69699" mass="2.244"
|
| 108 |
+
diaginertia="0.00304494 0.00296885 0.00189201"/>
|
| 109 |
+
<joint name="right_hip_yaw" axis="0 0 1" range="-0.43 0.43"/>
|
| 110 |
+
<geom class="visual" mesh="right_hip_yaw_link"/>
|
| 111 |
+
<body name="right_hip_roll_link" pos="0.039468 0 0">
|
| 112 |
+
<inertial pos="-0.0058 0.00319 -9e-05" quat="-0.0438242 0.70721 0.0729075 0.701867" mass="2.232"
|
| 113 |
+
diaginertia="0.00243264 0.00225325 0.00205492"/>
|
| 114 |
+
<joint name="right_hip_roll" axis="1 0 0" range="-0.43 0.43"/>
|
| 115 |
+
<geom class="visual" mesh="right_hip_roll_link"/>
|
| 116 |
+
<body name="right_hip_pitch_link" pos="0 -0.11536 0">
|
| 117 |
+
<inertial pos="0.00746 0.02346 -0.08193" quat="0.979828 -0.0513522 -0.0169854 0.192382" mass="4.152"
|
| 118 |
+
diaginertia="0.0829503 0.0821457 0.00510909"/>
|
| 119 |
+
<joint name="right_hip_pitch" axis="0 1 0" range="-3.14 2.53"/>
|
| 120 |
+
<geom class="visual" mesh="right_hip_pitch_link"/>
|
| 121 |
+
<body name="right_knee_link" pos="0 0 -0.4">
|
| 122 |
+
<inertial pos="-0.00136 0.00512 -0.1384" quat="0.777852 -0.0416277 -0.034227 0.626132" mass="1.721"
|
| 123 |
+
diaginertia="0.0125237 0.0123104 0.0019428"/>
|
| 124 |
+
<joint name="right_knee" axis="0 1 0" range="-0.26 2.05"/>
|
| 125 |
+
<geom class="visual" mesh="right_knee_link"/>
|
| 126 |
+
<body name="right_ankle_link" pos="0 0 -0.4">
|
| 127 |
+
<inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
|
| 128 |
+
diaginertia="0.00362 0.00355701 0.000149987"/>
|
| 129 |
+
<joint name="right_ankle" axis="0 1 0" range="-0.87 0.52"/>
|
| 130 |
+
<geom class="visual" mesh="right_ankle_link"/>
|
| 131 |
+
<geom size="0.15 0.015 0.015" pos="0.05 0 -0.055" type="box" class="collision"/>
|
| 132 |
+
<site name="right_foot" pos="0. 0 -0.05" rgba="0 1 0 1" size="0.2"/>
|
| 133 |
+
</body>
|
| 134 |
+
</body>
|
| 135 |
+
</body>
|
| 136 |
+
</body>
|
| 137 |
+
</body>
|
| 138 |
+
<body name="torso_link">
|
| 139 |
+
<inertial pos="0.000489 0.002797 0.20484" quat="0.999989 -0.00130808 -0.00282289 -0.00349105" mass="17.789"
|
| 140 |
+
diaginertia="0.487315 0.409628 0.127837"/>
|
| 141 |
+
<joint name="torso" axis="0 0 1" range="-2.35 2.35"/>
|
| 142 |
+
<geom class="visual" mesh="torso_link"/>
|
| 143 |
+
<site name="head" class="visual" size="0.01" pos="0 0 0.7" rgba="1 1 1 1"/>
|
| 144 |
+
<geom class="visual" material="white" mesh="logo_link"/>
|
| 145 |
+
<site name="imu" size="0.01" pos="-0.04452 0.0 0.27756"/>
|
| 146 |
+
<body name="left_shoulder_pitch_link" pos="0.0055 0.15535 0.42999" quat="0.976296 0.216438 0 0">
|
| 147 |
+
<inertial pos="0.005045 0.053657 -0.015715" quat="0.814858 0.579236 -0.0201072 -0.00936488" mass="1.033"
|
| 148 |
+
diaginertia="0.00129936 0.000987113 0.000858198"/>
|
| 149 |
+
<joint name="left_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/>
|
| 150 |
+
<geom class="visual" mesh="left_shoulder_pitch_link"/>
|
| 151 |
+
<body name="left_shoulder_roll_link" pos="-0.0055 0.0565 -0.0165" quat="0.976296 -0.216438 0 0">
|
| 152 |
+
<inertial pos="0.000679 0.00115 -0.094076" quat="0.732491 0.00917179 0.0766656 0.676384" mass="0.793"
|
| 153 |
+
diaginertia="0.00170388 0.00158256 0.00100336"/>
|
| 154 |
+
<joint name="left_shoulder_roll" axis="1 0 0" range="-0.34 3.11"/>
|
| 155 |
+
<geom class="visual" mesh="left_shoulder_roll_link"/>
|
| 156 |
+
<body name="left_shoulder_yaw_link" pos="0 0 -0.1343">
|
| 157 |
+
<inertial pos="0.01365 0.002767 -0.16266" quat="0.703042 -0.0331229 -0.0473362 0.708798" mass="0.839"
|
| 158 |
+
diaginertia="0.00408038 0.00370367 0.000622687"/>
|
| 159 |
+
<joint name="left_shoulder_yaw" axis="0 0 1" range="-1.3 4.45"/>
|
| 160 |
+
<geom class="visual" mesh="left_shoulder_yaw_link"/>
|
| 161 |
+
<body name="left_elbow_link" pos="0.0185 0 -0.198">
|
| 162 |
+
<inertial pos="0.15908 -0.000144 -0.015776" quat="0.0765232 0.720327 0.0853116 0.684102" mass="0.669"
|
| 163 |
+
diaginertia="0.00601829 0.00600579 0.000408305"/>
|
| 164 |
+
<joint name="left_elbow" axis="0 1 0" range="-1.25 2.61"/>
|
| 165 |
+
<geom class="visual" mesh="left_elbow_link"/>
|
| 166 |
+
<site name="left_hand" pos="0.31 0 -0.01" rgba="0 1 0 1" size="0.01"/>
|
| 167 |
+
</body>
|
| 168 |
+
</body>
|
| 169 |
+
</body>
|
| 170 |
+
</body>
|
| 171 |
+
<body name="right_shoulder_pitch_link" pos="0.0055 -0.15535 0.42999" quat="0.976296 -0.216438 0 0">
|
| 172 |
+
<inertial pos="0.005045 -0.053657 -0.015715" quat="0.579236 0.814858 0.00936488 0.0201072" mass="1.033"
|
| 173 |
+
diaginertia="0.00129936 0.000987113 0.000858198"/>
|
| 174 |
+
<joint name="right_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/>
|
| 175 |
+
<geom class="visual" mesh="right_shoulder_pitch_link"/>
|
| 176 |
+
<body name="right_shoulder_roll_link" pos="-0.0055 -0.0565 -0.0165" quat="0.976296 0.216438 0 0">
|
| 177 |
+
<inertial pos="0.000679 -0.00115 -0.094076" quat="0.676384 0.0766656 0.00917179 0.732491" mass="0.793"
|
| 178 |
+
diaginertia="0.00170388 0.00158256 0.00100336"/>
|
| 179 |
+
<joint name="right_shoulder_roll" axis="1 0 0" range="-3.11 0.34"/>
|
| 180 |
+
<geom class="visual" mesh="right_shoulder_roll_link"/>
|
| 181 |
+
<body name="right_shoulder_yaw_link" pos="0 0 -0.1343">
|
| 182 |
+
<inertial pos="0.01365 -0.002767 -0.16266" quat="0.708798 -0.0473362 -0.0331229 0.703042" mass="0.839"
|
| 183 |
+
diaginertia="0.00408038 0.00370367 0.000622687"/>
|
| 184 |
+
<joint name="right_shoulder_yaw" axis="0 0 1" range="-4.45 1.3"/>
|
| 185 |
+
<geom class="visual" mesh="right_shoulder_yaw_link"/>
|
| 186 |
+
<body name="right_elbow_link" pos="0.0185 0 -0.198">
|
| 187 |
+
<inertial pos="0.15908 0.000144 -0.015776" quat="-0.0765232 0.720327 -0.0853116 0.684102" mass="0.669"
|
| 188 |
+
diaginertia="0.00601829 0.00600579 0.000408305"/>
|
| 189 |
+
<joint name="right_elbow" axis="0 1 0" range="-1.25 2.61"/>
|
| 190 |
+
<geom class="visual" mesh="right_elbow_link"/>
|
| 191 |
+
<site name="right_hand" pos="0.31 0 -0.01"/>
|
| 192 |
+
</body>
|
| 193 |
+
</body>
|
| 194 |
+
</body>
|
| 195 |
+
</body>
|
| 196 |
+
</body>
|
| 197 |
+
</body>
|
| 198 |
+
</worldbody>
|
| 199 |
+
|
| 200 |
+
<actuator>
|
| 201 |
+
<position name="left_hip_yaw" joint="left_hip_yaw" ctrlrange="-0.43 0.43" class="hip" />
|
| 202 |
+
<position name="left_hip_roll" joint="left_hip_roll" ctrlrange="-0.43 0.43" class="hip" />
|
| 203 |
+
<position name="left_hip_pitch" joint="left_hip_pitch" ctrlrange="-3.14 2.53" class="hip" />
|
| 204 |
+
<position name="left_knee" joint="left_knee" ctrlrange="-0.26 2.05" class="knee" />
|
| 205 |
+
<position name="left_ankle" joint="left_ankle" ctrlrange="-0.87 0.52" class="ankle" />
|
| 206 |
+
<position name="right_hip_yaw" joint="right_hip_yaw" ctrlrange="-0.43 0.43" class="hip" />
|
| 207 |
+
<position name="right_hip_roll" joint="right_hip_roll" ctrlrange="-0.43 0.43" class="hip" />
|
| 208 |
+
<position name="right_hip_pitch" joint="right_hip_pitch" ctrlrange="-3.14 2.53" class="hip" />
|
| 209 |
+
<position name="right_knee" joint="right_knee" ctrlrange="-0.26 2.05" class="knee" />
|
| 210 |
+
<position name="right_ankle" joint="right_ankle" ctrlrange="-0.87 0.52" class="ankle" />
|
| 211 |
+
<position name="torso" joint="torso" ctrlrange="-2.35 2.35" class="torso" />
|
| 212 |
+
<position name="left_shoulder_pitch" joint="left_shoulder_pitch" ctrlrange="-2.87 2.87" class="shoulder1" />
|
| 213 |
+
<position name="left_shoulder_roll" joint="left_shoulder_roll" ctrlrange="-0.34 3.11" class="shoulder1" />
|
| 214 |
+
<position name="left_shoulder_yaw" joint="left_shoulder_yaw" ctrlrange="-1.3 4.45" class="shoulder2" />
|
| 215 |
+
<position name="left_elbow" joint="left_elbow" ctrlrange="-1.25 2.61" class="elbow" />
|
| 216 |
+
<position name="right_shoulder_pitch" joint="right_shoulder_pitch" ctrlrange="-2.87 2.87" class="shoulder1" />
|
| 217 |
+
<position name="right_shoulder_roll" joint="right_shoulder_roll" ctrlrange="-3.11 0.34" class="shoulder1" />
|
| 218 |
+
<position name="right_shoulder_yaw" joint="right_shoulder_yaw" ctrlrange="-4.45 1.3" class="shoulder2" />
|
| 219 |
+
<position name="right_elbow" joint="right_elbow" ctrlrange="-1.25 2.61" class="elbow" />
|
| 220 |
+
</actuator>
|
| 221 |
+
|
| 222 |
+
<sensor>
|
| 223 |
+
<touch name="left_foot_sensor" site="left_foot"/>
|
| 224 |
+
<touch name="right_foot_sensor" site="right_foot"/>
|
| 225 |
+
</sensor>
|
| 226 |
+
</mujoco>
|