From fc58fbd308252a0f28017eb643f3f5dee764abd6 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Tue, 6 Aug 2024 21:34:07 +0000 Subject: [PATCH] Switch costmap_queue to use modern CMake idioms. Signed-off-by: Chris Lalancette --- .../costmap_queue/CMakeLists.txt | 46 +++++++++++-------- nav2_dwb_controller/costmap_queue/package.xml | 4 +- 2 files changed, 28 insertions(+), 22 deletions(-) diff --git a/nav2_dwb_controller/costmap_queue/CMakeLists.txt b/nav2_dwb_controller/costmap_queue/CMakeLists.txt index 3cb0d967f8..28d47ed3dd 100644 --- a/nav2_dwb_controller/costmap_queue/CMakeLists.txt +++ b/nav2_dwb_controller/costmap_queue/CMakeLists.txt @@ -4,26 +4,20 @@ project(costmap_queue) find_package(ament_cmake REQUIRED) find_package(nav2_common REQUIRED) find_package(nav2_costmap_2d REQUIRED) -find_package(rclcpp REQUIRED) nav2_package() -include_directories( - include -) - add_library(${PROJECT_NAME} SHARED src/costmap_queue.cpp src/limited_costmap_queue.cpp ) - -set(dependencies - rclcpp - nav2_costmap_2d +target_include_directories(${PROJECT_NAME} + PUBLIC + "$" + "$" ) - -ament_target_dependencies(${PROJECT_NAME} - ${dependencies} +target_link_libraries(${PROJECT_NAME} PUBLIC + nav2_costmap_2d::nav2_costmap_2d_core ) if(BUILD_TESTING) @@ -34,24 +28,36 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) + find_package(rclcpp REQUIRED) + + ament_find_gtest() + ament_add_gtest(mbq_test test/mbq_test.cpp) - ament_target_dependencies(mbq_test ${dependencies}) + target_link_libraries(mbq_test + ${PROJECT_NAME} + ) ament_add_gtest(utest test/utest.cpp) - ament_target_dependencies(utest ${dependencies}) - target_link_libraries(utest ${PROJECT_NAME}) + target_link_libraries(utest + ${PROJECT_NAME} + nav2_costmap_2d::nav2_costmap_2d_core + rclcpp::rclcpp + ) endif() install(TARGETS ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin ) install(DIRECTORY include/ - DESTINATION include/ + DESTINATION include/${PROJECT_NAME} ) -ament_export_include_directories(include) +ament_export_include_directories(include/${PROJECT_NAME}) ament_export_libraries(${PROJECT_NAME}) +ament_export_dependencies(nav2_costmap_2d) +ament_export_targets(${PROJECT_NAME}) ament_package() diff --git a/nav2_dwb_controller/costmap_queue/package.xml b/nav2_dwb_controller/costmap_queue/package.xml index 4ea5fa964d..3a9a7bf9cc 100644 --- a/nav2_dwb_controller/costmap_queue/package.xml +++ b/nav2_dwb_controller/costmap_queue/package.xml @@ -10,11 +10,11 @@ nav2_common nav2_costmap_2d - rclcpp + ament_cmake_gtest ament_lint_common ament_lint_auto - ament_cmake_gtest + rclcpp ament_cmake