Skip to content
Snippets Groups Projects
Commit 66df5bb5 authored by Ferran Martínez Felipe's avatar Ferran Martínez Felipe
Browse files

Merge branch 'master' of ssh://gitlab.iri.upc.edu:2202/nen/modules/tiago_modules

Conflicts:
	CMakeLists.txt
	include/tiago_modules/head_module.h
parents b205589a 601fab73
No related branches found
No related tags found
No related merge requests found
...@@ -7,7 +7,7 @@ project(tiago_modules) ...@@ -7,7 +7,7 @@ project(tiago_modules)
## Find catkin macros and libraries ## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages ## 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 ## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system) # find_package(Boost REQUIRED COMPONENTS system)
...@@ -109,6 +109,7 @@ catkin_package( ...@@ -109,6 +109,7 @@ catkin_package(
INCLUDE_DIRS include INCLUDE_DIRS include
LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module#leds_module 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 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 # DEPENDS system_lib
) )
......
...@@ -53,7 +53,6 @@ ...@@ -53,7 +53,6 @@
<build_depend>pal_navigation_msgs</build_depend> <build_depend>pal_navigation_msgs</build_depend>
<build_depend>pal_waypoint_msgs</build_depend> <build_depend>pal_waypoint_msgs</build_depend>
<build_depend>pal_interaction_msgs</build_depend> <build_depend>pal_interaction_msgs</build_depend>
<build_depend>moveit_msgs</build_depend>
<build_depend>tf</build_depend> <build_depend>tf</build_depend>
<!-- new dependencies --> <!-- new dependencies -->
<!--<build_depend>new build dependency</build_depend>--> <!--<build_depend>new build dependency</build_depend>-->
...@@ -70,7 +69,6 @@ ...@@ -70,7 +69,6 @@
<run_depend>pal_navigation_msgs</run_depend> <run_depend>pal_navigation_msgs</run_depend>
<run_depend>pal_waypoint_msgs</run_depend> <run_depend>pal_waypoint_msgs</run_depend>
<run_depend>pal_interaction_msgs</run_depend> <run_depend>pal_interaction_msgs</run_depend>
<run_depend>moveit_msgs</run_depend>
<run_depend>tf</run_depend> <run_depend>tf</run_depend>
<!-- new dependencies --> <!-- new dependencies -->
<!--<run_depend>new run dependency</run_depend>--> <!--<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