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

Merge branch 'move_base_module' into 'master'

Move base module

See merge request nen/modules/tiago_modules!5
parents 1bb2e5cd a83ec550
No related branches found
No related tags found
No related merge requests found
......@@ -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
......
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