diff --git a/robots/panda_arm.xacro b/robots/panda_arm.xacro
index b44b230a6f194588e914f541fe2f311e7cbbd1d3..7ad94ecf176fba762602486981d5a6ac33eef789 100644
--- a/robots/panda_arm.xacro
+++ b/robots/panda_arm.xacro
@@ -66,7 +66,7 @@
       <parent link="${arm_id}_link0"/>
       <child link="${arm_id}_link1"/>
       <axis xyz="0 0 1"/>
-      <limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/>
+      <limit effort="87" lower="-2.7973" upper="2.7973" velocity="2.1750"/>
     </joint>
     <link name="${arm_id}_link2">
       <visual>
@@ -99,7 +99,7 @@
       <parent link="${arm_id}_link1"/>
       <child link="${arm_id}_link2"/>
       <axis xyz="0 0 1"/>
-      <limit effort="87" lower="-1.7628" upper="1.7628" velocity="2.1750"/>
+      <limit effort="87" lower="-1.6628" upper="1.6628" velocity="2.1750"/>
     </joint>
     <link name="${arm_id}_link3">
       <visual>
@@ -132,7 +132,7 @@
       <parent link="${arm_id}_link2"/>
       <child link="${arm_id}_link3"/>
       <axis xyz="0 0 1"/>
-      <limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/>
+      <limit effort="87" lower="-2.6973" upper="2.6973" velocity="2.1750"/>
     </joint>
     <link name="${arm_id}_link4">
       <visual>
@@ -165,7 +165,7 @@
       <parent link="${arm_id}_link3"/>
       <child link="${arm_id}_link4"/>
       <axis xyz="0 0 1"/>
-      <limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750"/>
+      <limit effort="87" lower="-2.9718" upper="0.0000" velocity="2.1750"/>
     </joint>
     <link name="${arm_id}_link5">
       <visual>
@@ -217,7 +217,7 @@
       <parent link="${arm_id}_link4"/>
       <child link="${arm_id}_link5"/>
       <axis xyz="0 0 1"/>
-      <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/>
+      <limit effort="12" lower="-2.7973" upper="2.7973" velocity="2.6100"/>
     </joint>
     <link name="${arm_id}_link6">
       <visual>
@@ -250,7 +250,7 @@
       <parent link="${arm_id}_link5"/>
       <child link="${arm_id}_link6"/>
       <axis xyz="0 0 1"/>
-      <limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.6100"/>
+      <limit effort="12" lower="0.0000" upper="3.6525" velocity="2.6100"/>
     </joint>
     <link name="${arm_id}_link7">
       <visual>
@@ -283,7 +283,7 @@
       <parent link="${arm_id}_link6"/>
       <child link="${arm_id}_link7"/>
       <axis xyz="0 0 1"/>
-      <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/>
+      <limit effort="12" lower="-2.7973" upper="2.7973" velocity="2.6100"/>
     </joint>
     <link name="${arm_id}_link8">
       <collision>