365 lines
23 KiB
XML
365 lines
23 KiB
XML
<mujoco model="g1_29dof_rev_1_0">
|
|
<compiler angle="radian" meshdir="assets"/>
|
|
|
|
<option integrator="implicitfast"/>
|
|
|
|
<default>
|
|
<default class="g1">
|
|
<site rgba="1 0 0 1" size="0.01" group="5"/>
|
|
<joint armature="0.01" frictionloss="0.3"/>
|
|
<position kp="500" dampratio="1" inheritrange="1"/>
|
|
<default class="visual">
|
|
<geom group="2" type="mesh" contype="0" conaffinity="0" density="0" material="metal"/>
|
|
</default>
|
|
<default class="collision">
|
|
<geom group="3" type="mesh"/>
|
|
<default class="foot">
|
|
<geom type="sphere" size="0.005" priority="1" friction="0.6" condim="3"/>
|
|
</default>
|
|
</default>
|
|
</default>
|
|
</default>
|
|
|
|
<asset>
|
|
<material name="black" rgba="0.2 0.2 0.2 1"/>
|
|
<material name="metal" rgba="0.7 0.7 0.7 1"/>
|
|
|
|
<mesh file="pelvis.STL"/>
|
|
<mesh file="pelvis_contour_link.STL"/>
|
|
<mesh file="left_hip_pitch_link.STL"/>
|
|
<mesh file="left_hip_roll_link.STL"/>
|
|
<mesh file="left_hip_yaw_link.STL"/>
|
|
<mesh file="left_knee_link.STL"/>
|
|
<mesh file="left_ankle_pitch_link.STL"/>
|
|
<mesh file="left_ankle_roll_link.STL"/>
|
|
<mesh file="right_hip_pitch_link.STL"/>
|
|
<mesh file="right_hip_roll_link.STL"/>
|
|
<mesh file="right_hip_yaw_link.STL"/>
|
|
<mesh file="right_knee_link.STL"/>
|
|
<mesh file="right_ankle_pitch_link.STL"/>
|
|
<mesh file="right_ankle_roll_link.STL"/>
|
|
<mesh name="waist_yaw_link" file="waist_yaw_link_rev_1_0.STL"/>
|
|
<mesh name="waist_roll_link" file="waist_roll_link_rev_1_0.STL"/>
|
|
<mesh name="torso_link" file="torso_link_rev_1_0.STL"/>
|
|
<mesh file="logo_link.STL"/>
|
|
<mesh file="head_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="left_wrist_roll_link.STL"/>
|
|
<mesh file="left_wrist_pitch_link.STL"/>
|
|
<mesh file="left_wrist_yaw_link.STL"/>
|
|
<mesh file="left_rubber_hand.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="right_wrist_roll_link.STL"/>
|
|
<mesh file="right_wrist_pitch_link.STL"/>
|
|
<mesh file="right_wrist_yaw_link.STL"/>
|
|
<mesh file="right_rubber_hand.STL"/>
|
|
</asset>
|
|
|
|
<worldbody>
|
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
|
<body name="pelvis" pos="0 0 0.793" childclass="g1">
|
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
|
<freejoint name="floating_base_joint"/>
|
|
<geom class="visual" material="black" mesh="pelvis"/>
|
|
<geom class="visual" mesh="pelvis_contour_link"/>
|
|
<geom class="collision" mesh="pelvis_contour_link"/>
|
|
<site name="imu_in_pelvis" pos="0.04525 0 -0.08339" size="0.01"/>
|
|
<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" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
|
<geom class="visual" material="black" mesh="left_hip_pitch_link"/>
|
|
<geom class="collision" material="black" 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" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139"/>
|
|
<geom class="visual" mesh="left_hip_roll_link"/>
|
|
<geom class="collision" 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" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
|
<geom class="visual" mesh="left_hip_yaw_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
|
<geom class="visual" mesh="left_knee_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
|
<geom class="visual" mesh="left_ankle_pitch_link"/>
|
|
<geom class="collision" 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" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
|
<geom class="visual" material="black" mesh="left_ankle_roll_link"/>
|
|
<geom class="foot" pos="-0.05 0.025 -0.03"/>
|
|
<geom class="foot" pos="-0.05 -0.025 -0.03"/>
|
|
<geom class="foot" pos="0.12 0.03 -0.03"/>
|
|
<geom class="foot" pos="0.12 -0.03 -0.03"/>
|
|
<site name="left_foot"/>
|
|
</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" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
|
<geom class="visual" material="black" mesh="right_hip_pitch_link"/>
|
|
<geom class="collision" material="black" 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" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-139 139"/>
|
|
<geom class="visual" mesh="right_hip_roll_link"/>
|
|
<geom class="collision" 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" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
|
<geom class="visual" mesh="right_hip_yaw_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
|
<geom class="visual" mesh="right_knee_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
|
<geom class="visual" mesh="right_ankle_pitch_link"/>
|
|
<geom class="collision" 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" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
|
<geom class="visual" material="black" mesh="right_ankle_roll_link"/>
|
|
<geom class="foot" pos="-0.05 0.025 -0.03"/>
|
|
<geom class="foot" pos="-0.05 -0.025 -0.03"/>
|
|
<geom class="foot" pos="0.12 0.03 -0.03"/>
|
|
<geom class="foot" pos="0.12 -0.03 -0.03"/>
|
|
<site name="right_foot"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="waist_yaw_link">
|
|
<inertial pos="0.003494 0.000233 0.018034" quat="0.289697 0.591001 -0.337795 0.672821" mass="0.214"
|
|
diaginertia="0.000163531 0.000107714 0.000102205"/>
|
|
<joint name="waist_yaw_joint" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
|
<geom class="visual" mesh="waist_yaw_link"/>
|
|
<body name="waist_roll_link" pos="-0.0039635 0 0.044">
|
|
<inertial pos="0 2.3e-05 0" quat="0.5 0.5 -0.5 0.5" mass="0.086" diaginertia="8.245e-06 7.079e-06 6.339e-06"/>
|
|
<joint name="waist_roll_joint" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
|
<geom class="visual" mesh="waist_roll_link"/>
|
|
<body name="torso_link">
|
|
<inertial pos="0.00203158 0.000339683 0.184568" quat="0.999803 -6.03319e-05 0.0198256 0.00131986"
|
|
mass="7.818" diaginertia="0.121847 0.109825 0.0273735"/>
|
|
<joint name="waist_pitch_joint" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
|
<geom class="visual" mesh="torso_link"/>
|
|
<geom class="collision" mesh="torso_link"/>
|
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" class="visual" material="black" mesh="logo_link"/>
|
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" class="collision" material="black" mesh="logo_link"/>
|
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" class="visual" material="black" mesh="head_link"/>
|
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" class="collision" material="black" mesh="head_link"/>
|
|
<site name="imu_in_torso" pos="-0.03959 -0.00224 0.14792" size="0.01"/>
|
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.24778"
|
|
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" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="left_shoulder_pitch_link"/>
|
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder"
|
|
rgba="0.7 0.7 0.7 1" class="collision"/>
|
|
<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" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" 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" class="collision"/>
|
|
<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" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="left_shoulder_yaw_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="left_elbow_link"/>
|
|
<geom class="collision" 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" axis="1 0 0" range="-1.97222 1.97222"
|
|
actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="left_wrist_roll_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-1.61443 1.61443"
|
|
actuatorfrcrange="-5 5"/>
|
|
<geom class="visual" mesh="left_wrist_pitch_link"/>
|
|
<geom class="collision" mesh="left_wrist_pitch_link"/>
|
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
|
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188"
|
|
mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
|
<joint name="left_wrist_yaw_joint" axis="0 0 1" range="-1.61443 1.61443"
|
|
actuatorfrcrange="-5 5"/>
|
|
<geom class="visual" mesh="left_wrist_yaw_link"/>
|
|
<geom class="collision" mesh="left_wrist_yaw_link"/>
|
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" class="visual" mesh="left_rubber_hand"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.24778"
|
|
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" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="right_shoulder_pitch_link"/>
|
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder"
|
|
rgba="0.7 0.7 0.7 1" class="collision"/>
|
|
<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" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" 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"
|
|
class="collision"/>
|
|
<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" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="right_shoulder_yaw_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="right_elbow_link"/>
|
|
<geom class="collision" 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" axis="1 0 0" range="-1.97222 1.97222"
|
|
actuatorfrcrange="-25 25"/>
|
|
<geom class="visual" mesh="right_wrist_roll_link"/>
|
|
<geom class="collision" 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" axis="0 1 0" range="-1.61443 1.61443"
|
|
actuatorfrcrange="-5 5"/>
|
|
<geom class="visual" mesh="right_wrist_pitch_link"/>
|
|
<geom class="collision" mesh="right_wrist_pitch_link"/>
|
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
|
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571"
|
|
mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
|
<joint name="right_wrist_yaw_joint" axis="0 0 1" range="-1.61443 1.61443"
|
|
actuatorfrcrange="-5 5"/>
|
|
<geom class="visual" mesh="right_wrist_yaw_link"/>
|
|
<geom class="collision" mesh="right_wrist_yaw_link"/>
|
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" class="visual" mesh="right_rubber_hand"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</worldbody>
|
|
|
|
<actuator>
|
|
<position class="g1" name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
|
<position class="g1" name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
|
<position class="g1" name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
|
<position class="g1" name="left_knee_joint" joint="left_knee_joint"/>
|
|
<position class="g1" name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
|
<position class="g1" name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
|
|
|
<position class="g1" name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
|
<position class="g1" name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
|
<position class="g1" name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
|
<position class="g1" name="right_knee_joint" joint="right_knee_joint"/>
|
|
<position class="g1" name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
|
<position class="g1" name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
|
|
|
<position class="g1" name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
|
<position class="g1" name="waist_roll_joint" joint="waist_roll_joint"/>
|
|
<position class="g1" name="waist_pitch_joint" joint="waist_pitch_joint"/>
|
|
|
|
<position class="g1" name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
|
<position class="g1" name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
|
<position class="g1" name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
|
<position class="g1" name="left_elbow_joint" joint="left_elbow_joint"/>
|
|
<position class="g1" name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
|
<position class="g1" name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
|
<position class="g1" name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
|
|
|
<position class="g1" name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
|
<position class="g1" name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
|
<position class="g1" name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
|
<position class="g1" name="right_elbow_joint" joint="right_elbow_joint"/>
|
|
<position class="g1" name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
|
<position class="g1" name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
|
<position class="g1" name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
|
</actuator>
|
|
|
|
<sensor>
|
|
<gyro site="imu_in_torso" name="imu-torso-angular-velocity" cutoff="34.9" noise="0.0005"/>
|
|
<accelerometer site="imu_in_torso" name="imu-torso-linear-acceleration" cutoff="157" noise="0.01"/>
|
|
<gyro site="imu_in_pelvis" name="imu-pelvis-angular-velocity" cutoff="34.9" noise="0.0005"/>
|
|
<accelerometer site="imu_in_pelvis" name="imu-pelvis-linear-acceleration" cutoff="157" noise="0.01"/>
|
|
</sensor>
|
|
|
|
<keyframe>
|
|
<key name="stand"
|
|
qpos="
|
|
0 0 0.79
|
|
1 0 0 0
|
|
0 0 0 0 0 0
|
|
0 0 0 0 0 0
|
|
0 0 0
|
|
0.2 0.2 0 1.28 0 0 0
|
|
0.2 -0.2 0 1.28 0 0 0
|
|
"
|
|
ctrl="
|
|
0 0 0 0 0 0
|
|
0 0 0 0 0 0
|
|
0 0 0
|
|
0.2 0.2 0 1.28 0 0 0
|
|
0.2 -0.2 0 1.28 0 0 0
|
|
"/>
|
|
</keyframe>
|
|
</mujoco>
|