From 09ef4ead2acaceae9b3b2bfc583346b9238ee537 Mon Sep 17 00:00:00 2001 From: kphawkins Date: Tue, 17 Dec 2013 18:47:35 -0500 Subject: [PATCH] Update ur5.urdf.xacro Corrected effort thresholds and friction values for UR5 urdf. --- ur_description/urdf/ur5.urdf.xacro | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/ur_description/urdf/ur5.urdf.xacro b/ur_description/urdf/ur5.urdf.xacro index 9cd7f9749..d6a88d926 100644 --- a/ur_description/urdf/ur5.urdf.xacro +++ b/ur_description/urdf/ur5.urdf.xacro @@ -79,8 +79,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, - - + + @@ -107,8 +107,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, - - + + @@ -136,8 +136,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, - - + + @@ -164,8 +164,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, - - + + @@ -193,8 +193,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, - - + + @@ -222,8 +222,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, - - + +