unitree_ros/robots/g1_description/g1.xml

334 lines
30 KiB
XML
Raw Normal View History

2024-05-15 16:39:06 +08:00
<mujoco model="g1">
<compiler angle="radian" meshdir="meshes/" autolimits="true" discardvisual="false"/>
<statistic meansize="0.144785" extent="1.23314" center="0.025392 2.0634e-05 -0.245975"/>
<default>
<joint damping="0.5" armature="0.01" frictionloss="0.1"/>
</default>
<asset>
<mesh name="pelvis" file="pelvis.STL"/>
<mesh name="pelvis_contour_link" file="pelvis_contour_link.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="torso_link" file="torso_link.STL"/>
<mesh name="head_link" file="head_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_pitch_link" file="left_elbow_pitch_link.STL"/>
<mesh name="left_elbow_roll_link" file="left_elbow_roll_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_pitch_link" file="right_elbow_pitch_link.STL"/>
<mesh name="right_elbow_roll_link" file="right_elbow_roll_link.STL"/>
<mesh name="logo_link" file="logo_link.STL"/>
<mesh name="left_palm_link" file="left_palm_link.STL"/>
<mesh name="left_zero_link" file="left_zero_link.STL"/>
<mesh name="left_one_link" file="left_one_link.STL"/>
<mesh name="left_two_link" file="left_two_link.STL"/>
<mesh name="left_three_link" file="left_three_link.STL"/>
<mesh name="left_four_link" file="left_four_link.STL"/>
<mesh name="left_five_link" file="left_five_link.STL"/>
<mesh name="left_six_link" file="left_six_link.STL"/>
<mesh name="right_palm_link" file="right_palm_link.STL"/>
<mesh name="right_zero_link" file="right_zero_link.STL"/>
<mesh name="right_one_link" file="right_one_link.STL"/>
<mesh name="right_two_link" file="right_two_link.STL"/>
<mesh name="right_three_link" file="right_three_link.STL"/>
<mesh name="right_four_link" file="right_four_link.STL"/>
<mesh name="right_five_link" file="right_five_link.STL"/>
<mesh name="right_six_link" file="right_six_link.STL"/>
</asset>
<worldbody>
<body name="pelvis" pos="0 0 0.755">
<inertial pos="0 0 -0.07605" quat="1 0 -0.000405289 0" mass="2.86" diaginertia="0.0079143 0.0069837 0.0059404"/>
<joint name="floating_base_joint" type="free"/>
<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"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis_contour_link"/>
<body name="left_hip_pitch_link" pos="0 0.06445 -0.1027" quat="0.984807 0 -0.17365 0">
<inertial pos="0.001962 0.049392 -0.000941" quat="0.420735 0.907025 -0.0155675 -0.00670646" mass="1.299" diaginertia="0.00138785 0.000955478 0.00086947"/>
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.35 3.05"/>
<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.0523 0">
<inertial pos="0.024757 -0.001036 -0.086323" quat="0.977498 -0.00692636 0.210181 0.0165269" mass="1.446" diaginertia="0.00244106 0.00230425 0.00142899"/>
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.26 2.53"/>
<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.01966 -0.0012139 -0.1241">
<inertial pos="-0.053554 -0.011477 -0.14067" quat="0.645099 0.15885 0.202109 0.71956" mass="2.052" diaginertia="0.0114475 0.0107868 0.00214501"/>
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.75 2.75"/>
<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.078292 -0.0017335 -0.177225" quat="0.967714 0 0.252052 0">
<inertial pos="0.005505 0.006534 -0.116629" quat="0.799234 -0.0128894 0.0354278 0.599836" mass="2.252" diaginertia="0.0127418 0.0124382 0.00192524"/>
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.33489 2.5449"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
<geom size="0.015 0.075" pos="0.007 0.005 -0.15" type="cylinder" rgba="0.7 0.7 0.7 1"/>
<body name="left_ankle_pitch_link" pos="0 0.0040687 -0.30007" quat="0.99678 0 -0.0801788 0">
<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.68 0.73"/>
<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.024762 2e-05 -0.012526" quat="0.000771333 0.734476 0.000921291 0.678634" mass="0.391" diaginertia="0.00110394 0.0010657 0.000149255"/>
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618"/>
<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 size="0.001" pos="-0.06 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
<geom size="0.001" pos="-0.06 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
<geom size="0.001" pos="0.13 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
<geom size="0.001" pos="0.13 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="right_hip_pitch_link" pos="0 -0.06445 -0.1027" quat="0.984807 0 -0.17365 0">
<inertial pos="0.001962 -0.049392 -0.000941" quat="0.907025 0.420735 0.00670646 0.0155675" mass="1.299" diaginertia="0.00138785 0.000955478 0.00086947"/>
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.35 3.05"/>
<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.0523 0">
<inertial pos="0.024757 0.001036 -0.086323" quat="0.977498 0.00692636 0.210181 -0.0165269" mass="1.446" diaginertia="0.00244106 0.00230425 0.00142899"/>
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.53 0.26"/>
<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.01966 0.0012139 -0.1241">
<inertial pos="-0.053554 0.011477 -0.14067" quat="0.71956 0.202109 0.15885 0.645099" mass="2.052" diaginertia="0.0114475 0.0107868 0.00214501"/>
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.75 2.75"/>
<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.078292 0.0017335 -0.177225" quat="0.967714 0 0.252052 0">
<inertial pos="0.005505 -0.006534 -0.116629" quat="0.599836 0.0354278 -0.0128894 0.799234" mass="2.252" diaginertia="0.0127418 0.0124382 0.00192524"/>
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.33489 2.5449"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
<geom size="0.015 0.075" pos="0.007 -0.005 -0.15" type="cylinder" rgba="0.7 0.7 0.7 1"/>
<body name="right_ankle_pitch_link" pos="0 -0.0040687 -0.30007" quat="0.99678 0 -0.0801788 0">
<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.68 0.73"/>
<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.024762 -2e-05 -0.012526" quat="-0.000771333 0.734476 -0.000921291 0.678634" mass="0.391" diaginertia="0.00110394 0.0010657 0.000149255"/>
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618"/>
<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 size="0.001" pos="-0.06 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
<geom size="0.001" pos="-0.06 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
<geom size="0.001" pos="0.13 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
<geom size="0.001" pos="0.13 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="torso_link">
<inertial pos="0.00187791 0.00229457 0.208747" quat="0.999957 0.00624375 -0.00636707 -0.0026338" mass="7.52036" diaginertia="0.12848 0.111753 0.0350394"/>
<joint name="torso_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618"/>
<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 type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
<body name="left_shoulder_pitch_link" pos="-0.0025 0.10396 0.25928" quat="0.990268 0.139172 0 0">
<inertial pos="-0.001431 0.048811 0.001304" quat="0.786417 0.588396 -0.180543 0.0523639" mass="0.713" diaginertia="0.000466421 0.000440181 0.000410999"/>
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.9671 2.7925"/>
<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.052 0" quat="0.990268 -0.139172 0 0">
<inertial pos="-0.003415 0.006955 -0.064598" quat="0.70683 0.0105364 0.00575207 0.707282" mass="0.642" diaginertia="0.000683514 0.000616029 0.000372857"/>
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515"/>
<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 size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
<body name="left_shoulder_yaw_link" pos="-0.00354 0.0062424 -0.1032">
<inertial pos="0.000375 -0.00444 -0.072374" quat="0.903834 -0.0374183 0.00985482 0.42613" mass="0.713" diaginertia="0.000977874 0.000964661 0.000379065"/>
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618"/>
<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_pitch_link" pos="0 0.00189 -0.0855">
<inertial pos="0.064497 0.002873 0" quat="0.582347 0.582495 0.400893 0.401069" mass="0.601" diaginertia="0.00049549 0.0004712 0.00025371"/>
<joint name="left_elbow_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.2268 3.4208"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_pitch_link"/>
<body name="left_elbow_roll_link" pos="0.1 0 0">
<inertial pos="0.133814 0.00147121 0.000265832" quat="0.496781 0.497877 0.498782 0.506502" mass="0.50826" diaginertia="0.00239763 0.00226639 0.000285577"/>
<joint name="left_elbow_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.0943 2.0943"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_roll_link"/>
<geom pos="0.12 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_palm_link"/>
<geom pos="0.12 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_palm_link"/>
<body name="left_zero_link" pos="0.17 0 0">
<inertial pos="-0.0260466 -0.00877511 1.08605e-05" quat="0.59241 0.381376 -0.592953 0.389884" mass="0.0509893" diaginertia="8.68047e-06 7.23365e-06 4.58058e-06"/>
<joint name="left_zero_joint" pos="0 0 0" axis="0 1 0" range="-0.523598 0.523598"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_zero_link"/>
<body name="left_one_link" pos="-0.026525 -0.0188 -5e-05">
<inertial pos="-0.00181538 -0.0327057 -0.000185871" quat="0.701646 0.698199 0.0817825 -0.116289" mass="0.047762" diaginertia="8.03051e-06 7.8455e-06 3.65282e-06"/>
<joint name="left_one_joint" pos="0 0 0" axis="0 0 1" range="-1 1.2"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_one_link"/>
<geom size="0.01 0.015 0.01" pos="-0.001 -0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
<body name="left_two_link" pos="0 -0.0431 0">
<inertial pos="-0.00135257 -0.0237591 -0.000119669" quat="0.717995 0.695316 -0.0180122 -0.0263741" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
<joint name="left_two_joint" pos="0 0 0" axis="0 0 1" range="0 1.84"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_two_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_two_link"/>
</body>
</body>
</body>
<body name="left_three_link" pos="0.205 0.004 0.02395">
<inertial pos="0.0362561 -0.0015725 0.000269899" quat="0.540443 0.459072 0.5397 0.45376" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
<joint name="left_three_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0.3"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_three_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_three_link"/>
<body name="left_four_link" pos="0.0471 -0.0036 0">
<inertial pos="0.0237591 0.00135257 0.000119669" quat="0.478926 0.48905 0.526348 0.504399" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
<joint name="left_four_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_four_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_four_link"/>
</body>
</body>
<body name="left_five_link" pos="0.205 0.004 -0.02395">
<inertial pos="0.0362561 -0.0015725 0.000269899" quat="0.540443 0.459072 0.5397 0.45376" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
<joint name="left_five_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0.3"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_five_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_five_link"/>
<body name="left_six_link" pos="0.0471 -0.0036 0">
<inertial pos="0.0237591 0.00135257 0.000119669" quat="0.478926 0.48905 0.526348 0.504399" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
<joint name="left_six_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_six_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_six_link"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="right_shoulder_pitch_link" pos="-0.0025 -0.10396 0.25928" quat="0.990268 -0.139172 0 0">
<inertial pos="-0.001431 -0.048811 0.001304" quat="0.588396 0.786417 -0.0523639 0.180543" mass="0.713" diaginertia="0.000466421 0.000440181 0.000410999"/>
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.9671 2.7925"/>
<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.052 0" quat="0.990268 0.139172 0 0">
<inertial pos="-0.003415 -0.006955 -0.064598" quat="0.707282 0.00575207 0.0105364 0.70683" mass="0.642" diaginertia="0.000683514 0.000616029 0.000372857"/>
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882"/>
<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 size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
<body name="right_shoulder_yaw_link" pos="-0.00354 -0.0062424 -0.1032">
<inertial pos="0.000375 0.00444 -0.072374" quat="0.42613 0.00985482 -0.0374183 0.903834" mass="0.713" diaginertia="0.000977874 0.000964661 0.000379065"/>
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618"/>
<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_pitch_link" pos="0 -0.00189 -0.0855">
<inertial pos="0.064497 -0.002873 0" quat="0.401069 0.400893 0.582495 0.582347" mass="0.601" diaginertia="0.00049549 0.0004712 0.00025371"/>
<joint name="right_elbow_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.2268 3.4208"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_pitch_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_pitch_link"/>
<body name="right_elbow_roll_link" pos="0.1 0 0">
<inertial pos="0.133814 -0.00147121 0.000265832" quat="0.506502 0.498782 0.497877 0.496781" mass="0.50826" diaginertia="0.00239763 0.00226639 0.000285577"/>
<joint name="right_elbow_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.0943 2.0943"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_roll_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_roll_link"/>
<geom pos="0.12 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_palm_link"/>
<geom pos="0.12 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_palm_link"/>
<body name="right_zero_link" pos="0.17 0 0">
<inertial pos="-0.0260466 0.00877511 1.08605e-05" quat="0.381376 0.59241 -0.389884 0.592953" mass="0.0509893" diaginertia="8.68047e-06 7.23365e-06 4.58058e-06"/>
<joint name="right_zero_joint" pos="0 0 0" axis="0 1 0" range="-0.523598 0.523598"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_zero_link"/>
<body name="right_one_link" pos="-0.026525 0.0188 -5e-05">
<inertial pos="-0.00181538 0.0327057 -0.000185871" quat="0.698199 0.701646 0.116289 -0.0817825" mass="0.047762" diaginertia="8.03051e-06 7.8455e-06 3.65282e-06"/>
<joint name="right_one_joint" pos="0 0 0" axis="0 0 1" range="-1.2 1"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_one_link"/>
<geom size="0.01 0.015 0.01" pos="-0.001 0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
<body name="right_two_link" pos="0 0.0431 0">
<inertial pos="-0.00135257 0.0237591 -0.000119669" quat="0.695316 0.717995 0.0263741 0.0180122" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
<joint name="right_two_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_two_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_two_link"/>
</body>
</body>
</body>
<body name="right_three_link" pos="0.205 -0.004 0.02395">
<inertial pos="0.0362561 0.0015725 0.000269899" quat="0.45376 0.5397 0.459072 0.540443" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
<joint name="right_three_joint" pos="0 0 0" axis="0 0 1" range="-0.3 1.84"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_three_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_three_link"/>
<body name="right_four_link" pos="0.0471 0.0036 0">
<inertial pos="0.0237591 -0.00135257 0.000119669" quat="0.504399 0.526348 0.48905 0.478926" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
<joint name="right_four_joint" pos="0 0 0" axis="0 0 1" range="0 1.84"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_four_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_four_link"/>
</body>
</body>
<body name="right_five_link" pos="0.205 -0.004 -0.02395">
<inertial pos="0.0362561 0.0015725 0.000269899" quat="0.45376 0.5397 0.459072 0.540443" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
<joint name="right_five_joint" pos="0 0 0" axis="0 0 1" range="-0.3 1.84"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_five_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_five_link"/>
<body name="right_six_link" pos="0.0471 0.0036 0">
<inertial pos="0.0237591 -0.00135257 0.000119669" quat="0.504399 0.526348 0.48905 0.478926" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
<joint name="right_six_joint" pos="0 0 0" axis="0 0 1" range="0 1.84"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_six_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_six_link"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint" ctrllimited="true" ctrlrange="-88 88"/>
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint" ctrllimited="true" ctrlrange="-88 88"/>
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint" ctrllimited="true" ctrlrange="-88 88"/>
<motor name="left_knee_joint" joint="left_knee_joint" ctrllimited="true" ctrlrange="-139 139"/>
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint" ctrllimited="true" ctrlrange="-40 40"/>
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint" ctrllimited="true" ctrlrange="-40 40"/>
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint" ctrllimited="true" ctrlrange="-88 88"/>
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint" ctrllimited="true" ctrlrange="-88 88"/>
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint" ctrllimited="true" ctrlrange="-88 88"/>
<motor name="right_knee_joint" joint="right_knee_joint" ctrllimited="true" ctrlrange="-139 139"/>
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint" ctrllimited="true" ctrlrange="-40 40"/>
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint" ctrllimited="true" ctrlrange="-40 40"/>
<motor name="torso_joint" joint="torso_joint" ctrllimited="true" ctrlrange="-88 88"/>
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="left_elbow_pitch_joint" joint="left_elbow_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="left_elbow_roll_joint" joint="left_elbow_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="right_elbow_pitch_joint" joint="right_elbow_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="right_elbow_roll_joint" joint="right_elbow_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
<motor name="left_zero_joint" joint="left_zero_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="left_one_joint" joint="left_one_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="left_two_joint" joint="left_two_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="left_three_joint" joint="left_three_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="left_four_joint" joint="left_four_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="left_five_joint" joint="left_five_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="left_six_joint" joint="left_six_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="right_zero_joint" joint="right_zero_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="right_one_joint" joint="right_one_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="right_two_joint" joint="right_two_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="right_three_joint" joint="right_three_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="right_four_joint" joint="right_four_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="right_five_joint" joint="right_five_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
<motor name="right_six_joint" joint="right_six_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
</actuator>
</mujoco>