<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_gripper">
|
|
|
|
<xacro:property name="scale_finger_length" value="0.9" />
|
|
|
|
<link
|
|
name="link_gripper">
|
|
name="link_gripper">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.013687 0.015548 -0.035364"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.175929" />
|
|
<inertia
|
|
ixx="0.000124"
|
|
ixy="3.7E-05"
|
|
ixz="5.7E-05"
|
|
iyy="0.000217"
|
|
iyz="1.1E-05"
|
|
izz="0.000221" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<!-- rpy="3.1416 0 1.5708" -->
|
|
<!-- rpy="0.0 0 1.5708" -->
|
|
<joint
|
|
name="joint_gripper"
|
|
type="fixed">
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="3.14159 0 -1.5708" />
|
|
<parent
|
|
link="link_wrist_yaw" />
|
|
<child
|
|
link="link_gripper" />
|
|
<axis
|
|
xyz="0 0 0" />
|
|
</joint>
|
|
|
|
<link
|
|
name="link_gripper_finger_left">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.094071 0.011377 0"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.06" />
|
|
<inertia
|
|
ixx="1.1E-05"
|
|
ixy="3.6E-05"
|
|
ixz="0"
|
|
iyy="0.000214"
|
|
iyz="0"
|
|
izz="0.000224" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_finger_left.STL" scale="${scale_finger_length} 1.0 1.0"/>
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_finger_left.STL" scale="${scale_finger_length} 1.0 1.0"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_gripper_finger_left"
|
|
type="revolute">
|
|
<origin
|
|
xyz="-0.047231 -0.010151 -0.04679"
|
|
rpy="2.1762E-15 0.5236 3.1416" />
|
|
<parent
|
|
link="link_gripper" />
|
|
<child
|
|
link="link_gripper_finger_left" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit effort="100" lower="-0.6" upper="0.6" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_gripper_fingertip_left">
|
|
<inertial>
|
|
<origin
|
|
xyz="0 0 0.008126"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.003822" />
|
|
<inertia
|
|
ixx="0"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="0"
|
|
iyz="0"
|
|
izz="1E-06" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_fingertip_left.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.250980392156863 0.250980392156863 0.250980392156863 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_fingertip_left.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_gripper_fingertip_left"
|
|
type="fixed">
|
|
<origin
|
|
xyz="${scale_finger_length * 0.19011} 0.014912 0"
|
|
rpy="-1.5708 -4.774E-15 -2.5545" />
|
|
<parent
|
|
link="link_gripper_finger_left" />
|
|
<child
|
|
link="link_gripper_fingertip_left" />
|
|
<axis
|
|
xyz="0 0 0" />
|
|
</joint>
|
|
|
|
<link
|
|
name="link_gripper_finger_right">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.093921 -0.011351 0"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.06" />
|
|
<inertia
|
|
ixx="1.1E-05"
|
|
ixy="3.6E-05"
|
|
ixz="0"
|
|
iyy="0.000213"
|
|
iyz="0"
|
|
izz="0.000223" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_finger_right.STL" scale="${scale_finger_length} 1.0 1.0"/>
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_finger_right.STL" scale="${scale_finger_length} 1.0 1.0"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_gripper_finger_right"
|
|
type="revolute">
|
|
<origin
|
|
xyz="-0.047231 0.010049 -0.04679"
|
|
rpy="3.1416 -0.5236 1.2943E-15" />
|
|
<parent
|
|
link="link_gripper" />
|
|
<child
|
|
link="link_gripper_finger_right" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit effort="100" lower="-0.6" upper="0.6" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_gripper_fingertip_right">
|
|
<inertial>
|
|
<origin
|
|
xyz="0 0 0.008126"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.003822" />
|
|
<inertia
|
|
ixx="0"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="0"
|
|
iyz="0"
|
|
izz="1E-06" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_fingertip_right.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.250980392156863 0.250980392156863 0.250980392156863 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_gripper_fingertip_right.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_gripper_fingertip_right"
|
|
type="fixed">
|
|
<origin
|
|
xyz="${scale_finger_length * -0.19011} -0.014912 0"
|
|
rpy="-1.5708 -2.0539E-15 0.58705" />
|
|
<parent
|
|
link="link_gripper_finger_right" />
|
|
<child
|
|
link="link_gripper_fingertip_right" />
|
|
<axis
|
|
xyz="0 0 0" />
|
|
</joint>
|
|
|
|
|
|
<link
|
|
name="link_grasp_center">
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_grasp_center"
|
|
type="fixed">
|
|
<origin
|
|
xyz="-0.205478 0 -0.138154"
|
|
rpy="0 0 3.141579" />
|
|
<parent
|
|
link="link_gripper" />
|
|
<child
|
|
link="link_grasp_center" />
|
|
</joint>
|
|
|
|
</robot>
|