diff --git a/ur5_moveit_config/config/joint_limits.yaml b/ur5_moveit_config/config/joint_limits.yaml
index 801a5e1141819314ca1728af2a1e2940cde9ac63..9b4d75b29d137281671c3ce143edcaee680f216c 100644
--- a/ur5_moveit_config/config/joint_limits.yaml
+++ b/ur5_moveit_config/config/joint_limits.yaml
@@ -1,31 +1,31 @@
 joint_limits:
   elbow_joint:
     has_velocity_limits: true
-    max_velocity: 1.0
+    max_velocity: 0.45
     has_acceleration_limits: true
     max_acceleration: 1.0
   shoulder_lift_joint:
     has_velocity_limits: true
-    max_velocity: 1.0
+    max_velocity: 0.45
     has_acceleration_limits: true
     max_acceleration: 1.0
   shoulder_pan_joint:
     has_velocity_limits: true
-    max_velocity: 1.0
+    max_velocity: 0.45
     has_acceleration_limits: true
     max_acceleration: 1.0
   wrist_1_joint:
     has_velocity_limits: true
-    max_velocity: 1.0
+    max_velocity: 0.45
     has_acceleration_limits: true
     max_acceleration: 1.0
   wrist_2_joint:
     has_velocity_limits: true
-    max_velocity: 1.0
+    max_velocity: 0.45
     has_acceleration_limits: true
     max_acceleration: 1.0
   wrist_3_joint:
     has_velocity_limits: true
-    max_velocity: 1.0
+    max_velocity: 0.45
     has_acceleration_limits: true
-    max_acceleration: 1.0
\ No newline at end of file
+    max_acceleration: 1.0
diff --git a/ur5_moveit_config/launch/ur5_moveit_controller_manager.launch b/ur5_moveit_config/launch/ur5_moveit_controller_manager.launch
index 5d02698d7b05f6356110c54ddd75cfbc5ed7084b..102f84eb33dea54786905d304d8271c35d92b17e 100644
--- a/ur5_moveit_config/launch/ur5_moveit_controller_manager.launch
+++ b/ur5_moveit_config/launch/ur5_moveit_controller_manager.launch
@@ -1,3 +1,17 @@
 <launch>
+  <arg name="moveit_controller_manager"
+       default="pr2_moveit_controller_manager/Pr2MoveItControllerManager"/>
+  <param name="moveit_controller_manager"
+         value="$(arg moveit_controller_manager)"/>
 
+  <arg name="controller_manager_name"
+       default="pr2_controller_manager" />
+  <param name="controller_manager_name"
+         value="$(arg controller_manager_name)"/>
+
+  <arg name="use_controller_manager" default="false" />
+  <param name="use_controller_manager"
+         value="$(arg use_controller_manager)" />
+
+  <rosparam file="$(find ur5_moveit_config)/config/controllers.yaml"/>
 </launch>