diff --git a/ur5_moveit_config/config/controllers.yaml b/ur5_moveit_config/config/controllers.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..54fc1eda9ac186996ea25a61759edc00ca8c37dd
--- /dev/null
+++ b/ur5_moveit_config/config/controllers.yaml
@@ -0,0 +1,12 @@
+controller_manager_ns: pr2_controller_manager
+controller_list:
+  - name: ""
+    ns: joint_trajectory_action
+    default: true
+    joints:
+      - shoulder_pan_joint
+      - shoulder_lift_joint
+      - elbow_joint
+      - wrist_1_joint
+      - wrist_2_joint
+      - wrist_3_joint
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/config/joint_names.yaml b/ur5_moveit_config/config/joint_names.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..c2e7cc2e8b5c38d4003f9965c865df7a17bfebdb
--- /dev/null
+++ b/ur5_moveit_config/config/joint_names.yaml
@@ -0,0 +1 @@
+controller_joint_names: ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
diff --git a/ur5_moveit_config/launch/moveit_planning_execution.launch b/ur5_moveit_config/launch/moveit_planning_execution.launch
new file mode 100644
index 0000000000000000000000000000000000000000..aa26da161378336899cacce71bb0a119bcfc99ca
--- /dev/null
+++ b/ur5_moveit_config/launch/moveit_planning_execution.launch
@@ -0,0 +1,46 @@
+<launch>
+  <!-- The planning and execution components of MoveIt! configured to run -->
+  <!-- using the ROS-Industrial interface. -->
+ 
+  <!-- the "sim" argument controls whether we connect to a Simulated or Real robot -->
+  <!--  - if sim=false, a robot_ip argument is required -->
+  <arg name="sim" default="true" />
+  <arg name="robot_ip" unless="$(arg sim)" />
+  
+  <!-- load robot specific joint names (in order expected by controller) -->
+   <rosparam command="load" file="$(find ur5_moveit_config)/config/joint_names.yaml"/>
+ 
+  <!-- load the robot_description parameter before launching ROS-I nodes -->
+  <include file="$(find ur5_moveit_config)/launch/planning_context.launch" >
+    <arg name="load_robot_description" value="true" />
+  </include>
+
+  <!-- run the robot simulator and action interface nodes -->
+  <group if="$(arg sim)">
+    <include file="$(find industrial_robot_simulator)/launch/robot_interface_simulator.launch" />
+  </group>
+
+  <!-- run the "real robot" interface nodes -->
+  <!--   - this typically includes: robot_state, motion_interface, and joint_trajectory_action nodes -->
+  <!--   - replace these calls with appropriate robot-specific calls or launch files -->
+  <group unless="$(arg sim)">
+    <!-- UR driver consists of a single node - does not currrently follow ROS-I convention -->
+    <node name="ur_driver" pkg="ur_driver" type="driver.py" args="$(arg robot_ip)" >
+      <remap from="follow_joint_trajectory/" to="joint_trajectory_action/"/>
+    </node>
+  </group>
+
+  <!-- publish the robot state (tf transforms) -->
+  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
+
+  <include file="$(find ur5_moveit_config)/launch/move_group.launch">
+    <arg name="publish_monitored_planning_scene" value="true" />
+  </include>
+
+  <include file="$(find ur5_moveit_config)/launch/moveit_rviz.launch">
+    <arg name="config" value="true"/>
+  </include>
+  
+  <include file="$(find ur5_moveit_config)/launch/default_warehouse_db.launch" />
+
+</launch>
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>