diff --git a/ur5_joint_limited_moveit_config/.setup_assistant b/ur5_joint_limited_moveit_config/.setup_assistant
deleted file mode 100644
index ebd93ed539f5f7b327fe7ceb9946602d0d6b8daf..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/.setup_assistant
+++ /dev/null
@@ -1,8 +0,0 @@
-moveit_setup_assistant_config:
-  URDF:
-    package: 
-    relative_path: /home/sedwards/ros/groovy_dev/universal_robot/ur_description/urdf/ur5_joint_limited_robot.urdf
-  SRDF:
-    relative_path: config/ur5.srdf
-  CONFIG:
-    generated_timestamp: 1369363902
\ No newline at end of file
diff --git a/ur5_joint_limited_moveit_config/CMakeLists.txt b/ur5_joint_limited_moveit_config/CMakeLists.txt
deleted file mode 100644
index 4a17ee4fa8f42790cb45ba81530891bea8e12f54..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/CMakeLists.txt
+++ /dev/null
@@ -1,9 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(ur5_joint_limited_moveit_config)
-
-find_package(catkin REQUIRED)
-
-catkin_package()
-
-install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
-install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
diff --git a/ur5_joint_limited_moveit_config/config/joint_limits.yaml b/ur5_joint_limited_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index 801a5e1141819314ca1728af2a1e2940cde9ac63..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,31 +0,0 @@
-joint_limits:
-  elbow_joint:
-    has_velocity_limits: true
-    max_velocity: 1.0
-    has_acceleration_limits: true
-    max_acceleration: 1.0
-  shoulder_lift_joint:
-    has_velocity_limits: true
-    max_velocity: 1.0
-    has_acceleration_limits: true
-    max_acceleration: 1.0
-  shoulder_pan_joint:
-    has_velocity_limits: true
-    max_velocity: 1.0
-    has_acceleration_limits: true
-    max_acceleration: 1.0
-  wrist_1_joint:
-    has_velocity_limits: true
-    max_velocity: 1.0
-    has_acceleration_limits: true
-    max_acceleration: 1.0
-  wrist_2_joint:
-    has_velocity_limits: true
-    max_velocity: 1.0
-    has_acceleration_limits: true
-    max_acceleration: 1.0
-  wrist_3_joint:
-    has_velocity_limits: true
-    max_velocity: 1.0
-    has_acceleration_limits: true
-    max_acceleration: 1.0
\ No newline at end of file
diff --git a/ur5_joint_limited_moveit_config/config/kinematics.yaml b/ur5_joint_limited_moveit_config/config/kinematics.yaml
deleted file mode 100644
index 5d492ac1f83c7fa00ed0fd19e0288dff7b6c7611..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/config/kinematics.yaml
+++ /dev/null
@@ -1,5 +0,0 @@
-manipulator:
-  kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
-  kinematics_solver_search_resolution: 0.005
-  kinematics_solver_timeout: 0.005
-  kinematics_solver_attempts: 3
diff --git a/ur5_joint_limited_moveit_config/config/ompl_planning.yaml b/ur5_joint_limited_moveit_config/config/ompl_planning.yaml
deleted file mode 100644
index 4267589c797b574cb9086dbd9ba5bf29f0fb04a2..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/config/ompl_planning.yaml
+++ /dev/null
@@ -1,31 +0,0 @@
-planner_configs:
-  SBLkConfigDefault:
-    type: geometric::SBL
-  LBKPIECEkConfigDefault:
-    type: geometric::LBKPIECE
-  RRTkConfigDefault:
-    type: geometric::RRT
-  RRTConnectkConfigDefault:
-    type: geometric::RRTConnect
-  LazyRRTkConfigDefault:
-    type: geometric::LazyRRT
-  ESTkConfigDefault:
-    type: geometric::EST
-  KPIECEkConfigDefault:
-    type: geometric::KPIECE
-  RRTStarkConfigDefault:
-    type: geometric::RRTstar
-  BKPIECEkConfigDefault:
-    type: geometric::BKPIECE
-manipulator:
-  planner_configs:
-    - SBLkConfigDefault
-    - LBKPIECEkConfigDefault
-    - RRTkConfigDefault
-    - RRTConnectkConfigDefault
-    - ESTkConfigDefault
-    - KPIECEkConfigDefault
-    - BKPIECEkConfigDefault
-    - RRTStarkConfigDefault
-  projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
-  longest_valid_segment_fraction: 0.05
\ No newline at end of file
diff --git a/ur5_joint_limited_moveit_config/config/ur5.srdf b/ur5_joint_limited_moveit_config/config/ur5.srdf
deleted file mode 100644
index f47d58b6594d1b83938a5893fcbaf45dd27f1b3b..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/config/ur5.srdf
+++ /dev/null
@@ -1,41 +0,0 @@
-<?xml version="1.0" ?>
-<!--This does not replace URDF, and is not an extension of URDF.
-    This is a format for representing semantic information about the robot structure.
-    A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
--->
-<robot name="ur5">
-    <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
-    <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
-    <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
-    <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
-    <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
-    <group name="manipulator">
-        <link name="base_link" />
-        <link name="shoulder_link" />
-        <link name="upper_arm_link" />
-        <link name="forearm_link" />
-        <link name="wrist_1_link" />
-        <link name="wrist_2_link" />
-        <link name="wrist_3_link" />
-        <link name="ee_link" />
-    </group>
-    <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
-    <group_state name="home" group="manipulator">
-        <joint name="elbow_joint" value="0" />
-        <joint name="shoulder_lift_joint" value="0" />
-        <joint name="shoulder_pan_joint" value="0" />
-        <joint name="wrist_1_joint" value="0" />
-        <joint name="wrist_2_joint" value="0" />
-        <joint name="wrist_3_joint" value="0" />
-    </group_state>
-    <!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
-    <virtual_joint name="FixedBase" type="fixed" parent_frame="world" child_link="base_link" />
-    <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
-    <disable_collisions link1="base_link" link2="shoulder_link" reason="Adjacent" />
-    <disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
-    <disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
-    <disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
-    <disable_collisions link1="wrist_1_link" link2="wrist_2_link" reason="Adjacent" />
-    <disable_collisions link1="wrist_1_link" link2="wrist_3_link" reason="Never" />
-    <disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent" />
-</robot>
diff --git a/ur5_joint_limited_moveit_config/default_warehouse_mongo_db/mongod.lock b/ur5_joint_limited_moveit_config/default_warehouse_mongo_db/mongod.lock
deleted file mode 100755
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ur5_joint_limited_moveit_config/launch/default_warehouse_db.launch b/ur5_joint_limited_moveit_config/launch/default_warehouse_db.launch
deleted file mode 100644
index a246c6a57a5ba0610129b0b2edcffb332b471d2f..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/default_warehouse_db.launch
+++ /dev/null
@@ -1,13 +0,0 @@
-<launch>
-
-  <arg name="reset" default="false"/>
-
-  <!-- Launch the warehouse with a default database location -->  
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/warehouse.launch">
-    <arg name="moveit_warehouse_database_path" value="$(find ur5_joint_limited_moveit_config)/default_warehouse_mongo_db" />
-  </include>
-
-  <!-- If we want to reset the database, run this node -->
-  <node if="$(arg reset)" name="$(anon moveit_default_db_reset)" type="moveit_init_demo_warehouse" pkg="moveit_ros_warehouse" respawn="false" output="screen" />
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/demo.launch b/ur5_joint_limited_moveit_config/launch/demo.launch
deleted file mode 100644
index 5a43cd393ffa6c0c672e75eda2d693b5e8bb6c7a..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/demo.launch
+++ /dev/null
@@ -1,25 +0,0 @@
-<launch>
-
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/planning_context.launch">
-    <arg name="load_robot_description" value="true"/>
-  </include>
-
-  
-
-  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
-    <param name="/use_gui" value="false"/>
-  </node>
-  
-  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />
-
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/move_group.launch">
-    <arg name="allow_trajectory_execution" value="false"/>
-  </include>
-
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/moveit_rviz.launch">
-    <arg name="config" value="true"/>
-  </include>
-
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/default_warehouse_db.launch" />
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/move_group.launch b/ur5_joint_limited_moveit_config/launch/move_group.launch
deleted file mode 100644
index 5179fdce82b9bfbc550514176ba3b32c821af63c..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/move_group.launch
+++ /dev/null
@@ -1,57 +0,0 @@
-<launch>
-
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/planning_context.launch" />
-
-  <arg name="debug" default="false" />
-  <arg unless="$(arg debug)" name="launch_prefix" value="" />
-  <arg     if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
-
-  <arg name="info" default="$(arg debug)" />  
-  <arg unless="$(arg info)" name="command_args" value="" />
-  <arg     if="$(arg info)" name="command_args" value="--debug" />
-
-  <arg name="allow_trajectory_execution" default="true"/>
-  <arg name="max_safe_path_cost" default="1"/>
-  <arg name="jiggle_fraction" default="0.05" />
-  <arg name="publish_monitored_planning_scene" default="false"/>
-
-  <include ns="move_group" file="$(find ur5_joint_limited_moveit_config)/launch/planning_pipeline.launch">
-    <arg name="pipeline" value="ompl" />
-  </include>
-
-  <include ns="move_group" file="$(find ur5_joint_limited_moveit_config)/launch/trajectory_execution.launch" if="$(arg allow_trajectory_execution)">
-    <arg name="moveit_controller_manager" value="ur5" /> 
-    <arg name="moveit_manage_controllers" value="true" />
-  </include>
-
-  <include ns="move_group" file="$(find ur5_joint_limited_moveit_config)/launch/sensor_manager.launch" if="$(arg allow_trajectory_execution)">
-    <arg name="moveit_sensor_manager" value="ur5" /> 
-  </include>
-
-  <node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
-    <!-- Set the display variable, in case OpenGL code is used internally -->
-    <env name="DISPLAY" value="$(optenv DISPLAY :0)" />
-
-    <param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
-    <param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
-    <param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
-
-    <!-- MoveGroup capabilities to load -->
-    <param name="capabilities" value="move_group/MoveGroupCartesianPathService
-				      move_group/MoveGroupExecuteService
-				      move_group/MoveGroupKinematicsService
-				      move_group/MoveGroupMoveAction
-				      move_group/MoveGroupPickPlaceAction
-				      move_group/MoveGroupPlanService
-				      move_group/MoveGroupQueryPlannersService
-				      move_group/MoveGroupStateValidationService
-				      " />
-
-    <!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
-    <param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
-    <param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
-    <param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
-    <param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
-  </node>
-  
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/moveit.rviz b/ur5_joint_limited_moveit_config/launch/moveit.rviz
deleted file mode 100644
index ad9bda98022e8454e65f9552afd72af87c65d64b..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/moveit.rviz
+++ /dev/null
@@ -1,203 +0,0 @@
-Panels:
-  - Class: rviz/Displays
-    Help Height: 84
-    Name: Displays
-    Property Tree Widget:
-      Expanded:
-        - /Global Options1
-        - /MotionPlanning1
-        - /MotionPlanning1/Planning Request1
-        - /MotionPlanning1/Planned Path1
-      Splitter Ratio: 0.74256
-    Tree Height: 379
-  - Class: rviz/Help
-    Name: Help
-  - Class: rviz/Views
-    Expanded:
-      - /Current View1
-    Name: Views
-    Splitter Ratio: 0.5
-Visualization Manager:
-  Class: ""
-  Displays:
-    - Alpha: 0.5
-      Cell Size: 1
-      Class: rviz/Grid
-      Color: 160; 160; 164
-      Enabled: true
-      Line Style:
-        Line Width: 0.03
-        Value: Lines
-      Name: Grid
-      Normal Cell Count: 0
-      Offset:
-        X: 0
-        Y: 0
-        Z: 0
-      Plane: XY
-      Plane Cell Count: 10
-      Reference Frame: <Fixed Frame>
-      Value: true
-    - Class: moveit_rviz_plugin/MotionPlanning
-      Enabled: true
-      MoveIt_Goal_Tolerance: 0
-      MoveIt_Planning_Time: 5
-      MoveIt_Use_Constraint_Aware_IK: true
-      MoveIt_Warehouse_Host: 127.0.0.1
-      MoveIt_Warehouse_Port: 33829
-      Name: MotionPlanning
-      Planned Path:
-        Links:
-          base_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          forearm_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          shoulder_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          upper_arm_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          wrist_1_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          wrist_2_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          wrist_3_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-        Loop Animation: false
-        Robot Alpha: 0.5
-        Show Robot Collision: false
-        Show Robot Visual: true
-        Show Trail: false
-        State Display Time: 0.05 s
-        Trajectory Topic: /move_group/display_planned_path
-      Planning Metrics:
-        Payload: 1
-        Show Joint Torques: false
-        Show Manipulability: false
-        Show Manipulability Index: false
-        Show Weight Limit: false
-        TextHeight: 0.08
-      Planning Request:
-        Colliding Link Color: 255; 0; 0
-        Goal State Alpha: 1
-        Goal State Color: 250; 128; 0
-        Interactive Marker Size: 0
-        Joint Violation Color: 255; 0; 255
-        Planning Group: manipulator
-        Query Goal State: true
-        Query Start State: false
-        Show Workspace: false
-        Start State Alpha: 1
-        Start State Color: 0; 255; 0
-      Planning Scene Topic: /move_group/monitored_planning_scene
-      Robot Description: robot_description
-      Scene Geometry:
-        Scene Alpha: 0.9
-        Scene Color: 50; 230; 50
-        Scene Display Time: 0.2
-        Show Scene Geometry: true
-        Voxel Coloring: Z-Axis
-        Voxel Rendering: Occupied Voxels
-      Scene Robot:
-        Attached Body Color: 150; 50; 150
-        Links:
-          base_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          forearm_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          shoulder_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          upper_arm_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          wrist_1_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          wrist_2_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-          wrist_3_link:
-            Alpha: 1
-            Show Axes: false
-            Show Trail: false
-            Value: true
-        Robot Alpha: 0.5
-        Show Scene Robot: true
-      Value: true
-  Enabled: true
-  Global Options:
-    Background Color: 48; 48; 48
-    Fixed Frame: /base_link
-  Name: root
-  Tools:
-    - Class: rviz/MoveCamera
-    - Class: rviz/Select
-    - Class: rviz/Interact
-      Hide Inactive Objects: true
-  Value: true
-  Views:
-    Current:
-      Class: rviz/XYOrbit
-      Distance: 4.85948
-      Focal Point:
-        X: 0.113567
-        Y: 0.10592
-        Z: 2.23518e-07
-      Name: Current View
-      Near Clip Distance: 0.01
-      Pitch: 0.219797
-      Target Frame: /base_link
-      Value: XYOrbit (rviz)
-      Yaw: 1.72177
-    Saved: ~
-Window Geometry:
-  Displays:
-    collapsed: false
-  Height: 1000
-  Help:
-    collapsed: false
-  Hide Left Dock: false
-  Hide Right Dock: false
-  Motion Planning:
-    collapsed: false
-  QMainWindow State: 000000ff00000000fd0000000100000000000002a2000003a2fc0200000005fb000000100044006900730070006c006100790073010000002800000210000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e0067010000023e0000018c0000017400ffffff00000258000003a200000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
-  Views:
-    collapsed: false
-  Width: 1280
-  X: 1
-  Y: 53
diff --git a/ur5_joint_limited_moveit_config/launch/moveit_rviz.launch b/ur5_joint_limited_moveit_config/launch/moveit_rviz.launch
deleted file mode 100644
index d1f5dc3583dd9d74b1c4dc9f7b48e673122870c9..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/moveit_rviz.launch
+++ /dev/null
@@ -1,16 +0,0 @@
-<launch>
-
-  <arg name="debug" default="false" />
-  <arg unless="$(arg debug)" name="launch_prefix" value="" />
-  <arg     if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
-
-  <arg name="config" default="false" />
-  <arg unless="$(arg config)" name="command_args" value="" />
-  <arg     if="$(arg config)" name="command_args" value="-d $(find ur5_joint_limited_moveit_config)/launch/moveit.rviz" />
-  
-  <node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false"
-	args="$(arg command_args)" output="screen">
-    <rosparam command="load" file="$(find ur5_joint_limited_moveit_config)/config/kinematics.yaml"/>
-  </node>
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/ompl_planning_pipeline.launch b/ur5_joint_limited_moveit_config/launch/ompl_planning_pipeline.launch
deleted file mode 100644
index accbb5b3f3f79a70ca00e6d15a65c009c178e2fb..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/ompl_planning_pipeline.launch
+++ /dev/null
@@ -1,23 +0,0 @@
-<launch>
-
-  <!-- OMPL Plugin for MoveIt! -->
-  <arg name="planning_plugin" value="ompl_interface/OMPLPlanner" />
-
-  <!-- The request adapters (plugins) used when planning with OMPL. 
-       ORDER MATTERS -->
-  <arg name="planning_adapters" value="default_planner_request_adapters/AddTimeParameterization
-				       default_planner_request_adapters/FixWorkspaceBounds
-				       default_planner_request_adapters/FixStartStateBounds
-				       default_planner_request_adapters/FixStartStateCollision
-				       default_planner_request_adapters/FixStartStatePathConstraints" />
-
-  <arg name="start_state_max_bounds_error" value="0.1" />
-
-  <param name="planning_plugin" value="$(arg planning_plugin)" />
-  <param name="request_adapters" value="$(arg planning_adapters)" />
-  <param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
-
-  <rosparam command="load" file="$(find ur5_joint_limited_moveit_config)/config/kinematics.yaml"/>
-  <rosparam command="load" file="$(find ur5_joint_limited_moveit_config)/config/ompl_planning.yaml"/>
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/planning_context.launch b/ur5_joint_limited_moveit_config/launch/planning_context.launch
deleted file mode 100644
index 38717127bd339f72f4eff411d96bf5c83985ae6d..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/planning_context.launch
+++ /dev/null
@@ -1,16 +0,0 @@
-<launch>
-  <!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->
-  <arg name="load_robot_description" default="false"/>
-
-  <!-- Load universal robotic description format (URDF) -->
-  <param if="$(arg load_robot_description)" name="robot_description" textfile="/home/sedwards/ros/groovy_dev/universal_robot/ur_description/urdf/ur5_joint_limited_robot.urdf" />
-      
-  <!-- The semantic description that corresponds to the URDF -->
-  <param name="robot_description_semantic" textfile="$(find ur5_joint_limited_moveit_config)/config/ur5.srdf" />
-  
-  <!-- Load to the parameter server yaml files -->
-  <group ns="robot_description_planning">    
-    <rosparam command="load" file="$(find ur5_joint_limited_moveit_config)/config/joint_limits.yaml"/>
-  </group>
-  
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/planning_pipeline.launch b/ur5_joint_limited_moveit_config/launch/planning_pipeline.launch
deleted file mode 100644
index 092b64d4592deb0eb0561509c1223314b19b58fd..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/planning_pipeline.launch
+++ /dev/null
@@ -1,10 +0,0 @@
-<launch>
-
-  <!-- This file makes it easy to include different planning pipelines; 
-       It is assumed that all planning pipelines are named XXX_planning_pipeline.launch  -->  
-
-  <arg name="pipeline" default="ompl" />
-
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch" />
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/run_benchmark_ompl.launch b/ur5_joint_limited_moveit_config/launch/run_benchmark_ompl.launch
deleted file mode 100644
index d67abc4d8062ce8d3257068aa1d58cfed5cf55cc..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/run_benchmark_ompl.launch
+++ /dev/null
@@ -1,22 +0,0 @@
-<launch>
-
-  <!-- This argument must specify the list of .cfg files to process for benchmarking -->
-  <arg name="cfg" />
-
-  <!-- Load URDF -->
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/planning_context.launch">
-    <arg name="load_robot_description" value="true"/>
-  </include>
-
-  <!-- Start the database -->
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/warehouse.launch">
-    <arg name="moveit_warehouse_database_path" value="moveit_ompl_benchmark_warehouse"/>
-  </include>  
-
-  <!-- Start Benchmark Executable -->
-  <node name="$(anon moveit_benchmark)" pkg="moveit_ros_benchmarks" type="moveit_run_benchmark" args="$(arg cfg) --benchmark-planners" respawn="false" output="screen">
-    <rosparam command="load" file="$(find ur5_joint_limited_moveit_config)/config/kinematics.yaml"/>
-    <rosparam command="load" file="$(find ur5_joint_limited_moveit_config)/config/ompl_planning.yaml"/>
-  </node>
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/sensor_manager.launch b/ur5_joint_limited_moveit_config/launch/sensor_manager.launch
deleted file mode 100644
index b1b2038c45b698fb50955cdbb20c3169e5de869f..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/sensor_manager.launch
+++ /dev/null
@@ -1,9 +0,0 @@
-<launch>
-
-  <!-- This file makes it easy to include the settings for sensor managers -->  
-
-  <!-- Load the robot specific sensor manager; this sets the moveit_sensor_manager ROS parameter -->
-  <arg name="moveit_sensor_manager" default="ur5" />
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch" />
-  
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/setup_assistant.launch b/ur5_joint_limited_moveit_config/launch/setup_assistant.launch
deleted file mode 100644
index a97957a99a11341cc1af66d10440222a7992070f..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/setup_assistant.launch
+++ /dev/null
@@ -1,15 +0,0 @@
-<!-- Re-launch the MoveIt Setup Assistant with this configuration package already loaded -->
-<launch>
-
-  <!-- Debug Info -->
-  <arg name="debug" default="false" />
-  <arg unless="$(arg debug)" name="launch_prefix" value="" />
-  <arg     if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
-
-  <!-- Run -->
-  <node pkg="moveit_setup_assistant" type="moveit_setup_assistant" name="moveit_setup_assistant" 
-	args="--config_pkg=ur5_joint_limited_moveit_config"
-	launch-prefix="$(arg launch_prefix)"
-        output="screen" />
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/trajectory_execution.launch b/ur5_joint_limited_moveit_config/launch/trajectory_execution.launch
deleted file mode 100644
index 1bc818f24fc4d370dbd99843e781029a0a558627..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/trajectory_execution.launch
+++ /dev/null
@@ -1,13 +0,0 @@
-<launch>
-
-  <!-- This file makes it easy to include the settings for trajectory execution  -->  
-
-  <!-- Flag indicating whether MoveIt! is allowed to load/unload  or switch controllers -->
-  <arg name="moveit_manage_controllers" default="true"/>
-  <param name="moveit_manage_controllers" value="$(arg moveit_manage_controllers)"/>
-  
-  <!-- Load the robot specific controller manager; this sets the moveit_controller_manager ROS parameter -->
-  <arg name="moveit_controller_manager" default="ur5" />
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch" />
-  
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/ur5_moveit_controller_manager.launch b/ur5_joint_limited_moveit_config/launch/ur5_moveit_controller_manager.launch
deleted file mode 100644
index 5d02698d7b05f6356110c54ddd75cfbc5ed7084b..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/ur5_moveit_controller_manager.launch
+++ /dev/null
@@ -1,3 +0,0 @@
-<launch>
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/ur5_moveit_sensor_manager.launch b/ur5_joint_limited_moveit_config/launch/ur5_moveit_sensor_manager.launch
deleted file mode 100644
index 5d02698d7b05f6356110c54ddd75cfbc5ed7084b..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/ur5_moveit_sensor_manager.launch
+++ /dev/null
@@ -1,3 +0,0 @@
-<launch>
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/warehouse.launch b/ur5_joint_limited_moveit_config/launch/warehouse.launch
deleted file mode 100644
index ee02d3080800f24e54ef208dd37200c6a1cb2f9a..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/warehouse.launch
+++ /dev/null
@@ -1,15 +0,0 @@
-<launch>
-  
-  <!-- The path to the database must be specified -->
-  <arg name="moveit_warehouse_database_path" />
-
-  <!-- Load warehouse parameters -->  
-  <include file="$(find ur5_joint_limited_moveit_config)/launch/warehouse_settings.launch" />
-
-  <!-- Run the DB server -->
-  <node name="$(anon mongo_wrapper_ros)" cwd="ROS_HOME" type="mongo_wrapper_ros.py" pkg="warehouse_ros">
-    <param name="overwrite" value="false"/>
-    <param name="database_path" value="$(arg moveit_warehouse_database_path)" />
-  </node>
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/launch/warehouse_settings.launch b/ur5_joint_limited_moveit_config/launch/warehouse_settings.launch
deleted file mode 100644
index d11aaeb21a1be35816cc2b66eea0c936a4b33854..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/launch/warehouse_settings.launch
+++ /dev/null
@@ -1,15 +0,0 @@
-<launch>
-  <!-- Set the parameters for the warehouse and run the mongodb server. -->
-
-  <!-- The default DB port for moveit (not default MongoDB port to avoid potential conflicts) -->  
-  <arg name="moveit_warehouse_port" default="33829" /> 
-
-  <!-- The default DB host for moveit -->
-  <arg name="moveit_warehouse_host" default="localhost" /> 
-  
-  <!-- Set parameters for the warehouse -->
-  <param name="warehouse_port" value="$(arg moveit_warehouse_port)"/>
-  <param name="warehouse_host" value="$(arg moveit_warehouse_host)"/>
-  <param name="warehouse_exec" value="mongod" />
-
-</launch>
diff --git a/ur5_joint_limited_moveit_config/package.xml b/ur5_joint_limited_moveit_config/package.xml
deleted file mode 100644
index edc0ef5ea278f936ced4f6931204478313ba2ceb..0000000000000000000000000000000000000000
--- a/ur5_joint_limited_moveit_config/package.xml
+++ /dev/null
@@ -1,22 +0,0 @@
-<package>
-
-  <name>ur5_joint_limited_moveit_config</name>
-  <version>0.2.0</version>
-  <description>
-     An automatically generated package with all the configuration and launch files for using the ur5 with the MoveIt Motion Planning Framework
-  </description>
-  <author email="assistant@moveit.ros.org">MoveIt Setup Assistant</author>
-  <maintainer email="assistant@moveit.ros.org">MoveIt Setup Assistant</maintainer>
-
-  <license>BSD</license>
-
-  <url type="website">http://moveit.ros.org/</url>
-  <url type="bugtracker">https://github.com/ros-planning/moveit_setup_assistant/issues</url>
-  <url type="repository">https://github.com/ros-planning/moveit_setup_assistant</url>
-
-  <run_depend>moveit_ros_move_group</run_depend>
-  ]
-
-  <buildtool_depend>catkin</buildtool_depend>
-  
-</package>
diff --git a/ur5_moveit_config/.setup_assistant b/ur5_moveit_config/.setup_assistant
index 24d21cddbdcb18dac2a17cbdedaafe7c231fb905..7b3c50b7a0c9ebf9b39bef6ff036b4d38e1b8981 100644
--- a/ur5_moveit_config/.setup_assistant
+++ b/ur5_moveit_config/.setup_assistant
@@ -1,8 +1,8 @@
 moveit_setup_assistant_config:
   URDF:
     package: ur_description
