From 7279d120c27b01ccb72c60375adf3b1723372724 Mon Sep 17 00:00:00 2001 From: Alopez <alopez@iri.upc.edu> Date: Wed, 18 Nov 2020 14:47:42 +0100 Subject: [PATCH] Fixed cmake error not found pal_waypoint_msgs when using the module from other code --- CMakeLists.txt | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6e6ea89..be57aab 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,6 +12,9 @@ find_package(pal_waypoint_msgs) if(${pal_waypoint_msgs_FOUND}) ADD_DEFINITIONS(-DHAVE_WAYPOINTS) + set(pal_waypoint_msgs_catkin_depends pal_navigation_msgs) +else() + set(pal_waypoint_msgs_catkin_depends ) endif() ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) @@ -109,7 +112,7 @@ set(module_bt_name tiago_nav_module_bt) catkin_package( INCLUDE_DIRS include LIBRARIES ${module_name} ${module_bt_name} - CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs iri_base_algorithm iri_behaviortree + CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs ${pal_waypoint_msgs_catkin_depends} iri_base_algorithm iri_behaviortree # DEPENDS system_lib ) -- GitLab