diff --git a/CMakeLists.txt b/CMakeLists.txt index 4ff38c947f646d5d3f80bb1e51d0c6173121a226..940d6a8c143c1e997635b3470142761948e035bd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,12 +2,12 @@ cmake_minimum_required(VERSION 2.8.3) project(tiago_modules) ## Add support for C++11, supported in ROS Kinetic and newer -# add_definitions(-std=c++11) +add_definitions(-std=c++11) ## 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_interaction_msgs pal_waypoint_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 moveit_ros_planning_interface) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) @@ -108,7 +108,7 @@ generate_dynamic_reconfigure_options( catkin_package( INCLUDE_DIRS include 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 + 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_ros_planning_interface # DEPENDS system_lib ) diff --git a/package.xml b/package.xml index 6f243bd56f0ee4ab09823b9380794a618f5dcddd..41f80f3a0b6fc2767957bb3f77f5be2dcc15bdd4 100644 --- a/package.xml +++ b/package.xml @@ -54,6 +54,7 @@ <build_depend>pal_waypoint_msgs</build_depend> <build_depend>pal_interaction_msgs</build_depend> <build_depend>tf</build_depend> + <build_depend>moveit_ros_planning_interface</build_depend> <!-- new dependencies --> <!--<build_depend>new build dependency</build_depend>--> <run_depend>iri_ros_tools</run_depend> @@ -70,6 +71,7 @@ <run_depend>pal_waypoint_msgs</run_depend> <run_depend>pal_interaction_msgs</run_depend> <run_depend>tf</run_depend> + <run_depend>moveit_ros_planning_interface</run_depend> <!-- new dependencies --> <!--<run_depend>new run dependency</run_depend>-->