diff --git a/CMakeLists.txt b/CMakeLists.txt
index cf96b3652bcb8373e54876205bbec23d0bfe0c0d..7afd1f6ecc9bdfa8581814875b98e4d139ac2eb8 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -7,7 +7,7 @@ project(tiago_modules)
 ## Find catkin macros and libraries
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 ## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs)
+find_package(catkin REQUIRED COMPONENTS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs)
 
 ## System dependencies are found with CMake's conventions
 # find_package(Boost REQUIRED COMPONENTS system)
@@ -107,8 +107,8 @@ generate_dynamic_reconfigure_options(
 ## DEPENDS: system dependencies of this project that dependent projects also need
 catkin_package(
  INCLUDE_DIRS include
- LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module arm_module#leds_module 
- CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs moveit_msgs
+ LIBRARIES gripper_module play_motion_module head_module torso_module nav_module arm_module tts_module #leds_module
+ CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs
 #  DEPENDS system_lib
 )
 
diff --git a/package.xml b/package.xml
index 4d4a9d2f1eecd3576a0d3f24404fd6e81b5bd9f1..6f243bd56f0ee4ab09823b9380794a618f5dcddd 100644
--- a/package.xml
+++ b/package.xml
@@ -53,7 +53,6 @@
   <build_depend>pal_navigation_msgs</build_depend>
   <build_depend>pal_waypoint_msgs</build_depend>
   <build_depend>pal_interaction_msgs</build_depend>
-  <build_depend>moveit_msgs</build_depend>
   <build_depend>tf</build_depend>
   <!-- new dependencies -->
   <!--<build_depend>new build dependency</build_depend>-->
@@ -70,7 +69,6 @@
   <run_depend>pal_navigation_msgs</run_depend>
   <run_depend>pal_waypoint_msgs</run_depend>
   <run_depend>pal_interaction_msgs</run_depend>
-  <run_depend>moveit_msgs</run_depend>
   <run_depend>tf</run_depend>
   <!-- new dependencies -->
   <!--<run_depend>new run dependency</run_depend>-->