rename G1 fingers

This commit is contained in:
matheecs 2024-09-03 21:32:44 +08:00
parent dd4fa6866e
commit 4e723b990d
16 changed files with 158 additions and 158 deletions

View File

@ -842,14 +842,14 @@
</geometry>
</collision>
</link>
<joint name="left_hand_zero_joint" type="revolute">
<joint name="left_hand_thumb_0_joint" type="revolute">
<origin xyz="0.028 0 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="left_hand_palm_link"/>
<child link="left_hand_zero_link"/>
<child link="left_hand_thumb_0_link"/>
<limit effort="2.45" velocity="6.857" lower="-1.04719755" upper="1.04719755"/>
</joint>
<link name="left_hand_zero_link">
<link name="left_hand_thumb_0_link">
<inertial>
<origin xyz="-0.00035441315 -0.01329887312 0.00041236207" rpy="0 0 0"/>
<mass value="0.08033018"/>
@ -858,7 +858,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_zero_link.STL"/>
<mesh filename="meshes/left_hand_thumb_0_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -867,18 +867,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_zero_link.STL"/>
<mesh filename="meshes/left_hand_thumb_0_link.STL"/>
</geometry>
</collision>
</link>
<joint name="left_hand_one_joint" type="revolute">
<joint name="left_hand_thumb_1_joint" type="revolute">
<origin xyz="0 -0.0246 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="left_hand_zero_link"/>
<child link="left_hand_one_link"/>
<parent link="left_hand_thumb_0_link"/>
<child link="left_hand_thumb_1_link"/>
<limit effort="0.7" velocity="24" lower="-0.72431163" upper="1.04719755"/>
</joint>
<link name="left_hand_one_link">
<link name="left_hand_thumb_1_link">
<inertial>
<origin xyz="0.00362060191 -0.04044395878 -0.00029771094" rpy="0 0 0"/>
<mass value="0.05619628"/>
@ -887,7 +887,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_one_link.STL"/>
<mesh filename="meshes/left_hand_thumb_1_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -900,14 +900,14 @@
</geometry>
</collision>
</link>
<joint name="left_hand_two_joint" type="revolute">
<joint name="left_hand_thumb_2_joint" type="revolute">
<origin xyz="0.0055 -0.0528 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="left_hand_one_link"/>
<child link="left_hand_two_link"/>
<parent link="left_hand_thumb_1_link"/>
<child link="left_hand_thumb_2_link"/>
<limit effort="0.7" velocity="24" lower="0" upper="2.09439510"/>
</joint>
<link name="left_hand_two_link">
<link name="left_hand_thumb_2_link">
<inertial>
<origin xyz="-0.00081405957 -0.03456206723 0.00012979919" rpy="0 0 0"/>
<mass value="0.02487314"/>
@ -916,7 +916,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_two_link.STL"/>
<mesh filename="meshes/left_hand_thumb_2_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -925,18 +925,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_two_link.STL"/>
<mesh filename="meshes/left_hand_thumb_2_link.STL"/>
</geometry>
</collision>
</link>
<joint name="left_hand_three_joint" type="revolute">
<joint name="left_hand_middle_0_joint" type="revolute">
<origin xyz="0.1 -0.0017 -0.0285" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="left_hand_palm_link"/>
<child link="left_hand_three_link"/>
<child link="left_hand_middle_0_link"/>
<limit effort="0.7" velocity="24" lower="-1.83259571" upper="0.19198621"/>
</joint>
<link name="left_hand_three_link">
<link name="left_hand_middle_0_link">
<inertial>
<origin xyz="0.04044395878 -0.00362060191 0.00028771094" rpy="0 0 0"/>
<mass value="0.05619628"/>
@ -945,7 +945,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_three_link.STL"/>
<mesh filename="meshes/left_hand_middle_0_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -954,18 +954,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_three_link.STL"/>
<mesh filename="meshes/left_hand_middle_0_link.STL"/>
</geometry>
</collision>
</link>
<joint name="left_hand_four_joint" type="revolute">
<joint name="left_hand_middle_1_joint" type="revolute">
<origin xyz="0.0528 -0.0055 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="left_hand_three_link"/>
<child link="left_hand_four_link"/>
<parent link="left_hand_middle_0_link"/>
<child link="left_hand_middle_1_link"/>
<limit effort="0.7" velocity="24" lower="-2.09439510" upper="0"/>
</joint>
<link name="left_hand_four_link">
<link name="left_hand_middle_1_link">
<inertial>
<origin xyz="0.03456206723 0.00081405957 -0.00012979919" rpy="0 0 0"/>
<mass value="0.02487314"/>
@ -974,7 +974,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_four_link.STL"/>
<mesh filename="meshes/left_hand_middle_1_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -983,18 +983,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_four_link.STL"/>
<mesh filename="meshes/left_hand_middle_1_link.STL"/>
</geometry>
</collision>
</link>
<joint name="left_hand_five_joint" type="revolute">
<joint name="left_hand_index_0_joint" type="revolute">
<origin xyz="0.1 -0.0017 0.0285" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="left_hand_palm_link"/>
<child link="left_hand_five_link"/>
<child link="left_hand_index_0_link"/>
<limit effort="0.7" velocity="24" lower="-1.83259571" upper="0.19198621"/>
</joint>
<link name="left_hand_five_link">
<link name="left_hand_index_0_link">
<inertial>
<origin xyz="0.04044395878 -0.00362060191 0.00028771094" rpy="0 0 0"/>
<mass value="0.05619628"/>
@ -1003,7 +1003,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_five_link.STL"/>
<mesh filename="meshes/left_hand_index_0_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1012,18 +1012,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_five_link.STL"/>
<mesh filename="meshes/left_hand_index_0_link.STL"/>
</geometry>
</collision>
</link>
<joint name="left_hand_six_joint" type="revolute">
<joint name="left_hand_index_1_joint" type="revolute">
<origin xyz="0.0528 -0.0055 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="left_hand_five_link"/>
<child link="left_hand_six_link"/>
<parent link="left_hand_index_0_link"/>
<child link="left_hand_index_1_link"/>
<limit effort="0.7" velocity="24" lower="-2.09439510" upper="0"/>
</joint>
<link name="left_hand_six_link">
<link name="left_hand_index_1_link">
<inertial>
<origin xyz="0.03456206723 0.00081405957 -0.00012979919" rpy="0 0 0"/>
<mass value="0.02487314"/>
@ -1032,7 +1032,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_six_link.STL"/>
<mesh filename="meshes/left_hand_index_1_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1041,7 +1041,7 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hand_six_link.STL"/>
<mesh filename="meshes/left_hand_index_1_link.STL"/>
</geometry>
</collision>
</link>
@ -1275,14 +1275,14 @@
</geometry>
</collision>
</link>
<joint name="right_hand_zero_joint" type="revolute">
<joint name="right_hand_thumb_0_joint" type="revolute">
<origin xyz="0.028 0 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="right_hand_palm_link"/>
<child link="right_hand_zero_link"/>
<child link="right_hand_thumb_0_link"/>
<limit effort="2.45" velocity="6.857" lower="-1.04719755" upper="1.04719755"/>
</joint>
<link name="right_hand_zero_link">
<link name="right_hand_thumb_0_link">
<inertial>
<origin xyz="-0.00035441315 0.01329887312 -0.00041236207" rpy="0 0 0"/>
<mass value="0.08033018"/>
@ -1291,7 +1291,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_zero_link.STL"/>
<mesh filename="meshes/right_hand_thumb_0_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1300,18 +1300,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_zero_link.STL"/>
<mesh filename="meshes/right_hand_thumb_0_link.STL"/>
</geometry>
</collision>
</link>
<joint name="right_hand_one_joint" type="revolute">
<joint name="right_hand_thumb_1_joint" type="revolute">
<origin xyz="0 0.0246 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="right_hand_zero_link"/>
<child link="right_hand_one_link"/>
<parent link="right_hand_thumb_0_link"/>
<child link="right_hand_thumb_1_link"/>
<limit effort="0.7" velocity="24" lower="-1.04719755" upper="0.72431163"/>
</joint>
<link name="right_hand_one_link">
<link name="right_hand_thumb_1_link">
<inertial>
<origin xyz="0.00362060191 0.04044395878 0.00029771094" rpy="0 0 0"/>
<mass value="0.05619628"/>
@ -1320,7 +1320,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_one_link.STL"/>
<mesh filename="meshes/right_hand_thumb_1_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1333,14 +1333,14 @@
</geometry>
</collision>
</link>
<joint name="right_hand_two_joint" type="revolute">
<joint name="right_hand_thumb_2_joint" type="revolute">
<origin xyz="0.0055 0.0528 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="right_hand_one_link"/>
<child link="right_hand_two_link"/>
<parent link="right_hand_thumb_1_link"/>
<child link="right_hand_thumb_2_link"/>
<limit effort="0.7" velocity="24" lower="-2.09439510" upper="0"/>
</joint>
<link name="right_hand_two_link">
<link name="right_hand_thumb_2_link">
<inertial>
<origin xyz="-0.00081405957 0.03456206723 -0.00012979919" rpy="0 0 0"/>
<mass value="0.02487314"/>
@ -1349,7 +1349,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_two_link.STL"/>
<mesh filename="meshes/right_hand_thumb_2_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1358,18 +1358,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_two_link.STL"/>
<mesh filename="meshes/right_hand_thumb_2_link.STL"/>
</geometry>
</collision>
</link>
<joint name="right_hand_three_joint" type="revolute">
<joint name="right_hand_index_0_joint" type="revolute">
<origin xyz="0.1 0.0017 0.0285" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="right_hand_palm_link"/>
<child link="right_hand_three_link"/>
<child link="right_hand_index_0_link"/>
<limit effort="0.7" velocity="24" lower="-0.19198621" upper="1.83259571"/>
</joint>
<link name="right_hand_three_link">
<link name="right_hand_index_0_link">
<inertial>
<origin xyz="0.04044395878 0.00362060191 -0.00028771094" rpy="0 0 0"/>
<mass value="0.05619628"/>
@ -1378,7 +1378,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_three_link.STL"/>
<mesh filename="meshes/right_hand_index_0_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1387,18 +1387,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_three_link.STL"/>
<mesh filename="meshes/right_hand_index_0_link.STL"/>
</geometry>
</collision>
</link>
<joint name="right_hand_four_joint" type="revolute">
<joint name="right_hand_index_1_joint" type="revolute">
<origin xyz="0.0528 0.0055 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="right_hand_three_link"/>
<child link="right_hand_four_link"/>
<parent link="right_hand_index_0_link"/>
<child link="right_hand_index_1_link"/>
<limit effort="0.7" velocity="24" lower="0" upper="2.09439510"/>
</joint>
<link name="right_hand_four_link">
<link name="right_hand_index_1_link">
<inertial>
<origin xyz="0.03456206723 -0.00081405957 0.00012979919" rpy="0 0 0"/>
<mass value="0.02487314"/>
@ -1407,7 +1407,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_four_link.STL"/>
<mesh filename="meshes/right_hand_index_1_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1416,18 +1416,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_four_link.STL"/>
<mesh filename="meshes/right_hand_index_1_link.STL"/>
</geometry>
</collision>
</link>
<joint name="right_hand_five_joint" type="revolute">
<joint name="right_hand_middle_0_joint" type="revolute">
<origin xyz="0.1 0.0017 -0.0285" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="right_hand_palm_link"/>
<child link="right_hand_five_link"/>
<child link="right_hand_middle_0_link"/>
<limit effort="0.7" velocity="24" lower="-0.19198621" upper="1.83259571"/>
</joint>
<link name="right_hand_five_link">
<link name="right_hand_middle_0_link">
<inertial>
<origin xyz="0.04044395878 0.00362060191 -0.00028771094" rpy="0 0 0"/>
<mass value="0.05619628"/>
@ -1436,7 +1436,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_five_link.STL"/>
<mesh filename="meshes/right_hand_middle_0_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1445,18 +1445,18 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_five_link.STL"/>
<mesh filename="meshes/right_hand_middle_0_link.STL"/>
</geometry>
</collision>
</link>
<joint name="right_hand_six_joint" type="revolute">
<joint name="right_hand_middle_1_joint" type="revolute">
<origin xyz="0.0528 0.0055 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="right_hand_five_link"/>
<child link="right_hand_six_link"/>
<parent link="right_hand_middle_0_link"/>
<child link="right_hand_middle_1_link"/>
<limit effort="0.7" velocity="24" lower="0" upper="2.09439510"/>
</joint>
<link name="right_hand_six_link">
<link name="right_hand_middle_1_link">
<inertial>
<origin xyz="0.03456206723 -0.00081405957 0.00012979919" rpy="0 0 0"/>
<mass value="0.02487314"/>
@ -1465,7 +1465,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_six_link.STL"/>
<mesh filename="meshes/right_hand_middle_1_link.STL"/>
</geometry>
<material name="white">
<color rgba="0.7 0.7 0.7 1"/>
@ -1474,7 +1474,7 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hand_six_link.STL"/>
<mesh filename="meshes/right_hand_middle_1_link.STL"/>
</geometry>
</collision>
</link>

