266 lines
14 KiB
XML

<mujoco model="T1">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<option integrator="implicitfast"/>
<asset>
<material name="light_gray" rgba="0.76 0.76 0.76 1"/>
<material name="medium_gray" rgba="0.4 0.4 0.4 1"/>
<mesh file="Trunk.stl"/>
<mesh file="H1.stl"/>
<mesh file="H2.stl"/>
<mesh file="AL1.stl"/>
<mesh file="AL2.stl"/>
<mesh file="AL3.stl"/>
<mesh file="left_hand_link.stl"/>
<mesh file="AR1.stl"/>
<mesh file="AR2.stl"/>
<mesh file="AR3.stl"/>
<mesh file="right_hand_link.stl"/>
<mesh file="Waist.stl"/>
<mesh file="Hip_Pitch_Left.stl"/>
<mesh file="Hip_Roll_Left.stl"/>
<mesh file="Hip_Yaw_Left.stl"/>
<mesh file="Shank_Left.stl"/>
<mesh file="Ankle_Cross_Left.stl"/>
<mesh file="left_foot_link.stl"/>
<mesh file="Hip_Pitch_Right.stl"/>
<mesh file="Hip_Roll_Right.stl"/>
<mesh file="Hip_Yaw_Right.stl"/>
<mesh file="Shank_Right.stl"/>
<mesh file="Ankle_Cross_Right.stl"/>
<mesh file="right_foot_link.stl"/>
</asset>
<default>
<default class="t1">
<geom material="medium_gray"/>
<site rgba="1 0 0 1" size="0.01" group="5"/>
<joint frictionloss="0.1" armature="0.005"/>
<position inheritrange="1" kp="75" kv="5"/>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom group="3"/>
</default>
</default>
</default>
<worldbody>
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
<body name="Trunk" pos="0 0 .7" childclass="t1">
<freejoint/>
<inertial pos="0.0551365 -1.42058e-06 0.105062" quat="0.99996 1.40561e-05 -0.00899532 -1.39249e-05" mass="11.7"
diaginertia="0.0915404 0.0767787 0.0556055"/>
<site name="imu"/>
<geom class="visual" material="light_gray" mesh="Trunk"/>
<geom class="collision" size="0.075 0.1 0.15" pos="0.06 0 0.12" type="box"/>
<body name="H1" pos="0.0625 0 0.243">
<inertial pos="-0.000508 -0.001403 0.057432" quat="0.763881 -0.0132172 0.00173419 0.645219" mass="0.44391"
diaginertia="0.000241549 0.00022351 0.000149941"/>
<joint name="AAHead_yaw" axis="0 0 1" range="-1.57 1.57" actuatorfrcrange="-7 7"/>
<geom class="visual" mesh="H1"/>
<body name="H2" pos="0 0 0.06185">
<inertial pos="0.007802 0.001262 0.098631" quat="0.988453 0.106172 -0.0745686 -0.0782786" mass="0.631019"
diaginertia="0.00203553 0.00192467 0.00172381"/>
<joint name="Head_pitch" axis="0 1 0" range="-0.35 1.22" actuatorfrcrange="-7 7"/>
<geom class="visual" mesh="H2"/>
<geom class="collision" size="0.08" pos="0.01 0 0.11"/>
</body>
</body>
<body name="AL1" pos="0.0575 0.1063 0.219" quat="1 0 0.000440565 0">
<inertial pos="-0.000677 0.044974 0" quat="0.50423 0.495734 -0.50423 0.495734" mass="0.53"
diaginertia="0.001367 0.00129329 0.000292711"/>
<joint name="Left_Shoulder_Pitch" axis="0 1 0" range="-3.31 1.22" actuatorfrcrange="-18 18"/>
<geom class="visual" material="light_gray" mesh="AL1"/>
<body name="AL2" pos="0 0.047 0">
<inertial pos="0.003862 0.037976 0" quat="0.487991 0.511727 -0.487991 0.511727" mass="0.16"
diaginertia="0.000401 0.00034538 0.00017662"/>
<joint name="Left_Shoulder_Roll" axis="1 0 0" range="-1.74 1.57" actuatorfrcrange="-18 18"/>
<geom class="visual" mesh="AL2"/>
<body name="AL3" pos="0.00025 0.0605 0">
<inertial pos="0 0.085353 -9.9e-05" quat="0.70641 0.707803 0 0" mass="1.02"
diaginertia="0.012869 0.012798 0.000620953"/>
<joint name="Left_Elbow_Pitch" axis="0 1 0" range="-2.27 2.27" actuatorfrcrange="-18 18"/>
<geom class="visual" mesh="AL3"/>
<geom class="collision" size="0.03 0.075" pos="0 0.05 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
<body name="left_hand_link" pos="0 0.1471 0">
<inertial pos="-0.000108 0.109573 0.000591" quat="0.707866 0.706347 -5.22939e-05 -0.000214913"
mass="0.327214" diaginertia="0.008159 0.00813104 0.000214962"/>
<joint name="Left_Elbow_Yaw" axis="0 0 1" range="-2.44 0" actuatorfrcrange="-18 18"/>
<geom class="visual" mesh="left_hand_link"/>
<geom class="collision" size="0.03 0.0875" pos="0 0.13 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
</body>
</body>
</body>
</body>
<body name="AR1" pos="0.0575 -0.1063 0.219" quat="1 0 0.000440565 0">
<inertial pos="-0.000677 -0.044974 0" quat="0.50423 0.495734 -0.50423 0.495734" mass="0.53"
diaginertia="0.001367 0.00129329 0.000292711"/>
<joint name="Right_Shoulder_Pitch" axis="0 1 0" range="-3.31 1.22" actuatorfrcrange="-18 18"/>
<geom class="visual" material="light_gray" mesh="AR1"/>
<body name="AR2" pos="0 -0.047 0">
<inertial pos="0.003862 -0.037976 0" quat="0.511727 0.487991 -0.511727 0.487991" mass="0.16"
diaginertia="0.000401 0.00034538 0.00017662"/>
<joint name="Right_Shoulder_Roll" axis="1 0 0" range="-1.57 1.74" actuatorfrcrange="-18 18"/>
<geom class="visual" mesh="AR2"/>
<body name="AR3" pos="0.00025 -0.0605 0">
<inertial pos="0 -0.085353 -9.9e-05" quat="0.707803 0.70641 0 0" mass="1.02"
diaginertia="0.012869 0.012798 0.000620953"/>
<joint name="Right_Elbow_Pitch" axis="0 1 0" range="-2.27 2.27" actuatorfrcrange="-18 18"/>
<geom class="visual" mesh="AR3"/>
<geom class="collision" size="0.03 0.075" pos="0 -0.05 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
<body name="right_hand_link" pos="0 -0.1471 0">
<inertial pos="-0.000108 -0.109573 0.000591" quat="0.706347 0.707866 0.000214913 5.22939e-05"
mass="0.327214" diaginertia="0.008159 0.00813104 0.000214962"/>
<joint name="Right_Elbow_Yaw" axis="0 0 1" range="0 2.44" actuatorfrcrange="-18 18"/>
<geom class="visual" mesh="right_hand_link"/>
<geom class="collision" size="0.03 0.0875" pos="0 -0.13 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
</body>
</body>
</body>
</body>
<body name="Waist" pos="0.0625 0 -0.1155">
<inertial pos="0.002284 3e-06 0.007301" quat="0.983649 0.000360386 -0.180076 0.00269791" mass="2.581"
diaginertia="0.00536742 0.005299 0.00474258"/>
<joint name="Waist" axis="0 0 1" range="-1.57 1.57" actuatorfrcrange="-30 30"/>
<geom class="visual" mesh="Waist"/>
<body name="Hip_Pitch_Left" pos="0 0.106 0">
<inertial pos="0.000534 -0.007296 -0.018083" quat="0.975141 0.2211 0.0145808 0.0017406" mass="1.021"
diaginertia="0.00180547 0.00145926 0.00125327"/>
<joint name="Left_Hip_Pitch" axis="0 1 0" range="-1.8 1.57" actuatorfrcrange="-45 45"/>
<geom class="visual" material="light_gray" mesh="Hip_Pitch_Left"/>
<body name="Hip_Roll_Left" pos="0 0 -0.02">
<inertial pos="0.001101 2.4e-05 -0.05375" quat="0.707081 -0.00599604 -0.00599604 0.707081" mass="0.385"
diaginertia="0.001743 0.00151729 0.000514712"/>
<joint name="Left_Hip_Roll" axis="1 0 0" range="-0.2 1.57" actuatorfrcrange="-30 30"/>
<geom class="visual" mesh="Hip_Roll_Left"/>
<body name="Hip_Yaw_Left" pos="0 0 -0.081854">
<inertial pos="-0.007233 0.000206 -0.089184" quat="0.696808 -0.033953 -0.0315708 0.715758" mass="2.166"
diaginertia="0.0257334 0.0253024 0.00259215"/>
<joint name="Left_Hip_Yaw" axis="0 0 1" range="-1 1" actuatorfrcrange="-30 30"/>
<geom class="visual" mesh="Hip_Yaw_Left"/>
<geom class="collision" size="0.05 0.08" type="cylinder"/>
<body name="Shank_Left" pos="-0.014 0 -0.134">
<inertial pos="-0.006012 0.000259 -0.124318" quat="0.997573 0.00144024 -0.023949 0.0653706" mass="1.73"
diaginertia="0.0346951 0.0345375 0.00185844"/>
<joint name="Left_Knee_Pitch" axis="0 1 0" range="0 2.34" actuatorfrcrange="-60 60"/>
<geom class="visual" mesh="Shank_Left"/>
<geom class="collision" size="0.05 0.075" pos="0 0 -0.12" type="cylinder"/>
<body name="Ankle_Cross_Left" pos="0 0 -0.28">
<inertial pos="-0.003722 0 -0.007981" quat="0.443136 0.551027 0.551027 0.443136" mass="0.073"
diaginertia="2.9e-05 2.56589e-05 1.13411e-05"/>
<joint name="Left_Ankle_Pitch" axis="0 1 0" range="-0.87 0.35" actuatorfrcrange="-20 20"/>
<geom class="visual" mesh="Ankle_Cross_Left"/>
<body name="left_foot_link" pos="0 0.00025 -0.012">
<inertial pos="-0.000249 0 -0.00914" quat="0 0.620755 0 0.784005" mass="0.685"
diaginertia="0.00269786 0.002385 0.00218714"/>
<joint name="Left_Ankle_Roll" axis="1 0 0" range="-0.44 0.44" actuatorfrcrange="-15 15"/>
<geom class="visual" mesh="left_foot_link"/>
<geom class="collision" size="0.1115 0.05 0.015" pos="0.01 0 -0.015" type="box"/>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="Hip_Pitch_Right" pos="0 -0.106 0">
<inertial pos="0.000534 0.007514 -0.018082" quat="0.973446 -0.228403 0.0147148 -0.00419349" mass="1.021"
diaginertia="0.00180552 0.0014632 0.00124928"/>
<joint name="Right_Hip_Pitch" axis="0 1 0" range="-1.8 1.57" actuatorfrcrange="-45 45"/>
<geom class="visual" material="light_gray" mesh="Hip_Pitch_Right"/>
<body name="Hip_Roll_Right" pos="0 0 -0.02">
<inertial pos="0.001099 2.4e-05 -0.053748" quat="0.707081 -0.00599604 -0.00599604 0.707081" mass="0.385"
diaginertia="0.001743 0.00151729 0.000514712"/>
<joint name="Right_Hip_Roll" axis="1 0 0" range="-1.57 0.2" actuatorfrcrange="-30 30"/>
<geom class="visual" mesh="Hip_Roll_Right"/>
<body name="Hip_Yaw_Right" pos="0 0 -0.081854">
<inertial pos="-0.007191 -0.000149 -0.08922" quat="0.714468 -0.0315638 -0.0336391 0.698146" mass="2.17"
diaginertia="0.0257623 0.0253298 0.00259389"/>
<joint name="Right_Hip_Yaw" axis="0 0 1" range="-1 1" actuatorfrcrange="-30 30"/>
<geom class="visual" mesh="Hip_Yaw_Right"/>
<geom class="collision" size="0.05 0.08" type="cylinder"/>
<body name="Shank_Right" pos="-0.014 0 -0.134">
<inertial pos="-0.005741 -0.000541 -0.122602" quat="0.99926 -0.000580963 -0.023461 -0.0304754"
mass="1.79" diaginertia="0.0351717 0.0349574 0.00196589"/>
<joint name="Right_Knee_Pitch" axis="0 1 0" range="0 2.34" actuatorfrcrange="-60 60"/>
<geom class="visual" mesh="Shank_Right"/>
<geom class="collision" size="0.05 0.075" pos="0 0 -0.12" type="cylinder"/>
<body name="Ankle_Cross_Right" pos="0 0 -0.28">
<inertial pos="-0.003722 0 -0.007981" quat="0.443136 0.551027 0.551027 0.443136" mass="0.073"
diaginertia="2.9e-05 2.56589e-05 1.13411e-05"/>
<joint name="Right_Ankle_Pitch" axis="0 1 0" range="-0.87 0.35" actuatorfrcrange="-20 20"/>
<geom class="visual" mesh="Ankle_Cross_Right"/>
<body name="right_foot_link" pos="0 -0.00025 -0.012">
<inertial pos="-0.000248 0 -0.00914" quat="0 0.620755 0 0.784005" mass="0.685"
diaginertia="0.00269786 0.002385 0.00218714"/>
<joint name="Right_Ankle_Roll" axis="1 0 0" range="-0.44 0.44" actuatorfrcrange="-15 15"/>
<geom class="visual" mesh="right_foot_link"/>
<geom class="collision" size="0.1115 0.05 0.015" pos="0.01 0 -0.015" type="box"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<sensor>
<gyro name="angular-velocity" site="imu"/>
<accelerometer name="linear-acceleration" site="imu"/>
<framequat name="orientation" objtype="site" objname="imu"/>
</sensor>
<actuator>
<position class="t1" name="AAHead_yaw" joint="AAHead_yaw"/>
<position class="t1" name="Head_pitch" joint="Head_pitch"/>
<position class="t1" name="Left_Shoulder_Pitch" joint="Left_Shoulder_Pitch"/>
<position class="t1" name="Left_Shoulder_Roll" joint="Left_Shoulder_Roll"/>
<position class="t1" name="Left_Elbow_Pitch" joint="Left_Elbow_Pitch"/>
<position class="t1" name="Left_Elbow_Yaw" joint="Left_Elbow_Yaw"/>
<position class="t1" name="Right_Shoulder_Pitch" joint="Right_Shoulder_Pitch"/>
<position class="t1" name="Right_Shoulder_Roll" joint="Right_Shoulder_Roll"/>
<position class="t1" name="Right_Elbow_Pitch" joint="Right_Elbow_Pitch"/>
<position class="t1" name="Right_Elbow_Yaw" joint="Right_Elbow_Yaw"/>
<position class="t1" name="Waist" joint="Waist"/>
<position class="t1" name="Left_Hip_Pitch" joint="Left_Hip_Pitch"/>
<position class="t1" name="Left_Hip_Roll" joint="Left_Hip_Roll"/>
<position class="t1" name="Left_Hip_Yaw" joint="Left_Hip_Yaw"/>
<position class="t1" name="Left_Knee_Pitch" joint="Left_Knee_Pitch"/>
<position class="t1" name="Left_Ankle_Pitch" joint="Left_Ankle_Pitch"/>
<position class="t1" name="Left_Ankle_Roll" joint="Left_Ankle_Roll"/>
<position class="t1" name="Right_Hip_Pitch" joint="Right_Hip_Pitch"/>
<position class="t1" name="Right_Hip_Roll" joint="Right_Hip_Roll"/>
<position class="t1" name="Right_Hip_Yaw" joint="Right_Hip_Yaw"/>
<position class="t1" name="Right_Knee_Pitch" joint="Right_Knee_Pitch"/>
<position class="t1" name="Right_Ankle_Pitch" joint="Right_Ankle_Pitch"/>
<position class="t1" name="Right_Ankle_Roll" joint="Right_Ankle_Roll"/>
</actuator>
<keyframe>
<key name="home"
qpos="
0 0 0.665
1 0 0 0
0 0
0 -1.4 0 -0.4
0 1.4 0 0.4
0
-0.2 0 0 0.4 -0.2 0
-0.2 0 0 0.4 -0.2 0
"
ctrl="
0 0
0 -1.4 0 -0.4
0 1.4 0 0.4
0
-0.2 0 0 0.4 -0.2 0
-0.2 0 0 0.4 -0.2 0
"/>
</keyframe>
</mujoco>