diff --git a/CMakeLists.txt b/CMakeLists.txt index 7afd1f6ecc9bdfa8581814875b98e4d139ac2eb8..c019c8951078be1f717ea67208963e8033726492 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -107,8 +107,9 @@ 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 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 + LIBRARIES gripper_module play_motion_module head_module torso_module nav_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 pal_waypoint_msgs pal_interaction_msgs + # DEPENDS system_lib )