View File

@ -30,13 +30,13 @@
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
<mesh name="left_hand_palm_link" file="left_hand_palm_link.STL"/>
<mesh name="left_hand_zero_link" file="left_hand_zero_link.STL"/>
<mesh name="left_hand_one_link" file="left_hand_one_link.STL"/>
<mesh name="left_hand_two_link" file="left_hand_two_link.STL"/>
<mesh name="left_hand_three_link" file="left_hand_three_link.STL"/>
<mesh name="left_hand_four_link" file="left_hand_four_link.STL"/>
<mesh name="left_hand_five_link" file="left_hand_five_link.STL"/>
<mesh name="left_hand_six_link" file="left_hand_six_link.STL"/>
<mesh name="left_hand_thumb_0_link" file="left_hand_thumb_0_link.STL"/>
<mesh name="left_hand_thumb_1_link" file="left_hand_thumb_1_link.STL"/>
<mesh name="left_hand_thumb_2_link" file="left_hand_thumb_2_link.STL"/>
<mesh name="left_hand_middle_0_link" file="left_hand_middle_0_link.STL"/>
<mesh name="left_hand_middle_1_link" file="left_hand_middle_1_link.STL"/>
<mesh name="left_hand_index_0_link" file="left_hand_index_0_link.STL"/>
<mesh name="left_hand_index_1_link" file="left_hand_index_1_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"/>
@ -45,13 +45,13 @@
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
<mesh name="right_hand_palm_link" file="right_hand_palm_link.STL"/>
<mesh name="right_hand_zero_link" file="right_hand_zero_link.STL"/>
<mesh name="right_hand_one_link" file="right_hand_one_link.STL"/>
<mesh name="right_hand_two_link" file="right_hand_two_link.STL"/>
<mesh name="right_hand_three_link" file="right_hand_three_link.STL"/>
<mesh name="right_hand_four_link" file="right_hand_four_link.STL"/>
<mesh name="right_hand_five_link" file="right_hand_five_link.STL"/>
<mesh name="right_hand_six_link" file="right_hand_six_link.STL"/>
<mesh name="right_hand_thumb_0_link" file="right_hand_thumb_0_link.STL"/>
<mesh name="right_hand_thumb_1_link" file="right_hand_thumb_1_link.STL"/>
<mesh name="right_hand_thumb_2_link" file="right_hand_thumb_2_link.STL"/>
<mesh name="right_hand_index_0_link" file="right_hand_index_0_link.STL"/>
<mesh name="right_hand_index_1_link" file="right_hand_index_1_link.STL"/>
<mesh name="right_hand_middle_0_link" file="right_hand_middle_0_link.STL"/>
<mesh name="right_hand_middle_1_link" file="right_hand_middle_1_link.STL"/>
</asset>
<worldbody>
@ -196,46 +196,46 @@
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
<body name="left_hand_zero_link" pos="0.0695 0.003 0">
<body name="left_hand_thumb_0_link" pos="0.0695 0.003 0">
<inertial pos="-0.000354413 -0.0132989 0.000412362" quat="0.385163 0.591021 -0.567321 0.424842" mass="0.0803302" diaginertia="1.39245e-05 1.32309e-05 1.19138e-05"/>
<joint name="left_hand_zero_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_zero_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_zero_link"/>
<body name="left_hand_one_link" pos="0 -0.0246 0">
<joint name="left_hand_thumb_0_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_0_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_0_link"/>
<body name="left_hand_thumb_1_link" pos="0 -0.0246 0">
<inertial pos="0.0036206 -0.040444 -0.000297711" quat="0.696371 0.699653 0.125539 -0.0989605" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="left_hand_one_joint" pos="0 0 0" axis="0 0 1" range="-0.724312 1.0472" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_one_link"/>
<joint name="left_hand_thumb_1_joint" pos="0 0 0" axis="0 0 1" range="-0.724312 1.0472" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_1_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_hand_two_link" pos="0.0055 -0.0528 0">
<body name="left_hand_thumb_2_link" pos="0.0055 -0.0528 0">
<inertial pos="-0.00081406 -0.0345621 0.000129799" quat="0.701976 0.711984 0.0160342 0.00721768" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="left_hand_two_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_two_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_two_link"/>
<joint name="left_hand_thumb_2_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_2_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_2_link"/>
</body>
</body>
</body>
<body name="left_hand_three_link" pos="0.1415 0.0013 -0.0285">
<body name="left_hand_middle_0_link" pos="0.1415 0.0013 -0.0285">
<inertial pos="0.040444 -0.0036206 0.000287711" quat="0.583499 0.422433 0.562384 0.40596" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="left_hand_three_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_three_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_three_link"/>
<body name="left_hand_four_link" pos="0.0528 -0.0055 0">
<joint name="left_hand_middle_0_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_0_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_0_link"/>
<body name="left_hand_middle_1_link" pos="0.0528 -0.0055 0">
<inertial pos="0.0345621 0.00081406 -0.000129799" quat="0.514787 0.501475 0.491268 0.492111" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="left_hand_four_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_four_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_four_link"/>
<joint name="left_hand_middle_1_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_1_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_1_link"/>
</body>
</body>
<body name="left_hand_five_link" pos="0.1415 0.0013 0.0285">
<body name="left_hand_index_0_link" pos="0.1415 0.0013 0.0285">
<inertial pos="0.040444 -0.0036206 0.000287711" quat="0.583499 0.422433 0.562384 0.40596" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="left_hand_five_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_five_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_five_link"/>
<body name="left_hand_six_link" pos="0.0528 -0.0055 0">
<joint name="left_hand_index_0_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_0_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_0_link"/>
<body name="left_hand_index_1_link" pos="0.0528 -0.0055 0">
<inertial pos="0.0345621 0.00081406 -0.000129799" quat="0.514787 0.501475 0.491268 0.492111" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="left_hand_six_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_six_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_six_link"/>
<joint name="left_hand_index_1_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_1_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_1_link"/>
</body>
</body>
</body>
@ -282,46 +282,46 @@
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
<body name="right_hand_zero_link" pos="0.0695 -0.003 0">
<body name="right_hand_thumb_0_link" pos="0.0695 -0.003 0">
<inertial pos="-0.000354413 0.0132989 -0.000412362" quat="0.424842 0.567321 -0.591021 0.385163" mass="0.0803302" diaginertia="1.39245e-05 1.32309e-05 1.19138e-05"/>
<joint name="right_hand_zero_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_zero_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_zero_link"/>
<body name="right_hand_one_link" pos="0 0.0246 0">
<joint name="right_hand_thumb_0_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_0_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_0_link"/>
<body name="right_hand_thumb_1_link" pos="0 0.0246 0">
<inertial pos="0.0036206 0.040444 0.000297711" quat="0.696371 0.699653 -0.125539 0.0989605" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="right_hand_one_joint" pos="0 0 0" axis="0 0 1" range="-1.0472 0.724312" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_one_link"/>
<joint name="right_hand_thumb_1_joint" pos="0 0 0" axis="0 0 1" range="-1.0472 0.724312" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_1_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_hand_two_link" pos="0.0055 0.0528 0">
<body name="right_hand_thumb_2_link" pos="0.0055 0.0528 0">
<inertial pos="-0.00081406 0.0345621 -0.000129799" quat="0.701976 0.711984 -0.0160342 -0.00721768" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="right_hand_two_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_two_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_two_link"/>
<joint name="right_hand_thumb_2_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_2_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_2_link"/>
</body>
</body>
</body>
<body name="right_hand_three_link" pos="0.1415 -0.0013 0.0285">
<body name="right_hand_index_0_link" pos="0.1415 -0.0013 0.0285">
<inertial pos="0.040444 0.0036206 -0.000287711" quat="0.562384 0.40596 0.583499 0.422433" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="right_hand_three_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_three_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_three_link"/>
<body name="right_hand_four_link" pos="0.0528 0.0055 0">
<joint name="right_hand_index_0_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_0_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_0_link"/>
<body name="right_hand_index_1_link" pos="0.0528 0.0055 0">
<inertial pos="0.0345621 -0.00081406 0.000129799" quat="0.491268 0.492111 0.514787 0.501475" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="right_hand_four_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_four_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_four_link"/>
<joint name="right_hand_index_1_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_1_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_1_link"/>
</body>
</body>
<body name="right_hand_five_link" pos="0.1415 -0.0013 -0.0285">
<body name="right_hand_middle_0_link" pos="0.1415 -0.0013 -0.0285">
<inertial pos="0.040444 0.0036206 -0.000287711" quat="0.562384 0.40596 0.583499 0.422433" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
<joint name="right_hand_five_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_five_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_five_link"/>
<body name="right_hand_six_link" pos="0.0528 0.0055 0">
<joint name="right_hand_middle_0_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_0_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_0_link"/>
<body name="right_hand_middle_1_link" pos="0.0528 0.0055 0">
<inertial pos="0.0345621 -0.00081406 0.000129799" quat="0.491268 0.492111 0.514787 0.501475" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
<joint name="right_hand_six_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_six_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_six_link"/>
<joint name="right_hand_middle_1_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_1_link"/>
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_1_link"/>
</body>
</body>
</body>
@ -360,13 +360,13 @@
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
<motor name="left_hand_zero_joint" joint="left_hand_zero_joint"/>
<motor name="left_hand_one_joint" joint="left_hand_one_joint"/>
<motor name="left_hand_two_joint" joint="left_hand_two_joint"/>
<motor name="left_hand_three_joint" joint="left_hand_three_joint"/>
<motor name="left_hand_four_joint" joint="left_hand_four_joint"/>
<motor name="left_hand_five_joint" joint="left_hand_five_joint"/>
<motor name="left_hand_six_joint" joint="left_hand_six_joint"/>
<motor name="left_hand_thumb_0_joint" joint="left_hand_thumb_0_joint"/>
<motor name="left_hand_thumb_1_joint" joint="left_hand_thumb_1_joint"/>
<motor name="left_hand_thumb_2_joint" joint="left_hand_thumb_2_joint"/>
<motor name="left_hand_middle_0_joint" joint="left_hand_middle_0_joint"/>
<motor name="left_hand_middle_1_joint" joint="left_hand_middle_1_joint"/>
<motor name="left_hand_index_0_joint" joint="left_hand_index_0_joint"/>
<motor name="left_hand_index_1_joint" joint="left_hand_index_1_joint"/>
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
@ -374,13 +374,13 @@
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
<motor name="right_hand_zero_joint" joint="right_hand_zero_joint"/>
<motor name="right_hand_one_joint" joint="right_hand_one_joint"/>
<motor name="right_hand_two_joint" joint="right_hand_two_joint"/>
<motor name="right_hand_three_joint" joint="right_hand_three_joint"/>
<motor name="right_hand_four_joint" joint="right_hand_four_joint"/>
<motor name="right_hand_five_joint" joint="right_hand_five_joint"/>
<motor name="right_hand_six_joint" joint="right_hand_six_joint"/>
<motor name="right_hand_thumb_0_joint" joint="right_hand_thumb_0_joint"/>
<motor name="right_hand_thumb_1_joint" joint="right_hand_thumb_1_joint"/>
<motor name="right_hand_thumb_2_joint" joint="right_hand_thumb_2_joint"/>
<motor name="right_hand_index_0_joint" joint="right_hand_index_0_joint"/>
<motor name="right_hand_index_1_joint" joint="right_hand_index_1_joint"/>
<motor name="right_hand_middle_0_joint" joint="right_hand_middle_0_joint"/>
<motor name="right_hand_middle_1_joint" joint="right_hand_middle_1_joint"/>
</actuator>
<sensor>