-    relative_path: urdf/ur5_robot.urdf.xacro
+    relative_path: urdf/ur5_joint_limited_robot.urdf
   SRDF:
     relative_path: config/ur5.srdf
   CONFIG:
-    generated_timestamp: 1369283055
+    generated_timestamp: 1369541351
\ No newline at end of file
diff --git a/ur5_moveit_config/launch/planning_context.launch b/ur5_moveit_config/launch/planning_context.launch
index 21aa0b0378efecdf76f980ecf2e36e979957dd0d..1f6ada328f99ef2e666af51c3ca4fc947b1933e1 100644
--- a/ur5_moveit_config/launch/planning_context.launch
+++ b/ur5_moveit_config/launch/planning_context.launch
@@ -3,7 +3,7 @@
   <arg name="load_robot_description" default="false"/>
 
   <!-- Load universal robotic description format (URDF) -->
-  <param if="$(arg load_robot_description)" name="robot_description" textfile="$(find ur_description)/urdf/ur5_robot.urdf" />
+  <param if="$(arg load_robot_description)" name="robot_description" textfile="$(find ur_description)/urdf/ur5_joint_limited_robot.urdf" />
       
   <!-- The semantic description that corresponds to the URDF -->
   <param name="robot_description_semantic" textfile="$(find ur5_moveit_config)/config/ur5.srdf" />