From d01b955eb564a9a8348667bcd3fb09dd11d0e8bb Mon Sep 17 00:00:00 2001
From: Simon Gabl <simon.gabl@franka.de>
Date: Fri, 22 Jun 2018 16:31:22 +0200
Subject: [PATCH] Update soft limits of joint 4 in the URDF.

---
 franka_description/robots/panda_arm.xacro | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/franka_description/robots/panda_arm.xacro b/franka_description/robots/panda_arm.xacro
index cdc0844..faba3d0 100644
--- a/franka_description/robots/panda_arm.xacro
+++ b/franka_description/robots/panda_arm.xacro
@@ -93,7 +93,7 @@
       </collision>
     </link>
     <joint name="${arm_id}_joint4" type="revolute">
-      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="0.0175"/>
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/>
       <origin rpy="${pi/2} 0 0" xyz="0.0825 0 0"/>
       <parent link="${arm_id}_link3"/>
       <child link="${arm_id}_link4"/>
-- 
GitLab