You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 

451 lines
11 KiB

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_dex_wrist">
<xacro:property name="scale_finger_length" value="0.9" />
<link
name="link_wrist_yaw_bottom">
<inertial>
<origin
xyz="-0.012462 -0.032314 -0.021973"
rpy="0 0 0" />
<mass
value="0.24284" />
<inertia
ixx="0.000194"
ixy="3.4E-05"
ixz="7E-06"
iyy="0.000107"
iyz="2E-05"
izz="0.000229" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_wrist_yaw_bottom.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_wrist_yaw_bottom.STL" />
</geometry>
</collision>
</link>
<joint
name="joint_wrist_yaw_bottom"
type="fixed">
<origin
xyz="0 0 0"
rpy="-3.14159265358979 1.13367999021379E-14 1.57079632679489" />
<parent
link="link_wrist_yaw" />
<child
link="link_wrist_yaw_bottom" />
<axis
xyz="0 0 0" />
</joint>
<link
name="link_wrist_pitch">
<inertial>
<origin
xyz="-0.006752 -0.01567 0.021672"
rpy="0 0 0" />
<mass
value="0.208129" />
<inertia
ixx="8.5E-05"
ixy="1.6E-05"
ixz="5E-06"
iyy="8.4E-05"
iyz="4E-06"
izz="0.000105" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_wrist_pitch.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_wrist_pitch.STL" />
</geometry>
</collision>
</link>
<joint
name="joint_wrist_pitch"
type="revolute">
<origin
xyz="0 -0.0195500000000002 -0.0247499999999984"
rpy="1.5707963267949 -8.12895570882604E-15 -3.14159265358979" />
<parent
link="link_wrist_yaw_bottom" />
<child
link="link_wrist_pitch" />
<axis
xyz="0 0 -1" />
<limit effort="100" lower="-1.57" upper="0.56" velocity="1.0"/>
</joint>
<link
name="link_wrist_roll">
<inertial>
<origin
xyz="6E-05 -3.1E-05 0.006242"
rpy="0 0 0" />
<mass
value="0.01528" />
<inertia
ixx="1E-06"
ixy="0"
ixz="0"
iyy="9.5E-07"
iyz="0"
izz="1.39E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_wrist_roll.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_wrist_roll.STL" />
</geometry>
</collision>
</link>
<joint
name="joint_wrist_roll"
type="revolute">
<origin
xyz="-0.0188587444076125 -0.0239999999998942 0.01955"
rpy="3.14159265358979 1.5707963267949 0" />
<parent
link="link_wrist_pitch" />
<child
link="link_wrist_roll" />
<axis
xyz="0 0 1" />
<limit effort="100" lower="-3.14" upper="3.14" velocity="1.0"/>
</joint>
<link
name="link_straight_gripper">
<inertial>
<origin
xyz="0.002409 -0.011138 0.028861"
rpy="0 0 0" />
<mass
value="0.147853" />
<inertia
ixx="9.5E-07"
ixy="-4E-06"
ixz="-1E-06"
iyy="0.000119"
iyz="6E-06"
izz="5.9E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_straight_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_straight_gripper.STL" />
</geometry>
</collision>
</link>
<joint
name="joint_straight_gripper"
type="fixed">
<origin
xyz="0 0 0.0155"
rpy="3.54987407349455E-30 3.24021254484265E-20 -3.14159265358979" />
<parent
link="link_wrist_roll" />
<child
link="link_straight_gripper" />
<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" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 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" />
</geometry>
</collision>
</link>
<joint
name="joint_gripper_finger_right"
type="revolute">
<origin
xyz="-0.018599 0.003 0.033689"
rpy="1.5708 1.5708 0" />
<parent
link="link_straight_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="-0.190596948563868 -0.015 0"
rpy="-1.57079632679483 -3.43320051448326E-14 0.540456056432235" />
<parent
link="link_gripper_finger_right" />
<child
link="link_gripper_fingertip_right" />
<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="3.141592653589793 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_gripper_finger_left.STL" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="1.5707963267948966 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_gripper_finger_left.STL" />
</geometry>
</collision>
</link>
<joint
name="joint_gripper_finger_left"
type="revolute">
<origin
xyz="0.018599 0.003 0.033689"
rpy="1.5708 -1.5708 0" />
<parent
link="link_straight_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="0.190596948563868 -0.015 0"
rpy="1.57079632679496 4.51275387511463E-14 2.60113659715756" />
<parent
link="link_gripper_finger_left" />
<child
link="link_gripper_fingertip_left" />
<axis
xyz="0 0 0" />
</joint>
<link
name="link_grasp_center">
</link>
<joint
name="joint_grasp_center"
type="fixed">
<origin
xyz="0 0 0.23"
rpy="-1.5707963267949 -1.5707963267949 0" />
<parent
link="link_straight_gripper" />
<child
link="link_grasp_center" />
</joint>
</robot>