diff --git a/CMakeLists.txt b/CMakeLists.txt
index 0990695f844632af82ed25efb5f76b441d2a0f39..4ff38c947f646d5d3f80bb1e51d0c6173121a226 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)
+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_interaction_msgs pal_waypoint_msgs)
 
 ## System dependencies are found with CMake's conventions
 # find_package(Boost REQUIRED COMPONENTS system)
@@ -93,6 +93,7 @@ generate_dynamic_reconfigure_options(
   cfg/NavModule.cfg
   cfg/TTSModule.cfg
   cfg/ArmModule.cfg
+  cfg/MovePlatformModule.cfg
 )
 
 ###################################
@@ -106,7 +107,7 @@ 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
+ LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module arm_module move_platform_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
 
 #  DEPENDS system_lib
@@ -228,6 +229,21 @@ target_link_libraries(arm_module ${iriutils_LIBRARY})
 ## either from message generation or dynamic reconfigure
 add_dependencies(arm_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
 
+## Declare a C++ library
+add_library(move_platform_module
+  src/move_platform_module.cpp
+)
+
+target_link_libraries(move_platform_module ${catkin_LIBRARIES})
+target_link_libraries(move_platform_module ${iriutils_LIBRARY})
+##Link to other modules
+##target_link_libraries(new_module <module path>/lib<module_name>.so)
+
+## Add cmake target dependencies of the library
+## as an example, code may need to be generated before libraries
+## either from message generation or dynamic reconfigure
+add_dependencies(move_platform_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
 ## Declare a C++ executable
 ## With catkin_make all packages are built within a single CMake context
 ## The recommended prefix ensures that target names across packages don't collide