diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml
index c3472cccfd83d9600602c1f26de1f818b32f58b3..d531621597828461f32cea726ab7f211f266c430 100644
--- a/config/joint_limits.yaml
+++ b/config/joint_limits.yaml
@@ -7,49 +7,56 @@ default_acceleration_scaling_factor: 0.1
 
 # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
 # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
+
+# As MoveIt! does not support jerk limits, the acceleration limits provided here are the highest values that guarantee
+# that no jerk limits will be violated. More precisely, applying Euler differentiation in the worst case (from min accel
+# to max accel in 1 ms) the acceleration limits are the ones that satisfy
+# max_jerk = (max_acceleration - min_acceleration) / 0.001
+
 joint_limits:
   panda_finger_joint1:
     has_velocity_limits: true
-    max_velocity: 0.2
+    max_velocity: 0.1
     has_acceleration_limits: false
     max_acceleration: 0
   panda_finger_joint2:
     has_velocity_limits: true
-    max_velocity: 0.2
+    max_velocity: 0.1
     has_acceleration_limits: false
     max_acceleration: 0
   panda_joint1:
     has_velocity_limits: true
-    max_velocity: 2.175
-    has_acceleration_limits: false
-    max_acceleration: 0
+    max_velocity: 2.1750
+    has_acceleration_limits: true
+    max_acceleration: 3.75
   panda_joint2:
     has_velocity_limits: true
-    max_velocity: 2.175
-    has_acceleration_limits: false
-    max_acceleration: 0
+    max_velocity: 2.1750
+    has_acceleration_limits: true
+    max_acceleration: 1.875
   panda_joint3:
     has_velocity_limits: true
-    max_velocity: 2.175
-    has_acceleration_limits: false
-    max_acceleration: 0
+    max_velocity: 2.1750
+    has_acceleration_limits: true
+    max_acceleration: 2.5
   panda_joint4:
     has_velocity_limits: true
-    max_velocity: 2.175
-    has_acceleration_limits: false
-    max_acceleration: 0
+    max_velocity: 2.1750
+    has_acceleration_limits: true
+    max_acceleration: 3.125
   panda_joint5:
     has_velocity_limits: true
-    max_velocity: 2.61
-    has_acceleration_limits: false
-    max_acceleration: 0
+    max_velocity: 2.6100
+    has_acceleration_limits: true
+    max_acceleration: 3.75
   panda_joint6:
     has_velocity_limits: true
-    max_velocity: 2.61
-    has_acceleration_limits: false
-    max_acceleration: 0
+    max_velocity: 2.6100
+    has_acceleration_limits: true
+    max_acceleration: 5
   panda_joint7:
     has_velocity_limits: true
-    max_velocity: 2.61
-    has_acceleration_limits: false
-    max_acceleration: 0
\ No newline at end of file
+    max_velocity: 2.6100
+    has_acceleration_limits: true
+    max_acceleration: 5
+