unitree_rl_gym/resources/robots/h1_2/h1_2_simplified.urdf

1333 lines
45 KiB
Plaintext
Raw Normal View History

2024-07-17 16:05:28 +08:00
<robot name="h1_5">
<mujoco>
<compiler meshdir="meshes" discardvisual="false"/>
</mujoco>
<!-- [CAUTION] uncomment when convert to mujoco -->
<!-- <link name="world"></link>
<joint name="floating_base_joint" type="floating">
<parent link="world"/>
<child link="pelvis"/>
</joint> -->
<link name="pelvis">
<inertial>
<origin xyz="-0.0004 3.7E-05 -0.046864" rpy="0 0 0"/>
<mass value="5.983"/>
<inertia ixx="49168.411E-06" ixy="-19.869E-06" ixz="-48.460E-06" iyy="9025.844E-06" iyz="3.431E-06" izz="53155.891E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/pelvis.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<!-- L Leg -->
<link name="left_hip_yaw_link">
<inertial>
<origin xyz="0 -0.026197 0.006647" rpy="0 0 0"/>
<mass value="2.829"/>
<inertia ixx="4553.605E-06" ixy="0.005E-06" ixz="0.817E-06" iyy="5688.730E-06" iyz="-345.157E-06" izz="3548.907E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hip_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_hip_yaw_joint" type="revolute">
<origin xyz="0 0.0875 -0.1632" rpy="0 0 0"/>
<parent link="pelvis"/>
<child link="left_hip_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="-0.43" upper="0.43" effort="200" velocity="23"/>
</joint>
<link name="left_hip_pitch_link">
<inertial>
<origin xyz="-0.00781 -0.004724 -0.000063" rpy="0 0 0"/>
<mass value="2.920"/>
<inertia ixx="5594.7E-06" ixy="143.308E-06" ixz="-11.847E-06" iyy="3862.581E-06" iyz="-9.607E-06" izz="4450.563E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hip_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_hip_pitch_joint" type="revolute">
<origin xyz="0 0.0755 0" rpy="0 0 0"/>
<parent link="left_hip_yaw_link"/>
<child link="left_hip_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-3.14" upper="2.5" effort="200" velocity="23"/>
</joint>
<link name="left_hip_roll_link">
<inertial>
<origin xyz="0.004171 -0.008576 -0.194509" rpy="0 0 0"/>
<mass value="4.962"/>
<inertia ixx="46305.869E-06" ixy="-322.626E-06" ixz="-1199.703E-06" iyy="47955.402E-06" iyz="288.147E-06" izz="8914.518E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_hip_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_hip_roll_joint" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="left_hip_pitch_link"/>
<child link="left_hip_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-0.43" upper="3.14" effort="200" velocity="23"/>
</joint>
<link name="left_knee_link">
<inertial>
<origin xyz="0.000179 0.000121 -0.168936" rpy="0 0 0"/>
<mass value="3.839"/>
<inertia ixx="39002.363e-6" ixy="-72.364e-6" ixz="-794.506e-6" iyy="39042.376e-6" iyz="-18.663e-6" izz="5029.829e-6"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_knee_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.2" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.02" length="0.2"/>
</geometry>
</collision>
</link>
<joint name="left_knee_joint" type="revolute">
<origin xyz="0 0 -0.4" rpy="0 0 0"/>
<parent link="left_hip_roll_link"/>
<child link="left_knee_link"/>
<axis xyz="0 1 0"/>
<limit lower="-0.26" upper="2.05" effort="300" velocity="14"/>
</joint>
<link name="left_ankle_pitch_link">
<inertial>
<origin xyz="-0.000294 0 -0.010794" rpy="0 0 0"/>
<mass value="0.102"/>
<inertia ixx="0.000023944" ixy="0" ixz="0.000000121" iyy="0.000021837" iyz="0" izz="0.000013414"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_ankle_pitch_joint" type="revolute">
<origin xyz="0 0 -0.4" rpy="0 0 0"/>
<parent link="left_knee_link"/>
<child link="left_ankle_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-0.897334" upper="0.523598" effort="60" velocity="9"/>
</joint>
<link name="left_ankle_roll_link">
<inertial>
<origin xyz="0.029589 0 -0.015973" rpy="0 0 0"/>
<mass value="0.747"/>
<inertia ixx="648.830e-6" ixy="0" ixz="158.380e-6" iyy="3435.339e-6" iyz="0" izz="3583.259e-6"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_ankle_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_ankle_roll_link.STL"/>
</geometry>
</collision>
</link>
<joint name="left_ankle_roll_joint" type="revolute">
<origin xyz="0 0 -0.02" rpy="0 0 0"/>
<parent link="left_ankle_pitch_link"/>
<child link="left_ankle_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-0.261799" upper="0.261799" effort="40" velocity="9"/>
</joint>
<!-- R Leg -->
<link name="right_hip_yaw_link">
<inertial>
<origin xyz="0 0.026197 0.006647" rpy="0 0 0"/>
<mass value="2.829"/>
<inertia ixx="4553.605E-06" ixy="-0.005E-06" ixz="0.817E-06" iyy="5688.730E-06" iyz="345.157E-06" izz="3548.907E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hip_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_hip_yaw_joint" type="revolute">
<origin xyz="0 -0.0875 -0.1632" rpy="0 0 0"/>
<parent link="pelvis"/>
<child link="right_hip_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="-0.43" upper="0.43" effort="200" velocity="23"/>
</joint>
<link name="right_hip_pitch_link">
<inertial>
<origin xyz="-0.00781 0.004724 -0.000063" rpy="0 0 0"/>
<mass value="2.920"/>
<inertia ixx="5594.7E-06" ixy="-143.308E-06" ixz="-11.847E-06" iyy="3862.581E-06" iyz="9.607E-06" izz="4450.563E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hip_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_hip_pitch_joint" type="revolute">
<origin xyz="0 -0.0755 0" rpy="0 0 0"/>
<parent link="right_hip_yaw_link"/>
<child link="right_hip_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-3.14" upper="2.5" effort="200" velocity="23"/>
</joint>
<link name="right_hip_roll_link">
<inertial>
<origin xyz="0.004171 0.008576 -0.194509" rpy="0 0 0"/>
<mass value="4.962"/>
<inertia ixx="46305.869E-06" ixy="322.626E-06" ixz="-1199.703E-06" iyy="47955.402E-06" iyz="-288.147E-06" izz="8914.518E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_hip_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_hip_roll_joint" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="right_hip_pitch_link"/>
<child link="right_hip_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-3.14" upper="0.43" effort="200" velocity="23"/>
</joint>
<link name="right_knee_link">
<inertial>
<origin xyz="0.000179 -0.000121 -0.168936" rpy="0 0 0"/>
<mass value="3.839"/>
<inertia ixx="39002.363e-6" ixy="72.364e-6" ixz="-794.506e-6" iyy="39042.376e-6" iyz="18.663e-6" izz="5029.829e-6"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_knee_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.2" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.02" length="0.2"/>
</geometry>
</collision>
</link>
<joint name="right_knee_joint" type="revolute">
<origin xyz="0 0 -0.4" rpy="0 0 0"/>
<parent link="right_hip_roll_link"/>
<child link="right_knee_link"/>
<axis xyz="0 1 0"/>
<limit lower="-0.26" upper="2.05" effort="300" velocity="14"/>
</joint>
<link name="right_ankle_pitch_link">
<inertial>
<origin xyz="-0.000294 0 -0.010794" rpy="0 0 0"/>
<mass value="0.102"/>
<inertia ixx="0.000023944" ixy="0" ixz="0.000000121" iyy="0.000021837" iyz="0" izz="0.000013414"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_ankle_pitch_joint" type="revolute">
<origin xyz="0 0 -0.4" rpy="0 0 0"/>
<parent link="right_knee_link"/>
<child link="right_ankle_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-0.897334" upper="0.523598" effort="60" velocity="9"/>
</joint>
<link name="right_ankle_roll_link">
<inertial>
<origin xyz="0.029589 0 -0.015973" rpy="0 0 0"/>
<mass value="0.747"/>
<inertia ixx="648.830e-6" ixy="0" ixz="158.380e-6" iyy="3435.339e-6" iyz="0" izz="3583.259e-6"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ankle_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ankle_roll_link.STL"/>
</geometry>
</collision>
</link>
<joint name="right_ankle_roll_joint" type="revolute">
<origin xyz="0 0 -0.02" rpy="0 0 0"/>
<parent link="right_ankle_pitch_link"/>
<child link="right_ankle_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-0.261799" upper="0.261799" effort="40" velocity="9"/>
</joint>
<!-- Torso -->
<link name="torso_link">
<inertial>
<origin xyz="0.000489 0.002797 0.20484" rpy="0 0 0"/>
<mass value="17.789"/>
<inertia ixx="0.4873" ixy="-0.00053763" ixz="0.0020276" iyy="0.40963" iyz="-0.00074582" izz="0.12785"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/torso_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<box size="0.08 0.16 0.1"/>
</geometry>
</collision>
</link>
<joint name="torso_joint" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="pelvis"/>
<child link="torso_link"/>
<axis xyz="0 0 1"/>
<limit lower="-2.35" upper="2.35" effort="200" velocity="23"/>
</joint>
<!-- L arm -->
<link name="left_shoulder_pitch_link">
<inertial>
<origin xyz="0.003053 0.06042 -0.0059" rpy="0 0 0"/>
<mass value="1.327"/>
<inertia ixx="0.00058661" ixy="-2.0157E-05" ixz="2.985E-06" iyy="0.0003989" iyz="2.238E-05" izz="0.00052936"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_shoulder_pitch_joint" type="revolute">
<origin xyz="0 0.14806 0.42333" rpy="0.2618 0 0"/>
<parent link="torso_link"/>
<child link="left_shoulder_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-3.14" upper="1.57" effort="40" velocity="9"/>
</joint>
<link name="left_shoulder_roll_link">
<inertial>
<origin xyz="-0.030932 -1E-06 -0.10609" rpy="0 0 0"/>
<mass value="1.393"/>
<inertia ixx="0.0018408" ixy="3.98E-07" ixz="-0.00048324" iyy="0.001934638" iyz="1.61E-07" izz="0.000617733"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_shoulder_roll_joint" type="revolute">
<origin xyz="0.0342 0.061999 -0.0060011" rpy="-0.2618 0 0"/>
<parent link="left_shoulder_pitch_link"/>
<child link="left_shoulder_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-0.38" upper="3.4" effort="40" velocity="9"/>
</joint>
<link name="left_shoulder_yaw_link">
<inertial>
<origin xyz="0.004583 0.001128 -0.001128" rpy="0 0 0"/>
<mass value="1.505"/>
<inertia ixx="0.004199" ixy="-1.7786E-05" ixz="0.00018372" iyy="0.0043139" iyz="9.278E-05" izz="0.00065755"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_shoulder_yaw_joint" type="revolute">
<origin xyz="-0.0342 0 -0.1456" rpy="0 0 0"/>
<parent link="left_shoulder_roll_link"/>
<child link="left_shoulder_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="-3.01" upper="2.66" effort="18" velocity="20"/>
</joint>
<link name="left_elbow_pitch_link">
<inertial>
<origin xyz="0.077092 -0.028751 -0.009714 " rpy="0 0 0"/>
<mass value="0.691"/>
<inertia ixx="0.000318491" ixy="0.000224554" ixz="6.62076E-05" iyy="0.000861224" iyz="-2.3329E-05" izz="0.000897899"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_elbow_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_elbow_pitch_joint" type="revolute">
<origin xyz="0.006 0.0329 -0.182" rpy="0 0 0"/>
<parent link="left_shoulder_yaw_link"/>
<child link="left_elbow_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-2.53" upper="1.6" effort="18" velocity="20"/>
</joint>
<link name="left_elbow_roll_link">
<inertial>
<origin xyz="0.035281 -0.002320 0.000337" rpy="0 0 0"/>
<mass value="0.683"/>
<inertia ixx="0.000313275" ixy="0.000016521" ixz="-0.000002501" iyy="0.000310412" iyz="0.000005435" izz="0.000345998"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_elbow_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_elbow_roll_joint" type="fixed">
<origin xyz="0.121 -0.0329 -0.011" rpy="0 0 0"/>
<parent link="left_elbow_pitch_link"/>
<child link="left_elbow_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-2.967" upper="2.967" effort="19" velocity="31.4"/>
</joint>
<link name="left_wrist_pitch_link">
<inertial>
<origin xyz="0.020395 0.000036 -0.002973" rpy="0 0 0"/>
<mass value="0.484"/>
<inertia ixx="0.000071364" ixy="0.000000308" ixz="0.000001485" iyy="0.000069915" iyz="-0.000000088" izz="0.000070702"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/left_wrist_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_wrist_pitch_joint" type="fixed">
<origin xyz="0.085 0 0" rpy="0 0 0"/>
<parent link="left_elbow_roll_link"/>
<child link="left_wrist_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-0.471" upper="0.349" effort="19" velocity="31.4"/>
</joint>
<link name="left_wrist_yaw_link">
<inertial>
<origin xyz="0.027967 0.000096 0.000739" rpy="0 0 0"/>
<mass value="0.124"/>
<inertia ixx="137.3e-6" ixy="-0.171e-6" ixz="2.942e-6" iyy="169.998e-6" iyz="-0.025e-6" izz="84.808e-6"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/wrist_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="left_wrist_yaw_joint" type="fixed">
<origin xyz="0.020 0 0" rpy="0 0 0"/>
<parent link="left_wrist_pitch_link"/>
<child link="left_wrist_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="-1.012" upper="1.012" effort="19" velocity="31.4"/>
</joint>
<!-- R arm -->
<link name="right_shoulder_pitch_link">
<inertial>
<origin xyz="0.003053 -0.06042 -0.0059" rpy="0 0 0"/>
<mass value="1.327"/>
<inertia ixx="0.00058661" ixy="2.0157E-05" ixz="2.985E-06" iyy="0.0003989" iyz="-2.238E-05" izz="0.00052936"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_shoulder_pitch_joint" type="revolute">
<origin xyz="0 -0.14806 0.42333" rpy="-0.2618 0 0"/>
<parent link="torso_link"/>
<child link="right_shoulder_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-1.57" upper="3.14" effort="40" velocity="9"/>
</joint>
<link name="right_shoulder_roll_link">
<inertial>
<origin xyz="-0.030932 1E-06 -0.10609" rpy="0 0 0"/>
<mass value="1.393"/>
<inertia ixx="0.0018408" ixy="-3.98E-07" ixz="-0.00048324" iyy="0.001934638" iyz="-1.61E-07" izz="0.000617733"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_shoulder_roll_joint" type="revolute">
<origin xyz="0.0342 -0.061999 -0.0060011" rpy="0.2618 0 0"/>
<parent link="right_shoulder_pitch_link"/>
<child link="right_shoulder_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-3.4" upper="0.38" effort="40" velocity="9"/>
</joint>
<link name="right_shoulder_yaw_link">
<inertial>
<origin xyz="0.004583 -0.001128 -0.001128" rpy="0 0 0"/>
<mass value="1.505"/>
<inertia ixx="0.004199" ixy="1.7786E-05" ixz="0.00018372" iyy="0.0043139" iyz="-9.278E-05" izz="0.00065755"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_shoulder_yaw_joint" type="revolute">
<origin xyz="-0.0342 0 -0.1456" rpy="0 0 0"/>
<parent link="right_shoulder_roll_link"/>
<child link="right_shoulder_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="-2.66" upper="3.01" effort="18" velocity="20"/>
</joint>
<link name="right_elbow_pitch_link">
<inertial>
<origin xyz="0.077092 0.028751 -0.009714 " rpy="0 0 0"/>
<mass value="0.691"/>
<inertia ixx="0.000318491" ixy="-0.000224554" ixz="6.62076E-05" iyy="0.000861224" iyz="2.3329E-05" izz="0.000897899"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_elbow_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_elbow_pitch_joint" type="revolute">
<origin xyz="0.006 -0.0329 -0.182" rpy="0 0 0"/>
<parent link="right_shoulder_yaw_link"/>
<child link="right_elbow_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-1.6" upper="2.53" effort="18" velocity="20"/>
</joint>
<link name="right_elbow_roll_link">
<inertial>
<origin xyz="0.035281 -0.002320 0.000337" rpy="0 0 0"/>
<mass value="0.683"/>
<inertia ixx="0.000313275" ixy="0.000016521" ixz="-0.000002501" iyy="0.000310412" iyz="0.000005435" izz="0.000345998"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_elbow_roll_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_elbow_roll_joint" type="fixed">
<origin xyz="0.121 0.0329 -0.011" rpy="0 0 0"/>
<parent link="right_elbow_pitch_link"/>
<child link="right_elbow_roll_link"/>
<axis xyz="1 0 0"/>
<limit lower="-2.967" upper="2.967" effort="19" velocity="31.4"/>
</joint>
<link name="right_wrist_pitch_link">
<inertial>
<origin xyz="0.020395 0.000036 -0.002973" rpy="0 0 0"/>
<mass value="0.484"/>
<inertia ixx="0.000071364" ixy="0.000000308" ixz="0.000001485" iyy="0.000069915" iyz="-0.000000088" izz="0.000070702"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_wrist_pitch_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_wrist_pitch_joint" type="fixed">
<origin xyz="0.085 0 0" rpy="0 0 0"/>
<parent link="right_elbow_roll_link"/>
<child link="right_wrist_pitch_link"/>
<axis xyz="0 1 0"/>
<limit lower="-0.471" upper="0.349" effort="19" velocity="31.4"/>
</joint>
<link name="right_wrist_yaw_link">
<inertial>
<origin xyz="0.027967 -0.000096 0.000739" rpy="0 0 0"/>
<mass value="0.124"/>
<inertia ixx="137.3e-6" ixy="0.171e-6" ixz="2.942e-6" iyy="169.998e-6" iyz="0.025e-6" izz="84.808e-6"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/wrist_yaw_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="right_wrist_yaw_joint" type="fixed">
<origin xyz="0.020 0 0" rpy="0 0 0"/>
<parent link="right_wrist_pitch_link"/>
<child link="right_wrist_yaw_link"/>
<axis xyz="0 0 1"/>
<limit lower="-1.012" upper="1.012" effort="19" velocity="31.4"/>
</joint>
<!-- LOGO -->
<link name="logo_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/logo_link.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
</link>
<joint name="logo_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="torso_link"/>
<child link="logo_link"/>
<axis xyz="0 0 0"/>
</joint>
<!-- IMU -->
<link name="imu_link"></link>
<joint name="imu_joint" type="fixed">
<origin xyz="-0.04233868314 0.00166 0.152067" rpy="0 0 0"/>
<parent link="torso_link"/>
<child link="imu_link"/>
</joint>
<!-- L Gripper -->
<joint name="L_base_link_joint" type="fixed">
<origin xyz="0.054 0 0" rpy="0 0 1.5707963267948966192313216916398"/>
<parent link="left_wrist_yaw_link"/>
<child link="L_hand_base_link"/>
</joint>
<link name="L_hand_base_link">
<inertial>
<origin xyz="-0.002551 -0.066047 -0.0019357" rpy="0 0 0"/>
<mass value="0.14143"/>
<inertia ixx="0.0001234" ixy="2.1995E-06" ixz="-1.7694E-06" iyy="8.3835E-05" iyz="1.5968E-06" izz="7.7231E-05"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/L_hand_base_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<link name="L_thumb_proximal_base">
<inertial>
<origin xyz="0.0048817 0.00038782 -0.00722" rpy="0 0 0"/>
<mass value="0.0018869"/>
<inertia ixx="5.5158E-08" ixy="-1.1803E-08" ixz="-4.6743E-09" iyy="8.2164E-08" iyz="-1.3521E-09" izz="6.7434E-08"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link11_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_thumb_proximal_yaw_joint" type="fixed">
<origin xyz="-0.01696 -0.0691 0.02045" rpy="1.5708 -1.5708 0"/>
<parent link="L_hand_base_link"/>
<child link="L_thumb_proximal_base"/>
<axis xyz="0 0 1"/>
<limit lower="-0.1" upper="1.3" effort="1" velocity="0.5"/>
</joint>
<link name="L_thumb_proximal">
<inertial>
<origin xyz="0.021936 -0.01279 -0.0080386" rpy="0 0 0"/>
<mass value="0.0066101"/>
<inertia ixx="1.5693E-06" ixy="7.8339E-07" ixz="8.5959E-10" iyy="1.7356E-06" iyz="1.0378E-09" izz="2.787E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link12_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_thumb_proximal_pitch_joint" type="fixed">
<origin xyz="0.0099867 0.0098242 -0.0089" rpy="-1.5708 0 0.16939"/>
<parent link="L_thumb_proximal_base"/>
<child link="L_thumb_proximal"/>
<axis xyz="0 0 -1"/>
<limit lower="-0.1" upper="0.6" effort="1" velocity="0.5"/>
</joint>
<link name="L_thumb_intermediate">
<inertial>
<origin xyz="0.0095531 0.0016282 -0.0072002" rpy="0 0 0"/>
<mass value="0.0037844"/>
<inertia ixx="3.6981E-07" ixy="9.8603E-08" ixz="-2.8173E-12" iyy="3.2395E-07" iyz="-2.8028E-12" izz="4.6532E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link13_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_thumb_intermediate_joint" type="fixed">
<origin xyz="0.04407 -0.034553 -0.0008" rpy="0 0 0"/>
<parent link="L_thumb_proximal"/>
<child link="L_thumb_intermediate"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="0.8" effort="1" velocity="0.5"/>
<mimic joint="L_thumb_proximal_pitch_joint" multiplier="1.6" offset="0"/>
</joint>
<link name="L_thumb_distal">
<inertial>
<origin xyz="0.0092888 -0.004953 -0.0060033" rpy="0 0 0"/>
<mass value="0.003344"/>
<inertia ixx="1.3632E-07" ixy="5.6787E-08" ixz="-9.1939E-11" iyy="1.4052E-07" iyz="1.2145E-10" izz="2.0026E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link14_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_thumb_distal_joint" type="fixed">
<origin xyz="0.020248 -0.010156 -0.0012" rpy="0 0 0"/>
<parent link="L_thumb_intermediate"/>
<child link="L_thumb_distal"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.2" effort="1" velocity="0.5"/>
<mimic joint="L_thumb_proximal_pitch_joint" multiplier="2.4" offset="0"/>
</joint>
<link name="L_index_proximal">
<inertial>
<origin xyz="0.0012971 -0.011934 -0.0059998" rpy="0 0 0"/>
<mass value="0.0042405"/>
<inertia ixx="6.6215E-07" ixy="1.8442E-08" ixz="1.3746E-12" iyy="2.1167E-07" iyz="-1.4773E-11" izz="6.9402E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link15_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_index_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.13653 0.032268" rpy="-0.034907 0 0"/>
<parent link="L_hand_base_link"/>
<child link="L_index_proximal"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="L_index_intermediate">
<inertial>
<origin xyz="0.0021753 -0.019567 -0.005" rpy="0 0 0"/>
<mass value="0.0045682"/>
<inertia ixx="7.6284E-07" ixy="-8.063E-08" ixz="3.6797E-13" iyy="9.4308E-08" iyz="1.5743E-13" izz="7.8176E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link16_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_index_intermediate_joint" type="fixed">
<origin xyz="-0.0024229 -0.032041 -0.001" rpy="0 0 0"/>
<parent link="L_index_proximal"/>
<child link="L_index_intermediate"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="L_index_proximal_joint" multiplier="1" offset="0"/>
</joint>
<link name="L_middle_proximal">
<inertial>
<origin xyz="0.0012971 -0.011934 -0.0059999" rpy="0 0 0"/>
<mass value="0.0042405"/>
<inertia ixx="6.6215E-07" ixy="1.8442E-08" ixz="1.2299E-12" iyy="2.1167E-07" iyz="-1.4484E-11" izz="6.9402E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link17_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_middle_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.1371 0.01295" rpy="0 0 0"/>
<parent link="L_hand_base_link"/>
<child link="L_middle_proximal"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="L_middle_intermediate">
<inertial>
<origin xyz="0.001921 -0.020796 -0.0049999" rpy="0 0 0"/>
<mass value="0.0050397"/>
<inertia ixx="9.5823E-07" ixy="-1.1425E-07" ixz="-2.4186E-12" iyy="1.0646E-07" iyz="3.6974E-12" izz="9.8385E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link18_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_middle_intermediate_joint" type="fixed">
<origin xyz="-0.0024229 -0.032041 -0.001" rpy="0 0 0"/>
<parent link="L_middle_proximal"/>
<child link="L_middle_intermediate"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="L_middle_proximal_joint" multiplier="1" offset="0"/>
</joint>
<link name="L_ring_proximal">
<inertial>
<origin xyz="0.0012971 -0.011934 -0.0059999" rpy="0 0 0"/>
<mass value="0.0042405"/>
<inertia ixx="6.6215E-07" ixy="1.8442E-08" ixz="9.6052E-13" iyy="2.1167E-07" iyz="-1.4124E-11" izz="6.9402E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link19_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_ring_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.13691 -0.0062872" rpy="0.05236 0 0"/>
<parent link="L_hand_base_link"/>
<child link="L_ring_proximal"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="L_ring_intermediate">
<inertial>
<origin xyz="0.0021753 -0.019567 -0.005" rpy="0 0 0"/>
<mass value="0.0045682"/>
<inertia ixx="7.6285E-07" ixy="-8.0631E-08" ixz="3.3472E-14" iyy="9.4308E-08" iyz="-4.4773E-13" izz="7.8176E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link20_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_ring_intermediate_joint" type="fixed">
<origin xyz="-0.0024229 -0.032041 -0.001" rpy="0 0 0"/>
<parent link="L_ring_proximal"/>
<child link="L_ring_intermediate"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="L_ring_proximal_joint" multiplier="1" offset="0"/>
</joint>
<link name="L_pinky_proximal">
<inertial>
<origin xyz="0.0012971 -0.011934 -0.0059999" rpy="0 0 0"/>
<mass value="0.0042405"/>
<inertia ixx="6.6215E-07" ixy="1.8442E-08" ixz="1.0279E-12" iyy="2.1167E-07" iyz="-1.4277E-11" izz="6.9402E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link21_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_pinky_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.13571 -0.025488" rpy="0.10472 0 0"/>
<parent link="L_hand_base_link"/>
<child link="L_pinky_proximal"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="L_pinky_intermediate">
<inertial>
<origin xyz="0.0024788 -0.016208 -0.0050001" rpy="0 0 0"/>
<mass value="0.0036036"/>
<inertia ixx="4.3923E-07" ixy="-4.1355E-08" ixz="1.2263E-12" iyy="7.0315E-08" iyz="3.1311E-12" izz="4.4881E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link22_L.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="L_pinky_intermediate_joint" type="fixed">
<origin xyz="-0.0024229 -0.032041 -0.001" rpy="0 0 0"/>
<parent link="L_pinky_proximal"/>
<child link="L_pinky_intermediate"/>
<axis xyz="0 0 -1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="L_pinky_proximal_joint" multiplier="1" offset="0"/>
</joint>
<!-- R Gripper -->
<joint name="R_base_link_joint" type="fixed">
<origin xyz="0.054 0 0" rpy="3.1415926535897932384626433832795 0 -1.5707963267948966192313216916398"/>
<parent link="right_wrist_yaw_link"/>
<child link="R_hand_base_link"/>
</joint>
<link name="R_hand_base_link">
<inertial>
<origin xyz="-0.0025264 -0.066047 0.0019598" rpy="0 0 0"/>
<mass value="0.14143"/>
<inertia ixx="0.00012281" ixy="2.1711E-06" ixz="1.7709E-06" iyy="8.3832E-05" iyz="-1.6551E-06" izz="7.6663E-05"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/R_hand_base_link.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<link name="R_thumb_proximal_base">
<inertial>
<origin xyz="-0.0048064 0.0009382 -0.00757" rpy="0 0 0"/>
<mass value="0.0018869"/>
<inertia ixx="5.816E-08" ixy="1.4539E-08" ixz="4.491E-09" iyy="7.9161E-08" iyz="-1.8727E-09" izz="6.7433E-08"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link11_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_thumb_proximal_yaw_joint" type="fixed">
<origin xyz="-0.01696 -0.0691 -0.02045" rpy="1.5708 -1.5708 0"/>
<parent link="R_hand_base_link"/>
<child link="R_thumb_proximal_base"/>
<axis xyz="0 0 -1"/>
<limit lower="-0.1" upper="1.3" effort="1" velocity="0.5"/>
</joint>
<link name="R_thumb_proximal">
<inertial>
<origin xyz="0.021932 0.012785 -0.0080386" rpy="0 0 0"/>
<mass value="0.0066075"/>
<inertia ixx="1.5686E-06" ixy="-7.8296E-07" ixz="8.9143E-10" iyy="1.7353E-06" iyz="-1.0191E-09" izz="2.786E-06"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link12_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_thumb_proximal_pitch_joint" type="fixed">
<origin xyz="-0.0088099 0.010892 -0.00925" rpy="1.5708 0 2.8587"/>
<parent link="R_thumb_proximal_base"/>
<child link="R_thumb_proximal"/>
<axis xyz="0 0 1"/>
<limit lower="-0.1" upper="0.6" effort="1" velocity="0.5"/>
</joint>
<link name="R_thumb_intermediate">
<inertial>
<origin xyz="0.0095544 -0.0016282 -0.0071997" rpy="0 0 0"/>
<mass value="0.0037847"/>
<inertia ixx="3.6981E-07" ixy="-9.8581E-08" ixz="-4.7469E-12" iyy="3.2394E-07" iyz="1.0939E-12" izz="4.6531E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link13_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_thumb_intermediate_joint" type="fixed">
<origin xyz="0.04407 0.034553 -0.0008" rpy="0 0 0"/>
<parent link="R_thumb_proximal"/>
<child link="R_thumb_intermediate"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="0.8" effort="1" velocity="0.5"/>
<mimic joint="R_thumb_proximal_pitch_joint" multiplier="1.6" offset="0"/>
</joint>
<link name="R_thumb_distal">
<inertial>
<origin xyz="0.0092888 0.0049529 -0.0060033" rpy="0 0 0"/>
<mass value="0.0033441"/>
<inertia ixx="1.3632E-07" ixy="-5.6788E-08" ixz="-9.2764E-11" iyy="1.4052E-07" iyz="-1.2283E-10" izz="2.0026E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link14_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_thumb_distal_joint" type="fixed">
<origin xyz="0.020248 0.010156 -0.0012" rpy="0 0 0"/>
<parent link="R_thumb_intermediate"/>
<child link="R_thumb_distal"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.2" effort="1" velocity="0.5"/>
<mimic joint="R_thumb_proximal_pitch_joint" multiplier="2.4" offset="0"/>
</joint>
<link name="R_index_proximal">
<inertial>
<origin xyz="0.0012259 0.011942 -0.0060001" rpy="0 0 0"/>
<mass value="0.0042403"/>
<inertia ixx="6.6232E-07" ixy="-1.5775E-08" ixz="1.8515E-12" iyy="2.1146E-07" iyz="-5.0828E-12" izz="6.9398E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link15_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_index_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.13653 -0.032268" rpy="-3.1067 0 0"/>
<parent link="R_hand_base_link"/>
<child link="R_index_proximal"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="R_index_intermediate">
<inertial>
<origin xyz="0.0019697 0.019589 -0.005" rpy="0 0 0"/>
<mass value="0.0045683"/>
<inertia ixx="7.6111E-07" ixy="8.7637E-08" ixz="-3.7751E-13" iyy="9.6076E-08" iyz="9.9444E-13" izz="7.8179E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link16_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_index_intermediate_joint" type="fixed">
<origin xyz="-0.0026138 0.032026 -0.001" rpy="0 0 0"/>
<parent link="R_index_proximal"/>
<child link="R_index_intermediate"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="R_index_proximal_joint" multiplier="1" offset="0"/>
</joint>
<link name="R_middle_proximal">
<inertial>
<origin xyz="0.001297 0.011934 -0.0060001" rpy="0 0 0"/>
<mass value="0.0042403"/>
<inertia ixx="6.6211E-07" ixy="-1.8461E-08" ixz="1.8002E-12" iyy="2.1167E-07" iyz="-6.6808E-12" izz="6.9397E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link17_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_middle_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.1371 -0.01295" rpy="-3.1416 0 0"/>
<parent link="R_hand_base_link"/>
<child link="R_middle_proximal"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="R_middle_intermediate">
<inertial>
<origin xyz="0.001921 0.020796 -0.005" rpy="0 0 0"/>
<mass value="0.0050396"/>
<inertia ixx="9.5822E-07" ixy="1.1425E-07" ixz="-2.4791E-12" iyy="1.0646E-07" iyz="5.9173E-12" izz="9.8384E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link18_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_middle_intermediate_joint" type="fixed">
<origin xyz="-0.0024229 0.032041 -0.001" rpy="0 0 0"/>
<parent link="R_middle_proximal"/>
<child link="R_middle_intermediate"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="R_middle_proximal_joint" multiplier="1" offset="0"/>
</joint>
<link name="R_ring_proximal">
<inertial>
<origin xyz="0.001297 0.011934 -0.0060002" rpy="0 0 0"/>
<mass value="0.0042403"/>
<inertia ixx="6.6211E-07" ixy="-1.8461E-08" ixz="1.5793E-12" iyy="2.1167E-07" iyz="-6.6868E-12" izz="6.9397E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link19_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_ring_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.13691 0.0062872" rpy="3.0892 0 0"/>
<parent link="R_hand_base_link"/>
<child link="R_ring_proximal"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="R_ring_intermediate">
<inertial>
<origin xyz="0.0021753 0.019567 -0.005" rpy="0 0 0"/>
<mass value="0.0045683"/>
<inertia ixx="7.6286E-07" ixy="8.0635E-08" ixz="-6.1562E-13" iyy="9.431E-08" iyz="5.8619E-13" izz="7.8177E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link20_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_ring_intermediate_joint" type="fixed">
<origin xyz="-0.0024229 0.032041 -0.001" rpy="0 0 0"/>
<parent link="R_ring_proximal"/>
<child link="R_ring_intermediate"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="R_ring_proximal_joint" multiplier="1" offset="0"/>
</joint>
<link name="R_pinky_proximal">
<inertial>
<origin xyz="0.001297 0.011934 -0.0060001" rpy="0 0 0"/>
<mass value="0.0042403"/>
<inertia ixx="6.6211E-07" ixy="-1.8461E-08" ixz="1.6907E-12" iyy="2.1167E-07" iyz="-6.9334E-12" izz="6.9397E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link21_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_pinky_proximal_joint" type="fixed">
<origin xyz="0.00028533 -0.13571 0.025488" rpy="3.0369 0 0"/>
<parent link="R_hand_base_link"/>
<child link="R_pinky_proximal"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
</joint>
<link name="R_pinky_intermediate">
<inertial>
<origin xyz="0.0024748 0.016203 -0.0050031" rpy="0 0 0"/>
<mass value="0.0035996"/>
<inertia ixx="4.3913E-07" ixy="4.1418E-08" ixz="3.7168E-11" iyy="7.0247E-08" iyz="5.8613E-11" izz="4.4867E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/link22_R.STL"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<joint name="R_pinky_intermediate_joint" type="fixed">
<origin xyz="-0.0024229 0.032041 -0.001" rpy="0 0 0"/>
<parent link="R_pinky_proximal"/>
<child link="R_pinky_intermediate"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="1.7" effort="1" velocity="0.5"/>
<mimic joint="R_pinky_proximal_joint" multiplier="1" offset="0"/>
</joint>
</robot>