Skip to content

Commit

Permalink
Merge pull request ros-industrial#1 from ros-industrial/master
Browse files Browse the repository at this point in the history
updating master branch on this fork
  • Loading branch information
jrgnicho committed Jan 10, 2014
2 parents b67f01a + 2f41f90 commit 83e972a
Show file tree
Hide file tree
Showing 3 changed files with 71 additions and 144 deletions.
100 changes: 33 additions & 67 deletions training/ref/demo_manipulation/robot_config/urdf/ur5_model.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,9 @@
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">

<include filename="$(find ur5_description)/urdf/arm.transmission.xacro" />

<include filename="$(find ur_description)/urdf/ur5.transmission.xacro" />
<include filename="$(find ur_description)/urdf/ur5.gazebo.xacro" />
<include filename="$(find ur_description)/urdf/materials.urdf.xacro" />
<!--
DH for UR5:
a = [0.00000, -0.42500, -0.39225, 0.00000, 0.00000, 0.0000]
Expand Down Expand Up @@ -52,24 +53,21 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<property name="forearm_radius" value="0.040" /> <!-- manually measured -->
<property name="wrist_radius" value="0.045" /> <!-- manually measured -->

<!-- Collision model -->
<property name="base_collision_length" value="0.160" /> <!-- manually measured -->
<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 -->



<xacro:macro name="ur5_robot" params="prefix">

<link name="${prefix}base_link" >
<visual>
<geometry>
<mesh filename="package://ur5_description/meshes/Base.dae" />
<mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" />
</geometry>
<origin xyz="0.0 0.0 0.003" rpy="0.0 0.0 ${3.0 * pi / 4.0}" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/collision/Base.dae" />
</geometry>
<!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.009159"/> -->
</collision>
<inertial>
<mass value="${base_mass}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
Expand All @@ -80,22 +78,22 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<parent link="${prefix}base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" />
<axis xyz="0 0 1" />
<limit lower="${-0.75 * pi}" upper="${0.75 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
</joint>

