| <mujoco model="h1"> | |
| <compiler angle="radian" meshdir="../meshes" autolimits="true"/> | |
| <default> | |
| <default class="h1"> | |
| <geom type="mesh"/> | |
| <joint damping="1" armature="0.1"/> | |
| <default class="visual"> | |
| <geom contype="0" conaffinity="0" group="2" material="black"/> | |
| </default> | |
| <default class="collision"> | |
| <geom group="3" mass="0" density="0"/> | |
| </default> | |
| <site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/> | |
| </default> | |
| </default> | |
| <asset> | |
| <material name="black" rgba="0.1 0.1 0.1 1"/> | |
| <material name="white" rgba="1 1 1 1"/> | |
| <mesh file="pelvis.STL"/> | |
| <mesh file="left_hip_yaw_link.STL"/> | |
| <mesh file="left_hip_roll_link.STL"/> | |
| <mesh file="left_hip_pitch_link.STL"/> | |
| <mesh file="left_knee_link.STL"/> | |
| <mesh file="left_ankle_link.STL"/> | |
| <mesh file="right_hip_yaw_link.STL"/> | |
| <mesh file="right_hip_roll_link.STL"/> | |
| <mesh file="right_hip_pitch_link.STL"/> | |
| <mesh file="right_knee_link.STL"/> | |
| <mesh file="right_ankle_link.STL"/> | |
| <mesh file="torso_link.STL"/> | |
| <mesh file="left_shoulder_pitch_link.STL"/> | |
| <mesh file="left_shoulder_roll_link.STL"/> | |
| <mesh file="left_shoulder_yaw_link.STL"/> | |
| <mesh file="left_elbow_link.STL"/> | |
| <mesh file="right_shoulder_pitch_link.STL"/> | |
| <mesh file="right_shoulder_roll_link.STL"/> | |
| <mesh file="right_shoulder_yaw_link.STL"/> | |
| <mesh file="right_elbow_link.STL"/> | |
| <mesh file="logo_link.STL"/> | |
| </asset> | |
| <worldbody> | |
| <body name="pelvis" pos="0 0 1.1" childclass="h1"> | |
| <inertial pos="-0.0002 4e-05 -0.04522" quat="0.498303 0.499454 -0.500496 0.501741" mass="5.39" | |
| diaginertia="0.0490211 0.0445821 0.00824619"/> | |
| <freejoint/> | |
| <geom class="visual" mesh="pelvis"/> | |
| <geom class="collision" mesh="pelvis"/> | |
| <body name="left_hip_yaw_link" pos="0 0.0875 -0.1742"> | |
| <inertial pos="-0.04923 0.0001 0.0072" quat="0.69699 0.219193 0.233287 0.641667" mass="2.244" | |
| diaginertia="0.00304494 0.00296885 0.00189201"/> | |
| <joint name="left_hip_yaw_joint" axis="0 0 1" range="-0.43 0.43"/> | |
| <geom class="visual" mesh="left_hip_yaw_link"/> | |
| <geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | |
| <body name="left_hip_roll_link" pos="0.039468 0 0"> | |
| <inertial pos="-0.0058 -0.00319 -9e-05" quat="0.0438242 0.70721 -0.0729075 0.701867" mass="2.232" | |
| diaginertia="0.00243264 0.00225325 0.00205492"/> | |
| <joint name="left_hip_roll_joint" axis="1 0 0" range="-0.43 0.43"/> | |
| <geom class="visual" mesh="left_hip_roll_link"/> | |
| <geom class="collision" mesh="left_hip_roll_link"/> | |
| <body name="left_hip_pitch_link" pos="0 0.11536 0"> | |
| <inertial pos="0.00746 -0.02346 -0.08193" quat="0.979828 0.0513522 -0.0169854 -0.192382" mass="4.152" | |
| diaginertia="0.0829503 0.0821457 0.00510909"/> | |
| <joint name="left_hip_pitch_joint" axis="0 1 0" range="-3.14 2.53"/> | |
| <geom class="visual" mesh="left_hip_pitch_link"/> | |
| <geom class="collision" mesh="left_hip_pitch_link"/> | |
| <body name="left_knee_link" pos="0 0 -0.4"> | |
| <inertial pos="-0.00136 -0.00512 -0.1384" quat="0.626132 -0.034227 -0.0416277 0.777852" mass="1.721" | |
| diaginertia="0.0125237 0.0123104 0.0019428"/> | |
| <joint name="left_knee_joint" axis="0 1 0" range="-0.26 2.05"/> | |
| <geom class="visual" mesh="left_knee_link"/> | |
| <geom class="collision" mesh="left_knee_link"/> | |
| <body name="left_ankle_link" pos="0 0 -0.4"> | |
| <inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448" | |
| diaginertia="0.00362 0.00355701 0.000149987"/> | |
| <joint name="left_ankle_joint" axis="0 1 0" range="-0.87 0.52"/> | |
| <geom class="visual" mesh="left_ankle_link"/> | |
| <geom class="collision" mesh="left_ankle_link"/> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| <body name="right_hip_yaw_link" pos="0 -0.0875 -0.1742"> | |
| <inertial pos="-0.04923 -0.0001 0.0072" quat="0.641667 0.233287 0.219193 0.69699" mass="2.244" | |
| diaginertia="0.00304494 0.00296885 0.00189201"/> | |
| <joint name="right_hip_yaw_joint" axis="0 0 1" range="-0.43 0.43"/> | |
| <geom class="visual" mesh="right_hip_yaw_link"/> | |
| <geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | |
| <body name="right_hip_roll_link" pos="0.039468 0 0"> | |
| <inertial pos="-0.0058 0.00319 -9e-05" quat="-0.0438242 0.70721 0.0729075 0.701867" mass="2.232" | |
| diaginertia="0.00243264 0.00225325 0.00205492"/> | |
| <joint name="right_hip_roll_joint" axis="1 0 0" range="-0.43 0.43"/> | |
| <geom class="visual" mesh="right_hip_roll_link"/> | |
| <geom class="collision" mesh="right_hip_roll_link"/> | |
| <body name="right_hip_pitch_link" pos="0 -0.11536 0"> | |
| <inertial pos="0.00746 0.02346 -0.08193" quat="0.979828 -0.0513522 -0.0169854 0.192382" mass="4.152" | |
| diaginertia="0.0829503 0.0821457 0.00510909"/> | |
| <joint name="right_hip_pitch_joint" axis="0 1 0" range="-3.14 2.53"/> | |
| <geom class="visual" mesh="right_hip_pitch_link"/> | |
| <geom class="collision" mesh="right_hip_pitch_link"/> | |
| <body name="right_knee_link" pos="0 0 -0.4"> | |
| <inertial pos="-0.00136 0.00512 -0.1384" quat="0.777852 -0.0416277 -0.034227 0.626132" mass="1.721" | |
| diaginertia="0.0125237 0.0123104 0.0019428"/> | |
| <joint name="right_knee_joint" axis="0 1 0" range="-0.26 2.05"/> | |
| <geom class="visual" mesh="right_knee_link"/> | |
| <geom class="collision" mesh="right_knee_link"/> | |
| <body name="right_ankle_link" pos="0 0 -0.4"> | |
| <inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448" | |
| diaginertia="0.00362 0.00355701 0.000149987"/> | |
| <joint name="right_ankle_joint" axis="0 1 0" range="-0.87 0.52"/> | |
| <geom class="visual" mesh="right_ankle_link"/> | |
| <geom class="collision" mesh="right_ankle_link"/> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| <body name="torso_link"> | |
| <inertial pos="0.000489 0.002797 0.20484" quat="0.999989 -0.00130808 -0.00282289 -0.00349105" mass="17.789" | |
| diaginertia="0.487315 0.409628 0.127837"/> | |
| <joint name="torso_joint" axis="0 0 1" range="-2.35 2.35"/> | |
| <geom class="visual" mesh="torso_link"/> | |
| <geom class="collision" mesh="torso_link"/> | |
| <geom class="visual" material="white" mesh="logo_link"/> | |
| <site name="imu" size="0.01" pos="-0.04452 -0.01891 0.27756"/> | |
| <body name="left_shoulder_pitch_link" pos="0.0055 0.15535 0.42999" quat="0.976296 0.216438 0 0"> | |
| <inertial pos="0.005045 0.053657 -0.015715" quat="0.814858 0.579236 -0.0201072 -0.00936488" mass="1.033" | |
| diaginertia="0.00129936 0.000987113 0.000858198"/> | |
| <joint name="left_shoulder_pitch_joint" axis="0 1 0" range="-2.87 2.87"/> | |
| <geom class="visual" mesh="left_shoulder_pitch_link"/> | |
| <geom class="collision" mesh="left_shoulder_pitch_link"/> | |
| <body name="left_shoulder_roll_link" pos="-0.0055 0.0565 -0.0165" quat="0.976296 -0.216438 0 0"> | |
| <inertial pos="0.000679 0.00115 -0.094076" quat="0.732491 0.00917179 0.0766656 0.676384" mass="0.793" | |
| diaginertia="0.00170388 0.00158256 0.00100336"/> | |
| <joint name="left_shoulder_roll_joint" axis="1 0 0" range="-0.34 3.11"/> | |
| <geom class="visual" mesh="left_shoulder_roll_link"/> | |
| <geom class="collision" mesh="left_shoulder_roll_link"/> | |
| <body name="left_shoulder_yaw_link" pos="0 0 -0.1343"> | |
| <inertial pos="0.01365 0.002767 -0.16266" quat="0.703042 -0.0331229 -0.0473362 0.708798" mass="0.839" | |
| diaginertia="0.00408038 0.00370367 0.000622687"/> | |
| <joint name="left_shoulder_yaw_joint" axis="0 0 1" range="-1.3 4.45"/> | |
| <geom class="visual" mesh="left_shoulder_yaw_link"/> | |
| <geom class="collision" mesh="left_shoulder_yaw_link"/> | |
| <body name="left_elbow_link" pos="0.0185 0 -0.198"> | |
| <inertial pos="0.15908 -0.000144 -0.015776" quat="0.0765232 0.720327 0.0853116 0.684102" mass="0.669" | |
| diaginertia="0.00601829 0.00600579 0.000408305"/> | |
| <joint name="left_elbow_joint" axis="0 1 0" range="-1.25 2.61"/> | |
| <geom class="visual" mesh="left_elbow_link"/> | |
| <geom class="collision" mesh="left_elbow_link"/> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| <body name="right_shoulder_pitch_link" pos="0.0055 -0.15535 0.42999" quat="0.976296 -0.216438 0 0"> | |
| <inertial pos="0.005045 -0.053657 -0.015715" quat="0.579236 0.814858 0.00936488 0.0201072" mass="1.033" | |
| diaginertia="0.00129936 0.000987113 0.000858198"/> | |
| <joint name="right_shoulder_pitch_joint" axis="0 1 0" range="-2.87 2.87"/> | |
| <geom class="visual" mesh="right_shoulder_pitch_link"/> | |
| <geom class="collision" mesh="right_shoulder_pitch_link"/> | |
| <body name="right_shoulder_roll_link" pos="-0.0055 -0.0565 -0.0165" quat="0.976296 0.216438 0 0"> | |
| <inertial pos="0.000679 -0.00115 -0.094076" quat="0.676384 0.0766656 0.00917179 0.732491" mass="0.793" | |
| diaginertia="0.00170388 0.00158256 0.00100336"/> | |
| <joint name="right_shoulder_roll_joint" axis="1 0 0" range="-3.11 0.34"/> | |
| <geom class="visual" mesh="right_shoulder_roll_link"/> | |
| <geom class="collision" mesh="right_shoulder_roll_link"/> | |
| <body name="right_shoulder_yaw_link" pos="0 0 -0.1343"> | |
| <inertial pos="0.01365 -0.002767 -0.16266" quat="0.708798 -0.0473362 -0.0331229 0.703042" mass="0.839" | |
| diaginertia="0.00408038 0.00370367 0.000622687"/> | |
| <joint name="right_shoulder_yaw_joint" axis="0 0 1" range="-4.45 1.3"/> | |
| <geom class="visual" mesh="right_shoulder_yaw_link"/> | |
| <geom class="collision" mesh="right_shoulder_yaw_link"/> | |
| <body name="right_elbow_link" pos="0.0185 0 -0.198"> | |
| <inertial pos="0.15908 0.000144 -0.015776" quat="-0.0765232 0.720327 -0.0853116 0.684102" mass="0.669" | |
| diaginertia="0.00601829 0.00600579 0.000408305"/> | |
| <joint name="right_elbow_joint" axis="0 1 0" range="-1.25 2.61"/> | |
| <geom class="visual" mesh="right_elbow_link"/> | |
| <geom class="collision" mesh="right_elbow_link"/> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| </worldbody> | |
| <actuator> | |
| <motor class="h1" name="left_hip_yaw_joint" joint="left_hip_yaw_joint" ctrlrange="-200 200"/> | |
| <motor class="h1" name="left_hip_roll_joint" joint="left_hip_roll_joint" ctrlrange="-200 200"/> | |
| <motor class="h1" name="left_hip_pitch_joint" joint="left_hip_pitch_joint" ctrlrange="-200 200"/> | |
| <motor class="h1" name="left_knee_joint" joint="left_knee_joint" ctrlrange="-300 300"/> | |
| <motor class="h1" name="left_ankle_joint" joint="left_ankle_joint" ctrlrange="-40 40"/> | |
| <motor class="h1" name="right_hip_yaw_joint" joint="right_hip_yaw_joint" ctrlrange="-200 200"/> | |
| <motor class="h1" name="right_hip_roll_joint" joint="right_hip_roll_joint" ctrlrange="-200 200"/> | |
| <motor class="h1" name="right_hip_pitch_joint" joint="right_hip_pitch_joint" ctrlrange="-200 200"/> | |
| <motor class="h1" name="right_knee_joint" joint="right_knee_joint" ctrlrange="-300 300"/> | |
| <motor class="h1" name="right_ankle_joint" joint="right_ankle_joint" ctrlrange="-40 40"/> | |
| <motor class="h1" name="torso_joint" joint="torso_joint" ctrlrange="-200 200"/> | |
| <motor class="h1" name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint" ctrlrange="-40 40"/> | |
| <motor class="h1" name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint" ctrlrange="-40 40"/> | |
| <motor class="h1" name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint" ctrlrange="-18 18"/> | |
| <motor class="h1" name="left_elbow_joint" joint="left_elbow_joint" ctrlrange="-18 18"/> | |
| <motor class="h1" name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint" ctrlrange="-40 40"/> | |
| <motor class="h1" name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint" ctrlrange="-40 40"/> | |
| <motor class="h1" name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint" ctrlrange="-18 18"/> | |
| <motor class="h1" name="right_elbow_joint" joint="right_elbow_joint" ctrlrange="-18 18"/> | |
| </actuator> | |
| <sensor> | |
| <framequat name='orientation' objtype='site' noise='0.001' objname='imu'/> | |
| <gyro name='angular-velocity' site='imu' noise='0.005' cutoff='34.9'/> | |
| <gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/> | |
| <accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/> | |
| </sensor> | |
| <keyframe> | |
| <key name="home" | |
| qpos=" | |
| 0 0 0.98 | |
| 1 0 0 0 | |
| 0 0 -0.4 0.8 -0.4 | |
| 0 0 -0.4 0.8 -0.4 | |
| 0 | |
| 0 0 0 0 | |
| 0 0 0 0"/> | |
| </keyframe> | |
| </mujoco> | |