diff --git a/CHANGELOG.md b/CHANGELOG.md
index a576401fdf7933f5ad0e2576605ba6ef93827d6b..0dcc9fc9b15237e32140f946f50976c49d5e267a 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -12,7 +12,7 @@
     * Add `load_gripper` argument (default: `true`) to `panda_moveit.launch`
     * Conditionally load controllers/SRDFs based on `load_gripper`
     * Add gripper controller configuration (requires running `franka_gripper_node`)
-  * Added `mimic` tag for gripper fingers to URDF
+  * Added `mimic` tag for gripper fingers to URDF and fixed velocity limits
 
 ## 0.3.0 - 2018-02-22
 
diff --git a/franka_description/robots/hand.xacro b/franka_description/robots/hand.xacro
index c00ef1afacaf8e47ce30a844edefdf6c1f91a71a..1cd3777e10cb268a4a9d0c6998b9cefccabb30b8 100644
--- a/franka_description/robots/hand.xacro
+++ b/franka_description/robots/hand.xacro
@@ -51,14 +51,14 @@
       <child link="${ns}_leftfinger"/>
       <origin xyz="0 0 0.0584" rpy="0 0 0"/>
       <axis xyz="0 1 0"/>
-      <limit effort="20" lower="0.0" upper="0.04" velocity="0.3"/>
+      <limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
     </joint>
     <joint name="${ns}_finger_joint2" type="prismatic">
       <parent link="${ns}_hand"/>
       <child link="${ns}_rightfinger"/>
       <origin xyz="0 0 0.0584" rpy="0 0 0"/>
       <axis xyz="0 -1 0"/>
-      <limit effort="20" lower="0.0" upper="0.04" velocity="0.3"/>
+      <limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
       <mimic joint="${ns}_finger_joint1" />
     </joint>
   </xacro:macro>
diff --git a/franka_gripper/config/franka_gripper_node.yaml b/franka_gripper/config/franka_gripper_node.yaml
index 8799cbd639f4716f07d550162945c3a3bda08d7e..195ec8f399bacbcdf43994ab03b5d9bc8694a023 100644
--- a/franka_gripper/config/franka_gripper_node.yaml
+++ b/franka_gripper/config/franka_gripper_node.yaml
@@ -5,4 +5,4 @@ joint_names:
 default_speed: 0.1  # [m/s]
 default_grasp_epsilon:
   inner: 0.005 # [m]
-  outer: 0.005 # [m]
\ No newline at end of file
+  outer: 0.005 # [m]
diff --git a/panda_moveit_config/config/joint_limits.yaml b/panda_moveit_config/config/joint_limits.yaml
index b254201f58080a04166f7c02c757d46261b5de74..603067f270c9c54f0fc84d419cbad4ca022b2979 100644
--- a/panda_moveit_config/config/joint_limits.yaml
+++ b/panda_moveit_config/config/joint_limits.yaml
@@ -37,3 +37,13 @@ joint_limits:
     max_velocity: 2.871
     has_acceleration_limits: false
     max_acceleration: 0
+  panda_finger_joint1:
+    has_velocity_limits: true
+    max_velocity: 0.1
+    has_acceleration_limits: false
+    max_acceleration: 0
+  panda_finger_joint2:
+    has_velocity_limits: true
+    max_velocity: 0.1
+    has_acceleration_limits: false
+    max_acceleration: 0
diff --git a/panda_moveit_config/launch/trajectory_execution.launch.xml b/panda_moveit_config/launch/trajectory_execution.launch.xml
index b6c03c9b75d36198aa21aecd195f6a62ad4bf96a..72906ef58f7dafd89692db66ad0c22e4f2792408 100644
--- a/panda_moveit_config/launch/trajectory_execution.launch.xml
+++ b/panda_moveit_config/launch/trajectory_execution.launch.xml
@@ -7,7 +7,7 @@
   <param name="moveit_manage_controllers" value="$(arg moveit_manage_controllers)"/>
 
   <!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution -->
-  <param name="trajectory_execution/allowed_execution_duration_scaling" value="1.2"/> <!-- default 1.2 -->
+  <param name="trajectory_execution/allowed_execution_duration_scaling" value="1.5"/> <!-- default 1.2 -->
   <!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) -->
   <param name="trajectory_execution/allowed_goal_duration_margin" value="0.5"/> <!-- default 0.5 -->
   <!-- Allowed joint-value tolerance for validation that trajectory's first point matches current robot state -->