<link name="${prefix}shoulder_link">
<visual>
<geometry>
<mesh filename="package://ur5_description/meshes/Shoulder.dae" />
<mesh filename="package://ur_description/meshes/ur5/visual/Shoulder.dae" />
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="${base_collision_length}" radius="${shoulder_radius}"/>
<mesh filename="package://ur_description/meshes/ur5/collision/Shoulder.dae" />
</geometry>
<origin xyz="0.0 0.0 ${-shoulder_height + (base_collision_length/2.0)}" rpy="0.0 0.0 0.0" />
<!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.009159"/> -->
</collision>
<inertial>
<mass value="${shoulder_mass}" />
Expand All @@ -108,23 +106,23 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<parent link="${prefix}shoulder_link" />
<child link = "${prefix}upper_arm_link" />
<origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0.0 1.0 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-1.0 * pi}" upper="${1.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
</joint>

<link name="${prefix}upper_arm_link">
<visual>
<geometry>
<mesh filename="package://ur5_description/meshes/UpperArm.dae" />
<mesh filename="package://ur_description/meshes/ur5/visual/UpperArm.dae" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</visual>
<collision>
<geometry>
<cylinder length="${upper_arm_length}" radius="${upper_arm_radius}"/>
<mesh filename="package://ur_description/meshes/ur5/collision/UpperArm.dae" />
</geometry>
<origin xyz="0.0 0.0 ${upper_arm_length/2.0}" rpy="0.0 0.0 0.0" />
<!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.2125"/> -->
</collision>
<inertial>
<mass value="${upper_arm_mass}" />
Expand All @@ -137,22 +135,22 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<parent link="${prefix}upper_arm_link" />
<child link = "${prefix}forearm_link" />
<origin xyz="0.0 ${-elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-0.2 * pi}" upper="${0.9 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
</joint>

<link name="${prefix}forearm_link">
<visual>
<geometry>
<mesh filename="package://ur5_description/meshes/Forearm.dae" />
<mesh filename="package://ur_description/meshes/ur5/visual/Forearm.dae" />
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="${forearm_length}" radius="${forearm_radius}"/>
<mesh filename="package://ur_description/meshes/ur5/collision/Forearm.dae" />
</geometry>
<origin xyz="0.0 0.0 ${forearm_length/2.0}" rpy="0.0 0.0 0.0" />
<!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.196125"/> -->
</collision>
<inertial>
<mass value="${forearm_mass}" />
Expand All @@ -165,23 +163,23 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<parent link="${prefix}forearm_link" />
<child link = "${prefix}wrist_1_link" />
<origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0.0 1.0 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-1.0 * pi}" upper="${0.01 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
</joint>

<link name="${prefix}wrist_1_link">
<visual>
<geometry>
<mesh filename="package://ur5_description/meshes/Wrist1.dae" />
<mesh filename="package://ur_description/meshes/ur5/visual/Wrist1.dae" />
</geometry>
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
</visual>
<collision>
<geometry>
<cylinder length="${1.6*wrist_1_length}" radius="${wrist_radius}"/>
<mesh filename="package://ur_description/meshes/ur5/collision/Wrist1.dae" />
</geometry>
<origin xyz="0.0 ${0.25*wrist_1_length} 0.0" rpy="${-pi/2.0} 0.0 0.0" />
<origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.093 0.0"/>
</collision>
<inertial>
<mass value="${wrist_1_mass}" />
Expand All @@ -194,23 +192,23 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<parent link="${prefix}wrist_1_link" />
<child link = "${prefix}wrist_2_link" />
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" />
<axis xyz="0 0 1" />
<limit lower="${-1.0 * pi}" upper="${1.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
</joint>

<link name="${prefix}wrist_2_link">
<visual>
<geometry>
<mesh filename="package://ur5_description/meshes/Wrist2.dae" />
<mesh filename="package://ur_description/meshes/ur5/visual/Wrist2.dae" />
</geometry>
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
</visual>
<collision>
<geometry>
<cylinder length="${1.6*wrist_2_length}" radius="${wrist_radius}"/>
<mesh filename="package://ur_description/meshes/ur5/collision/Wrist2.dae" />
</geometry>
<origin xyz="0.0 0.0 ${0.25*wrist_2_length}" rpy="0.0 0.0 0.0" />
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.09465"/>
</collision>
<inertial>
<mass value="${wrist_2_mass}" />
Expand All @@ -223,22 +221,21 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<parent link="${prefix}wrist_2_link" />
<child link = "${prefix}wrist_3_link" />
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-1.5 * pi}" upper="${1.5 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
</joint>

<link name="${prefix}wrist_3_link">
<visual>
<geometry>
<mesh filename="package://ur5_description/meshes/Wrist3.dae" />
<mesh filename="package://ur_description/meshes/ur5/visual/Wrist3.dae" />
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="${1.65*wrist_3_length}" radius="${wrist_radius}"/>
<mesh filename="package://ur_description/meshes/ur5/collision/Wrist3.dae" />
</geometry>
<origin xyz="0.0 ${0.15 * wrist_3_length} 0.0" rpy="${-pi/2.0} 0.0 0.0" />
</collision>
<inertial>
<mass value="${wrist_3_mass}" />
Expand All @@ -254,37 +251,6 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
</joint>

<link name="${prefix}ee_link" />



<!-- Extra links for collision model -->
<!-- Somehow don't work with gazebo TODO: fix this
<joint name="${prefix}shoulder_collision_joint" type="fixed">
<parent link="${prefix}upper_arm_link" />
<child link = "${prefix}shoulder_collision_link" />
</joint>
<link name="${prefix}shoulder_collision_link">
<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="${prefix}elbow_collision_joint" type="fixed">
<parent link="${prefix}upper_arm_link" />
<child link = "${prefix}elbow_collision_link" />
</joint>
<link name="${prefix}elbow_collision_link">
<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:ur_arm_transmission name="${prefix}" />

Expand Down
Loading

0 comments on commit 83e972a

Please sign in to comment.