diff --git a/ur_description/meshes/ur10/collision/base.stl b/ur_description/meshes/ur10/collision/base.stl
new file mode 100644
index 0000000000000000000000000000000000000000..16575ddf171310cb14bb9f5156572cbf45d2f4ca
Binary files /dev/null and b/ur_description/meshes/ur10/collision/base.stl differ
diff --git a/ur_description/meshes/ur10/collision/forearm.stl b/ur_description/meshes/ur10/collision/forearm.stl
new file mode 100644
index 0000000000000000000000000000000000000000..d9ca04182997fe98d44ef328aec7442c79173adf
Binary files /dev/null and b/ur_description/meshes/ur10/collision/forearm.stl differ
diff --git a/ur_description/meshes/ur10/collision/shoulder.stl b/ur_description/meshes/ur10/collision/shoulder.stl
new file mode 100644
index 0000000000000000000000000000000000000000..7881e85c6e5b808e580fd53fa214d3a03f7e30ae
Binary files /dev/null and b/ur_description/meshes/ur10/collision/shoulder.stl differ
diff --git a/ur_description/meshes/ur10/collision/upper_arm.stl b/ur_description/meshes/ur10/collision/upper_arm.stl
new file mode 100644
index 0000000000000000000000000000000000000000..15af610fee9bd63c078b8e1ace9c0924d3e7457d
Binary files /dev/null and b/ur_description/meshes/ur10/collision/upper_arm.stl differ
diff --git a/ur_description/meshes/ur10/collision/wrist_1.stl b/ur_description/meshes/ur10/collision/wrist_1.stl
new file mode 100644
index 0000000000000000000000000000000000000000..c9fa25520817f5a5066d6da8d158626b38033e9d
Binary files /dev/null and b/ur_description/meshes/ur10/collision/wrist_1.stl differ
diff --git a/ur_description/meshes/ur10/collision/wrist_2.stl b/ur_description/meshes/ur10/collision/wrist_2.stl
new file mode 100644
index 0000000000000000000000000000000000000000..d3828547dee073927ca689de604a190f806b217a
Binary files /dev/null and b/ur_description/meshes/ur10/collision/wrist_2.stl differ
diff --git a/ur_description/meshes/ur10/collision/wrist_3.stl b/ur_description/meshes/ur10/collision/wrist_3.stl
new file mode 100644
index 0000000000000000000000000000000000000000..597433627d5463c546b3f1d3f23c15f62da6ecb5
Binary files /dev/null and b/ur_description/meshes/ur10/collision/wrist_3.stl differ
diff --git a/ur_description/urdf/ur10.urdf.xacro b/ur_description/urdf/ur10.urdf.xacro
index 2ffeb2d96f761fa97944ecabde1339f39c1011cc..f9261281c2e461594365d161da123380d2767ed3 100644
--- a/ur_description/urdf/ur10.urdf.xacro
+++ b/ur_description/urdf/ur10.urdf.xacro
@@ -73,7 +73,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>
       <xacro:cylinder_inertial radius="0.075" length="0.038" mass="${base_mass}">
@@ -103,7 +103,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>
       <xacro:cylinder_inertial radius="0.075" length="0.178" mass="${shoulder_mass}">
@@ -133,7 +133,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>
       <xacro:cylinder_inertial radius="0.075" length="${-ur10_a2}" mass="${upper_arm_mass}">
@@ -163,7 +163,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>
       <xacro:cylinder_inertial radius="0.075" length="${-ur10_a3}" mass="${forearm_mass}">
@@ -193,7 +193,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>
       <xacro:cylinder_inertial radius="0.075" length="0.12" mass="${wrist_1_mass}">
@@ -223,7 +223,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>
       <xacro:cylinder_inertial radius="0.075" length="0.12" mass="${wrist_2_mass}">
@@ -253,7 +253,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>
       <xacro:cylinder_inertial radius="0.075" length="0.12" mass="${wrist_3_mass}">
@@ -267,7 +267,14 @@
       <origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
     </joint>
 
-    <link name="${prefix}ee_link" />
+    <link name="${prefix}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>
 
     <xacro:ur10_arm_transmission prefix="${prefix}" />
     <xacro:ur10_arm_gazebo prefix="${prefix}" />