Skip to content
Snippets Groups Projects
Commit e9071480 authored by Irene Garcia Camacho's avatar Irene Garcia Camacho
Browse files

Merge branch 'move_platform' into 'master'

Move platform

See merge request nen/modules/tiago_modules!8
parents 7673ad4d 9e2f6e5f
No related branches found
No related tags found
No related merge requests found
......@@ -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
)
......
......@@ -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>-->
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment