| <?xml version="1.0" encoding="utf-8"?>
|
| <robot name="dual_arm_piper">
|
|
|
|
|
| <link name="base_link"/>
|
|
|
|
|
|
|
| <link name="left_base_link">
|
| <inertial>
|
| <origin xyz="-0.00473641164191482 2.56829134630247E-05 0.041451518036016" rpy="0 0 0"/>
|
| <mass value="1.02"/>
|
| <inertia ixx="0.00267433" ixy="-0.00000073" ixz="-0.00017389" iyy="0.00282612" iyz="0.0000004" izz="0.00089624"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/base_link.STL"/>
|
| </geometry>
|
| <material name="silver">
|
| <color rgba="0.792 0.819 0.933 1"/>
|
| </material>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/base_link.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="base_link_to_left_base" type="fixed">
|
| <origin xyz="0 0 0" rpy="0 0 0"/>
|
| <parent link="base_link"/>
|
| <child link="left_base_link"/>
|
| </joint>
|
|
|
|
|
| <link name="left_link1">
|
| <inertial>
|
| <origin xyz="0.000121504734057468 0.000104632162460536 -0.00438597309559853" rpy="0 0 0"/>
|
| <mass value="0.71"/>
|
| <inertia ixx="0.00048916" ixy="-0.00000036" ixz="-0.00000224" iyy="0.00040472" iyz="-0.00000242" izz="0.00043982"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link1.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link1.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint1" type="revolute">
|
| <origin xyz="0 0 0.123" rpy="0 0 0"/>
|
| <parent link="left_base_link"/>
|
| <child link="left_link1"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-2.618" upper="2.168" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="left_link2">
|
| <inertial>
|
| <origin xyz="0.198666145229743 -0.010926924140076 0.00142121714502687" rpy="0 0 0"/>
|
| <mass value="1.17"/>
|
| <inertia ixx="0.00116918" ixy="-0.00180037" ixz="0.00025146" iyy="0.06785384" iyz="-0.00000455" izz="0.06774489"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link2.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link2.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint2" type="revolute">
|
| <origin xyz="0 0 0" rpy="1.5708 -0.1359 -3.1416"/>
|
| <parent link="left_link1"/>
|
| <child link="left_link2"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="0" upper="3.14" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="left_link3">
|
| <inertial>
|
| <origin xyz="-0.0202737662122021 -0.133914995944595 -0.000458682652737356" rpy="0 0 0"/>
|
| <mass value="0.5"/>
|
| <inertia ixx="0.01361711" ixy="0.00165794" ixz="-0.00000048" iyy="0.00045024" iyz="-0.00000045" izz="0.01380322"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link3.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link3.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint3" type="revolute">
|
| <origin xyz="0.28503 0 0" rpy="0 0 -1.7939"/>
|
| <parent link="left_link2"/>
|
| <child link="left_link3"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-2.967" upper="0" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="left_link4">
|
| <inertial>
|
| <origin xyz="-9.66635791618542E-05 0.000876064475651083 -0.00496880904640868" rpy="0 0 0"/>
|
| <mass value="0.38"/>
|
| <inertia ixx="0.00018501" ixy="0.00000054" ixz="0.00000120" iyy="0.00018965" iyz="-0.00000841" izz="0.00015484"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link4.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link4.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint4" type="revolute">
|
| <origin xyz="-0.021984 -0.25075 0" rpy="1.5708 0 0"/>
|
| <parent link="left_link3"/>
|
| <child link="left_link4"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-1.745" upper="1.745" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="left_link5">
|
| <inertial>
|
| <origin xyz="-4.10554118924211E-05 -0.0566486692356075 -0.0037205791677906" rpy="0 0 0"/>
|
| <mass value="0.383"/>
|
| <inertia ixx="0.00166169" ixy="0.00000006" ixz="-0.00000007" iyy="0.00018510" iyz="0.00001026" izz="0.00164321"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link5.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link5.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint5" type="revolute">
|
| <origin xyz="0 0 0" rpy="-1.5708 0 0"/>
|
| <parent link="left_link4"/>
|
| <child link="left_link5"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-1.22" upper="1.22" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="left_link6">
|
| <inertial>
|
| <origin xyz="-8.82590762930069E-05 9.0598378529832E-06 -0.002" rpy="0 0 0"/>
|
| <mass value="0.00699089613564366"/>
|
| <inertia ixx="5.73015540542155E-07" ixy="-1.98305403089247E-22" ixz="-7.2791893904596E-23" iyy="5.73015540542155E-07" iyz="-3.4146026640245E-24" izz="1.06738869138926E-06"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link6.STL"/>
|
| </geometry>
|
| <material name="white">
|
| <color rgba="0.898 0.917 0.929 1"/>
|
| </material>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link6.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint6" type="revolute">
|
| <origin xyz="8.8259E-05 -0.091 0" rpy="1.5708 0 0"/>
|
| <parent link="left_link5"/>
|
| <child link="left_link6"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-2.0944" upper="2.0944" effort="100" velocity="3"/>
|
| </joint>
|
|
|
| <link name="left_gripper_base">
|
| <inertial>
|
| <origin xyz="-0.000183807162235591 8.05033155577911E-05 0.0321436689908876" rpy="0 0 0"/>
|
| <mass value="0.45"/>
|
| <inertia ixx="0.00092934" ixy="0.00000034" ixz="-0.00000738" iyy="0.00071447" iyz="0.00000005" izz="0.00039442"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/gripper_base.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/gripper_base.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint6_to_gripper" type="fixed">
|
| <origin xyz="0 0 0" rpy="0 0 0"/>
|
| <parent link="left_link6"/>
|
| <child link="left_gripper_base"/>
|
| </joint>
|
|
|
| <link name="left_link7">
|
| <inertial>
|
| <origin xyz="0.00065123185041968 -0.0491929869131989 0.00972258769184025" rpy="0 0 0"/>
|
| <mass value="0.025"/>
|
| <inertia ixx="0.00007371" ixy="-0.00000113" ixz="0.00000021" iyy="0.00000781" iyz="-0.00001372" izz="0.0000747"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link7.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link7.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint7" type="prismatic">
|
| <origin xyz="0 0 0.1358" rpy="1.5708 0 0"/>
|
| <parent link="left_gripper_base"/>
|
| <child link="left_link7"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="0" upper="0.035" effort="10" velocity="1"/>
|
| </joint>
|
|
|
| <link name="left_link8">
|
| <inertial>
|
| <origin xyz="0.000651231850419722 -0.0491929869131991 0.00972258769184024" rpy="0 0 0"/>
|
| <mass value="0.025"/>
|
| <inertia ixx="0.00007371" ixy="-0.00000113" ixz="0.00000021" iyy="0.00000781" iyz="-0.00001372" izz="0.0000747"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link8.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link8.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="left_joint8" type="prismatic">
|
| <origin xyz="0 0 0.1358" rpy="1.5708 0 -3.1416"/>
|
| <parent link="left_gripper_base"/>
|
| <child link="left_link8"/>
|
| <axis xyz="0 0 -1"/>
|
| <limit lower="-0.035" upper="0" effort="10" velocity="1"/>
|
| </joint>
|
|
|
|
|
|
|
| <link name="right_base_link">
|
| <inertial>
|
| <origin xyz="-0.00473641164191482 2.56829134630247E-05 0.041451518036016" rpy="0 0 0"/>
|
| <mass value="1.02"/>
|
| <inertia ixx="0.00267433" ixy="-0.00000073" ixz="-0.00017389" iyy="0.00282612" iyz="0.0000004" izz="0.00089624"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/base_link.STL"/>
|
| </geometry>
|
| <material name="silver"/>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/base_link.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="base_link_to_right_base" type="fixed">
|
| <origin xyz="0 -0.6 0" rpy="0 0 0"/>
|
| <parent link="base_link"/>
|
| <child link="right_base_link"/>
|
| </joint>
|
|
|
|
|
| <link name="right_link1">
|
| <inertial>
|
| <origin xyz="0.000121504734057468 0.000104632162460536 -0.00438597309559853" rpy="0 0 0"/>
|
| <mass value="0.71"/>
|
| <inertia ixx="0.00048916" ixy="-0.00000036" ixz="-0.00000224" iyy="0.00040472" iyz="-0.00000242" izz="0.00043982"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link1.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link1.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint1" type="revolute">
|
| <origin xyz="0 0 0.123" rpy="0 0 0"/>
|
| <parent link="right_base_link"/>
|
| <child link="right_link1"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-2.618" upper="2.168" effort="100" velocity="5"/>
|
| </joint>
|
|
|
|
|
| <link name="right_link2">
|
| <inertial>
|
| <origin xyz="0.198666145229743 -0.010926924140076 0.00142121714502687" rpy="0 0 0"/>
|
| <mass value="1.17"/>
|
| <inertia ixx="0.00116918" ixy="-0.00180037" ixz="0.00025146" iyy="0.06785384" iyz="-0.00000455" izz="0.06774489"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link2.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link2.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint2" type="revolute">
|
| <origin xyz="0 0 0" rpy="1.5708 -0.1359 -3.1416"/>
|
| <parent link="right_link1"/>
|
| <child link="right_link2"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="0" upper="3.14" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="right_link3">
|
| <inertial>
|
| <origin xyz="-0.0202737662122021 -0.133914995944595 -0.000458682652737356" rpy="0 0 0"/>
|
| <mass value="0.5"/>
|
| <inertia ixx="0.01361711" ixy="0.00165794" ixz="-0.00000048" iyy="0.00045024" iyz="-0.00000045" izz="0.01380322"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link3.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link3.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint3" type="revolute">
|
| <origin xyz="0.28503 0 0" rpy="0 0 -1.7939"/>
|
| <parent link="right_link2"/>
|
| <child link="right_link3"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-2.967" upper="0" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="right_link4">
|
| <inertial>
|
| <origin xyz="-9.66635791618542E-05 0.000876064475651083 -0.00496880904640868" rpy="0 0 0"/>
|
| <mass value="0.38"/>
|
| <inertia ixx="0.00018501" ixy="0.00000054" ixz="0.00000120" iyy="0.00018965" iyz="-0.00000841" izz="0.00015484"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link4.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link4.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint4" type="revolute">
|
| <origin xyz="-0.021984 -0.25075 0" rpy="1.5708 0 0"/>
|
| <parent link="right_link3"/>
|
| <child link="right_link4"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-1.745" upper="1.745" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="right_link5">
|
| <inertial>
|
| <origin xyz="-4.10554118924211E-05 -0.0566486692356075 -0.0037205791677906" rpy="0 0 0"/>
|
| <mass value="0.383"/>
|
| <inertia ixx="0.00166169" ixy="0.00000006" ixz="-0.00000007" iyy="0.00018510" iyz="0.00001026" izz="0.00164321"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link5.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link5.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint5" type="revolute">
|
| <origin xyz="0 0 0" rpy="-1.5708 0 0"/>
|
| <parent link="right_link4"/>
|
| <child link="right_link5"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-1.22" upper="1.22" effort="100" velocity="5"/>
|
| </joint>
|
|
|
| <link name="right_link6">
|
| <inertial>
|
| <origin xyz="-8.82590762930069E-05 9.0598378529832E-06 -0.002" rpy="0 0 0"/>
|
| <mass value="0.00699089613564366"/>
|
| <inertia ixx="5.73015540542155E-07" ixy="-1.98305403089247E-22" ixz="-7.2791893904596E-23" iyy="5.73015540542155E-07" iyz="-3.4146026640245E-24" izz="1.06738869138926E-06"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link6.STL"/>
|
| </geometry>
|
| <material name="white">
|
| <color rgba="0.898 0.917 0.929 1"/>
|
| </material>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link6.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint6" type="revolute">
|
| <origin xyz="8.8259E-05 -0.091 0" rpy="1.5708 0 0"/>
|
| <parent link="right_link5"/>
|
| <child link="right_link6"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="-2.0944" upper="2.0944" effort="100" velocity="3"/>
|
| </joint>
|
|
|
| <link name="right_gripper_base">
|
| <inertial>
|
| <origin xyz="-0.000183807162235591 8.05033155577911E-05 0.0321436689908876" rpy="0 0 0"/>
|
| <mass value="0.45"/>
|
| <inertia ixx="0.00092934" ixy="0.00000034" ixz="-0.00000738" iyy="0.00071447" iyz="0.00000005" izz="0.00039442"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/gripper_base.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/gripper_base.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint6_to_gripper" type="fixed">
|
| <origin xyz="0 0 0" rpy="0 0 0"/>
|
| <parent link="right_link6"/>
|
| <child link="right_gripper_base"/>
|
| </joint>
|
|
|
| <link name="right_link7">
|
| <inertial>
|
| <origin xyz="0.00065123185041968 -0.0491929869131989 0.00972258769184025" rpy="0 0 0"/>
|
| <mass value="0.025"/>
|
| <inertia ixx="0.00007371" ixy="-0.00000113" ixz="0.00000021" iyy="0.00000781" iyz="-0.00001372" izz="0.0000747"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link7.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link7.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint7" type="prismatic">
|
| <origin xyz="0 0 0.1358" rpy="1.5708 0 0"/>
|
| <parent link="right_gripper_base"/>
|
| <child link="right_link7"/>
|
| <axis xyz="0 0 1"/>
|
| <limit lower="0" upper="0.035" effort="10" velocity="1"/>
|
| </joint>
|
|
|
| <link name="right_link8">
|
| <inertial>
|
| <origin xyz="0.000651231850419722 -0.0491929869131991 0.00972258769184024" rpy="0 0 0"/>
|
| <mass value="0.025"/>
|
| <inertia ixx="0.00007371" ixy="-0.00000113" ixz="0.00000021" iyy="0.00000781" iyz="-0.00001372" izz="0.0000747"/>
|
| </inertial>
|
| <visual>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link8.STL"/>
|
| </geometry>
|
| </visual>
|
| <collision>
|
| <geometry>
|
| <mesh filename="package://piper_description/meshes/link8.STL"/>
|
| </geometry>
|
| </collision>
|
| </link>
|
|
|
| <joint name="right_joint8" type="prismatic">
|
| <origin xyz="0 0 0.1358" rpy="1.5708 0 -3.1416"/>
|
| <parent link="right_gripper_base"/>
|
| <child link="right_link8"/>
|
| <axis xyz="0 0 -1"/>
|
| <limit lower="-0.035" upper="0" effort="10" velocity="1"/>
|
| </joint>
|
| </robot>
|
|
|