From d6458d4926ac6d04bc01130818e3cc4c4c8c7ec8 Mon Sep 17 00:00:00 2001
From: ipa-fxm <felix.messmer@ipa.fhg.de>
Date: Tue, 21 Oct 2014 12:19:17 +0000
Subject: [PATCH] re-generate urdf-files from latest xacro-files

---
 .../urdf/ur10_joint_limited_robot.urdf        | 23 ++++++++++++-------
 ur_description/urdf/ur10_robot.urdf           | 23 ++++++++++++-------
 .../urdf/ur5_joint_limited_robot.urdf         | 23 ++++++++++++-------
 ur_description/urdf/ur5_robot.urdf            | 23 ++++++++++++-------
 4 files changed, 60 insertions(+), 32 deletions(-)

diff --git a/ur_description/urdf/ur10_joint_limited_robot.urdf b/ur_description/urdf/ur10_joint_limited_robot.urdf
index 7ccfc3c..b2c3bba 100644
--- a/ur_description/urdf/ur10_joint_limited_robot.urdf
+++ b/ur_description/urdf/ur10_joint_limited_robot.urdf
@@ -35,7 +35,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Base.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/base.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -60,7 +60,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/shoulder.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -85,7 +85,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/upper_arm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -110,7 +110,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Forearm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -135,7 +135,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_1.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -160,7 +160,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_2.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -185,7 +185,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_3.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -199,7 +199,14 @@
     <child link="ee_link"/>
     <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0922 0.0"/>
   </joint>
-  <link name="ee_link"/>
+  <link name="ee_link">
+    <collision>
+      <geometry>
+        <box size="0.01 0.01 0.01"/>
+      </geometry>
+      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
+    </collision>
+  </link>
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
     <joint name="shoulder_pan_joint"/>
diff --git a/ur_description/urdf/ur10_robot.urdf b/ur_description/urdf/ur10_robot.urdf
index 810b5d8..7287ffb 100644
--- a/ur_description/urdf/ur10_robot.urdf
+++ b/ur_description/urdf/ur10_robot.urdf
@@ -35,7 +35,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Base.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/base.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -60,7 +60,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/shoulder.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -85,7 +85,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/upper_arm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -110,7 +110,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Forearm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -135,7 +135,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_1.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -160,7 +160,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_2.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -185,7 +185,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.dae"/>
+        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_3.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -199,7 +199,14 @@
     <child link="ee_link"/>
     <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0922 0.0"/>
   </joint>
-  <link name="ee_link"/>
+  <link name="ee_link">
+    <collision>
+      <geometry>
+        <box size="0.01 0.01 0.01"/>
+      </geometry>
+      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
+    </collision>
+  </link>
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
     <joint name="shoulder_pan_joint"/>
diff --git a/ur_description/urdf/ur5_joint_limited_robot.urdf b/ur_description/urdf/ur5_joint_limited_robot.urdf
index b0c992b..671e2f8 100644
--- a/ur_description/urdf/ur5_joint_limited_robot.urdf
+++ b/ur_description/urdf/ur5_joint_limited_robot.urdf
@@ -35,7 +35,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Base.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/base.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -60,7 +60,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Shoulder.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -85,7 +85,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/UpperArm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/upper_arm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -110,7 +110,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Forearm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -135,7 +135,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Wrist1.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/wrist_1.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -160,7 +160,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Wrist2.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/wrist_2.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -185,7 +185,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Wrist3.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/wrist_3.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -199,7 +199,14 @@
     <child link="ee_link"/>
     <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0823 0.0"/>
   </joint>
-  <link name="ee_link"/>
+  <link name="ee_link">
+    <collision>
+      <geometry>
+        <box size="0.01 0.01 0.01"/>
+      </geometry>
+      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
+    </collision>
+  </link>
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
     <joint name="shoulder_pan_joint"/>
diff --git a/ur_description/urdf/ur5_robot.urdf b/ur_description/urdf/ur5_robot.urdf
index 74103fa..d516f3d 100644
--- a/ur_description/urdf/ur5_robot.urdf
+++ b/ur_description/urdf/ur5_robot.urdf
@@ -35,7 +35,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Base.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/base.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -60,7 +60,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Shoulder.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -85,7 +85,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/UpperArm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/upper_arm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -110,7 +110,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Forearm.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -135,7 +135,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Wrist1.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/wrist_1.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -160,7 +160,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Wrist2.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/wrist_2.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -185,7 +185,7 @@
     </visual>
     <collision>
       <geometry>
-        <mesh filename="package://ur_description/meshes/ur5/collision/Wrist3.dae"/>
+        <mesh filename="package://ur_description/meshes/ur5/collision/wrist_3.stl"/>
       </geometry>
     </collision>
     <inertial>
@@ -199,7 +199,14 @@
     <child link="ee_link"/>
     <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0823 0.0"/>
   </joint>
-  <link name="ee_link"/>
+  <link name="ee_link">
+    <collision>
+      <geometry>
+        <box size="0.01 0.01 0.01"/>
+      </geometry>
+      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
+    </collision>
+  </link>
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
     <joint name="shoulder_pan_joint"/>
-- 
GitLab