Newer
Older
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">
<include filename="$(find ur_description)/urdf/ur10.transmission.xacro" />
<include filename="$(find ur_description)/urdf/ur10.gazebo.xacro" />
<include filename="$(find ur_description)/urdf/materials.urdf.xacro" />
a = [0.00000, -0.42500, -0.39225, 0.00000, 0.00000, 0.0000]
d = [0.089159, 0.00000, 0.00000, 0.10915, 0.09465, 0.0823]
alpha = [ 1.570796327, 0, 0, 1.570796327, -1.570796327, 0 ]
q_home_offset = [0, -1.570796327, 0, -1.570796327, 0, 0]
joint_direction = [-1, -1, 1, 1, 1, 1]
mass = [3.7000, 8.3930, 2.2750, 1.2190, 1.2190, 0.1879]
center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, 0.0265], [0, -0.0018, 0.01634], [0, 0.0018,0.01634], [0, 0, -0.001159] ]
-->
<property name="pi" value="3.14159265" />
<property name="base_mass" value="4.0" /> <!-- Invented number, only matters for simulator -->
<property name="shoulder_mass" value="3.7000" />
<property name="upper_arm_mass" value="8.3930" />
<property name="forearm_mass" value="2.2750" />
<property name="wrist_1_mass" value="1.2190" />
<property name="wrist_2_mass" value="1.2190" />
<property name="wrist_3_mass" value="0.1879" />
<property name="shoulder_cog" value="0.0 0.00193 -0.02561" />
<property name="upper_arm_cog" value="0.0 -0.024201 0.2125" /> <!-- 0.11336 - 0.089159 = -->
<property name="forearm_cog" value="0.0 0.0265 0.11993" /> <!-- 0.119 is not half of 0.39225, is this really correct? -->
<property name="wrist_1_cog" value="0.0 0.110949 0.01634" /> <!-- 0.0018 + 0.10915 = 0.110949 -->
<property name="wrist_2_cog" value="0.0 0.0018 0.11099" /> <!-- 0.01634 + 0.09465 = 0.11099-->
<property name="wrist_3_cog" value="0.0 0.001159 0.0" />
<property name="shoulder_height" value="0.128" />
<property name="shoulder_offset" value="0.1704" /> <!-- shoulder_offset - elbow_offset + wrist_1_length = 0.10915 -->
<property name="upper_arm_length" value="0.60186" />
<property name="elbow_offset" value="0.12817" /> <!-- CAD measured -->
<property name="forearm_length" value="0.56415" />
<property name="wrist_1_length" value="0.11279" /> <!-- CAD measured -->
<property name="wrist_2_length" value="0.11279" /> <!-- In CAD this distance is 0.930, but in the spec it is 0.09465 -->
<property name="wrist_3_length" value="0.0857" />
<property name="shoulder_radius" value="0.060" /> <!-- manually measured -->
Wim Meeussen
committed
<property name="upper_arm_radius" value="0.054" /> <!-- manually measured -->
<property name="elbow_radius" value="0.060" /> <!-- manually measured -->
<property name="forearm_radius" value="0.040" /> <!-- manually measured -->
<property name="wrist_radius" value="0.045" /> <!-- manually measured -->
Wim Meeussen
committed
<!-- Collision model -->
<property name="base_collision_length" value="0.160" /> <!-- manually measured -->
Wim Meeussen
committed
<property name="shoulder_collision_length" value="0.200" /> <!-- manually measured -->
<property name="shoulder_collision_offset" value="0.035" /> <!-- manually measured -->
<property name="elbow_collision_length" value="0.200" /> <!-- manually measured -->
<property name="elbow_collision_offset" value="0.035" /> <!-- manually measured -->
Wim Meeussen
committed
<xacro:macro name="ur10_robot" params="parent name *origin">
<!-- joint between base_link and ur_base_link -->
<joint name="${name}_base_joint" type="fixed" >
<insert_block name="origin" />
<parent link="${parent}" />
<child link="${name}_base_link" />
</joint>
<mesh filename="package://ur_description/meshes/ur10/Base.stl" />
</geometry>
<origin xyz="0.0 0.0 0.003" rpy="0.0 0.0 ${3.0 * pi / 4.0}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="${name}_shoulder_pan_joint" type="revolute">
<parent link="${name}_base_link" />
<child link = "${name}_shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<mesh filename="package://ur_description/meshes/ur10/Shoulder.stl" />
<cylinder length="${base_collision_length}" radius="${shoulder_radius}"/>
<origin xyz="0.0 0.0 ${-shoulder_height + (base_collision_length/2.0)}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
<origin xyz="${shoulder_cog}" rpy="0.0 0.0 0.0" />
<joint name="${name}_shoulder_lift_joint" type="revolute">
<parent link="${name}_shoulder_link" />
<child link = "${name}_upper_arm_link" />
<origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<mesh filename="package://ur_description/meshes/ur10/UpperArm.stl" />
Wim Meeussen
committed
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<collision>
<geometry>
<cylinder length="${upper_arm_length}" radius="${upper_arm_radius}"/>
</geometry>
<origin xyz="0.0 0.0 ${upper_arm_length/2.0}" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
<origin xyz="${upper_arm_cog}" rpy="0.0 0.0 0.0" />
<joint name="${name}_elbow_joint" type="revolute">
<parent link="${name}_upper_arm_link" />
<child link = "${name}_forearm_link" />
Wim Meeussen
committed
<origin xyz="0.0 ${-elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<mesh filename="package://ur_description/meshes/ur10/Forearm_new.stl" />
<collision>
<geometry>
<cylinder length="${forearm_length}" radius="${forearm_radius}"/>
</geometry>
<origin xyz="0.0 0.0 ${forearm_length/2.0}" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<mass value="${forearm_mass}" />
<origin xyz="${forearm_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
<joint name="${name}_wrist_1_joint" type="revolute">
<parent link="${name}_forearm_link" />
<child link = "${name}_wrist_1_link" />
<origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<mesh filename="package://ur_description/meshes/ur10/Wrist1_new.stl" />
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0 0.0" />
<cylinder length="${1.6*wrist_1_length}" radius="${wrist_radius}"/>
<origin xyz="0.0 ${0.25*wrist_1_length} 0.0" rpy="${-pi/2.0} 0.0 0.0" />
<mass value="${wrist_1_mass}" />
<origin xyz="${wrist_1_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
<joint name="${name}_wrist_2_joint" type="revolute">
<parent link="${name}_wrist_1_link" />
<child link = "${name}_wrist_2_link" />
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<mesh filename="package://ur_description/meshes/ur10/Wrist2_new.stl" />
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
<cylinder length="${1.6*wrist_2_length}" radius="${wrist_radius}"/>
<origin xyz="0.0 0.0 ${0.25*wrist_2_length}" rpy="0.0 0.0 0.0" />
<mass value="${wrist_2_mass}" />
<origin xyz="${wrist_2_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
<joint name="${name}_wrist_3_joint" type="revolute">
<parent link="${name}_wrist_2_link" />
<child link = "${name}_wrist_3_link" />
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<mesh filename="package://ur_description/meshes/ur10/Wrist3_new.stl" />
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 0" />
<cylinder length="${1.65*wrist_3_length}" radius="${wrist_radius}"/>
<origin xyz="0.0 ${0.15 * wrist_3_length} 0.0" rpy="${-pi/2.0} 0.0 0.0" />
<mass value="${wrist_3_mass}" />
<origin xyz="${wrist_3_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
<joint name="${name}_ee_fixed_joint" type="fixed">
<parent link="${name}_wrist_3_link" />
<child link = "${name}_ee_link" />
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
</joint>
Wim Meeussen
committed
<!-- Somehow don't work with gazebo TODO: fix this
<joint name="${name}_shoulder_collision_joint" type="fixed">
<parent link="${name}_upper_arm_link" />
<child link = "${name}_shoulder_collision_link" />
Wim Meeussen
committed
</joint>
Wim Meeussen
committed
<collision>
<geometry>
<cylinder length="${shoulder_collision_length}" radius="${shoulder_radius}"/>
</geometry>
<origin xyz="0.0 ${-shoulder_collision_offset} 0.0" rpy="${-pi / 2.0} 0.0 0.0" />
</collision>
</link>
<joint name="${name}_elbow_collision_joint" type="fixed">
<parent link="${name}_upper_arm_link" />
<child link = "${name}_elbow_collision_link" />
Wim Meeussen
committed
</joint>
Wim Meeussen
committed
<collision>
<geometry>
<cylinder length="${elbow_collision_length}" radius="${elbow_radius}"/>
</geometry>
<origin xyz="0.0 ${-elbow_collision_offset} ${upper_arm_length}" rpy="${pi / 2.0} 0.0 0.0" />
</collision>
</link>
<xacro:ur10_arm_transmission name="${name}" />
<xacro:ur10_arm_gazebo name="${name}" />
Wim Meeussen
committed