384 lines
26 KiB
XML
384 lines
26 KiB
XML
|
<mujoco model="g1_29dof_with_hand_rev_1_0">
|
||
|
<compiler angle="radian" meshdir="assets"/>
|
||
|
|
||
|
<option integrator="implicitfast" impratio="10" cone="elliptic" noslip_iterations="3" timestep="0.0064">
|
||
|
<flag multiccd="enable" />
|
||
|
</option>
|
||
|
|
||
|
<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"/>
|
||
|
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
|
||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3"
|
||
|
markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||
|
|
||
|
<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 name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||
|
<mesh file="left_wrist_yaw_link.STL"/>
|
||
|
<mesh file="left_hand_palm_link.STL"/>
|
||
|
<mesh file="left_hand_thumb_0_link.STL"/>
|
||
|
<mesh file="left_hand_thumb_1_link.STL"/>
|
||
|
<mesh file="left_hand_thumb_2_link.STL"/>
|
||
|
<mesh file="left_hand_middle_0_link.STL"/>
|
||
|
<mesh file="left_hand_middle_1_link.STL"/>
|
||
|
<mesh file="left_hand_index_0_link.STL"/>
|
||
|
<mesh file="left_hand_index_1_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="right_wrist_roll_link.STL"/>
|
||
|
<mesh file="right_wrist_pitch_link.STL"/>
|
||
|
<mesh file="right_wrist_yaw_link.STL"/>
|
||
|
<mesh file="right_hand_palm_link.STL"/>
|
||
|
<mesh file="right_hand_thumb_0_link.STL"/>
|
||
|
<mesh file="right_hand_thumb_1_link.STL"/>
|
||
|
<mesh file="right_hand_thumb_2_link.STL"/>
|
||
|
<mesh file="right_hand_middle_0_link.STL"/>
|
||
|
<mesh file="right_hand_middle_1_link.STL"/>
|
||
|
<mesh file="right_hand_index_0_link.STL"/>
|
||
|
<mesh file="right_hand_index_1_link.STL"/>
|
||
|
</asset>
|
||
|
|
||
|
<worldbody>
|
||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||
|
<body name="waist_yaw_link" pos="0 0 0.01" childclass="g1">
|
||
|
<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" class="visual" material="black" mesh="head_link"/>
|
||
|
<geom pos="0.0039635 0 -0.044" class="collision" mesh="head_link"/>
|
||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||
|
<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" 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" 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.0885506 0.00212216 -0.000374562" quat="0.487149 0.493844 0.513241 0.505358"
|
||
|
mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
|
||
|
<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_hand_palm_link"/>
|
||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" class="collision" mesh="left_hand_palm_link"/>
|
||
|
<body name="left_hand_thumb_0_link" pos="0.067 0.003 0">
|
||
|
<inertial pos="-0.000884246 -0.00863407 0.000944293"
|
||
|
quat="0.462991 0.643965 -0.460173 0.398986" mass="0.0862366"
|
||
|
diaginertia="1.6546e-05 1.60058e-05 1.43741e-05"/>
|
||
|
<joint name="left_hand_thumb_0_joint" axis="0 1 0" range="-1.0472 1.0472"
|
||
|
actuatorfrcrange="-2.45 2.45"/>
|
||
|
<geom class="visual" mesh="left_hand_thumb_0_link"/>
|
||
|
<geom class="collision" mesh="left_hand_thumb_0_link"/>
|
||
|
<body name="left_hand_thumb_1_link" pos="-0.0025 -0.0193 0">
|
||
|
<inertial pos="-0.000827888 -0.0354744 -0.0003809"
|
||
|
quat="0.685598 0.705471 -0.15207 0.0956069" mass="0.0588507"
|
||
|
diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||
|
<joint name="left_hand_thumb_1_joint" axis="0 0 1" range="-0.724312 1.0472"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="left_hand_thumb_1_link"/>
|
||
|
<geom size="0.01 0.015 0.01" pos="-0.001 -0.032 0" type="box" class="collision"/>
|
||
|
<body name="left_hand_thumb_2_link" pos="0 -0.0458 0">
|
||
|
<inertial pos="-0.00171735 -0.0262819 0.000107789"
|
||
|
quat="0.703174 0.710977 -0.00017564 -0.00766553" mass="0.0203063"
|
||
|
diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||
|
<joint name="left_hand_thumb_2_joint" axis="0 0 1" range="0 1.74533"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="left_hand_thumb_2_link"/>
|
||
|
<geom class="collision" mesh="left_hand_thumb_2_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="left_hand_middle_0_link" pos="0.1192 0.0046 -0.0285">
|
||
|
<inertial pos="0.0354744 0.000827888 0.0003809" quat="0.391313 0.552395 0.417187 0.606373"
|
||
|
mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||
|
<joint name="left_hand_middle_0_joint" axis="0 0 1" range="-1.5708 0"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="left_hand_middle_0_link"/>
|
||
|
<geom class="collision" mesh="left_hand_middle_0_link"/>
|
||
|
<body name="left_hand_middle_1_link" pos="0.0458 0 0">
|
||
|
<inertial pos="0.0262819 0.00171735 -0.000107789"
|
||
|
quat="0.502612 0.491799 0.502639 0.502861" mass="0.0203063"
|
||
|
diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||
|
<joint name="left_hand_middle_1_joint" axis="0 0 1" range="-1.74533 0"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="left_hand_middle_1_link"/>
|
||
|
<geom class="collision" mesh="left_hand_middle_1_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="left_hand_index_0_link" pos="0.1192 0.0046 0.0285">
|
||
|
<inertial pos="0.0354744 0.000827888 0.0003809" quat="0.391313 0.552395 0.417187 0.606373"
|
||
|
mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||
|
<joint name="left_hand_index_0_joint" axis="0 0 1" range="-1.5708 0"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="left_hand_index_0_link"/>
|
||
|
<geom class="collision" mesh="left_hand_index_0_link"/>
|
||
|
<body name="left_hand_index_1_link" pos="0.0458 0 0">
|
||
|
<inertial pos="0.0262819 0.00171735 -0.000107789"
|
||
|
quat="0.502612 0.491799 0.502639 0.502861" mass="0.0203063"
|
||
|
diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||
|
<joint name="left_hand_index_1_joint" axis="0 0 1" range="-1.74533 0"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="left_hand_index_1_link"/>
|
||
|
<geom class="collision" mesh="left_hand_index_1_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</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" 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" 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.0885506 -0.00212216 -0.000374562" quat="0.505358 0.513241 0.493844 0.487149"
|
||
|
mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
|
||
|
<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_hand_palm_link"/>
|
||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" class="collision" mesh="right_hand_palm_link"/>
|
||
|
<body name="right_hand_thumb_0_link" pos="0.067 -0.003 0">
|
||
|
<inertial pos="-0.000884246 0.00863407 0.000944293"
|
||
|
quat="0.643965 0.462991 -0.398986 0.460173" mass="0.0862366"
|
||
|
diaginertia="1.6546e-05 1.60058e-05 1.43741e-05"/>
|
||
|
<joint name="right_hand_thumb_0_joint" axis="0 1 0" range="-1.0472 1.0472"
|
||
|
actuatorfrcrange="-2.45 2.45"/>
|
||
|
<geom class="visual" mesh="right_hand_thumb_0_link"/>
|
||
|
<geom class="collision" mesh="right_hand_thumb_0_link"/>
|
||
|
<body name="right_hand_thumb_1_link" pos="-0.0025 0.0193 0">
|
||
|
<inertial pos="-0.000827888 0.0354744 -0.0003809"
|
||
|
quat="0.705471 0.685598 -0.0956069 0.15207" mass="0.0588507"
|
||
|
diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||
|
<joint name="right_hand_thumb_1_joint" axis="0 0 1" range="-1.0472 0.724312"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="right_hand_thumb_1_link"/>
|
||
|
<geom size="0.01 0.015 0.01" pos="-0.001 0.032 0" type="box" class="collision"/>
|
||
|
<body name="right_hand_thumb_2_link" pos="0 0.0458 0">
|
||
|
<inertial pos="-0.00171735 0.0262819 0.000107789"
|
||
|
quat="0.710977 0.703174 0.00766553 0.00017564" mass="0.0203063"
|
||
|
diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||
|
<joint name="right_hand_thumb_2_joint" axis="0 0 1" range="-1.74533 0"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="right_hand_thumb_2_link"/>
|
||
|
<geom class="collision" mesh="right_hand_thumb_2_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="right_hand_middle_0_link" pos="0.1192 -0.0046 -0.0285">
|
||
|
<inertial pos="0.0354744 -0.000827888 0.0003809" quat="0.606373 0.417187 0.552395 0.391313"
|
||
|
mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||
|
<joint name="right_hand_middle_0_joint" axis="0 0 1" range="0 1.5708"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="right_hand_middle_0_link"/>
|
||
|
<geom class="collision" mesh="right_hand_middle_0_link"/>
|
||
|
<body name="right_hand_middle_1_link" pos="0.0458 0 0">
|
||
|
<inertial pos="0.0262819 -0.00171735 -0.000107789"
|
||
|
quat="0.502861 0.502639 0.491799 0.502612" mass="0.0203063"
|
||
|
diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||
|
<joint name="right_hand_middle_1_joint" axis="0 0 1" range="0 1.74533"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="right_hand_middle_1_link"/>
|
||
|
<geom class="collision" mesh="right_hand_middle_1_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="right_hand_index_0_link" pos="0.1192 -0.0046 0.0285">
|
||
|
<inertial pos="0.0354744 -0.000827888 0.0003809" quat="0.606373 0.417187 0.552395 0.391313"
|
||
|
mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||
|
<joint name="right_hand_index_0_joint" axis="0 0 1" range="0 1.5708"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="right_hand_index_0_link"/>
|
||
|
<geom class="collision" mesh="right_hand_index_0_link"/>
|
||
|
<body name="right_hand_index_1_link" pos="0.0458 0 0">
|
||
|
<inertial pos="0.0262819 -0.00171735 -0.000107789"
|
||
|
quat="0.502861 0.502639 0.491799 0.502612" mass="0.0203063"
|
||
|
diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||
|
<joint name="right_hand_index_1_joint" axis="0 0 1" range="0 1.74533"
|
||
|
actuatorfrcrange="-1.4 1.4"/>
|
||
|
<geom class="visual" mesh="right_hand_index_1_link"/>
|
||
|
<geom class="collision" mesh="right_hand_index_1_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</worldbody>
|
||
|
|
||
|
<actuator>
|
||
|
|
||
|
|
||
|
<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="left_hand_thumb_0_joint" joint="left_hand_thumb_0_joint"/>
|
||
|
<position class="g1" name="left_hand_thumb_1_joint" joint="left_hand_thumb_1_joint"/>
|
||
|
<position class="g1" name="left_hand_thumb_2_joint" joint="left_hand_thumb_2_joint"/>
|
||
|
<position class="g1" name="left_hand_middle_0_joint" joint="left_hand_middle_0_joint"/>
|
||
|
<position class="g1" name="left_hand_middle_1_joint" joint="left_hand_middle_1_joint"/>
|
||
|
<position class="g1" name="left_hand_index_0_joint" joint="left_hand_index_0_joint"/>
|
||
|
<position class="g1" name="left_hand_index_1_joint" joint="left_hand_index_1_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"/>
|
||
|
<position class="g1" name="right_hand_thumb_0_joint" joint="right_hand_thumb_0_joint"/>
|
||
|
<position class="g1" name="right_hand_thumb_1_joint" joint="right_hand_thumb_1_joint"/>
|
||
|
<position class="g1" name="right_hand_thumb_2_joint" joint="right_hand_thumb_2_joint"/>
|
||
|
<position class="g1" name="right_hand_index_0_joint" joint="right_hand_index_0_joint"/>
|
||
|
<position class="g1" name="right_hand_index_1_joint" joint="right_hand_index_1_joint"/>
|
||
|
<position class="g1" name="right_hand_middle_0_joint" joint="right_hand_middle_0_joint"/>
|
||
|
<position class="g1" name="right_hand_middle_1_joint" joint="right_hand_middle_1_joint"/>
|
||
|
</actuator>
|
||
|
|
||
|
<sensor>
|
||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||
|
</sensor>
|
||
|
</mujoco>
|