From 19f89baa082afd1a836ac273b42ffb06173bbaf5 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sun, 10 Mar 2024 22:05:44 -0600 Subject: [PATCH] Link nav2_costmap_2d the old way * Upstream nav2 didn't backport it yet Signed-off-by: Ryan Friedman --- grid_map_costmap_2d/CMakeLists.txt | 3 ++- grid_map_costmap_2d/test/CMakeLists.txt | 2 ++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/grid_map_costmap_2d/CMakeLists.txt b/grid_map_costmap_2d/CMakeLists.txt index 201c8760..12504998 100644 --- a/grid_map_costmap_2d/CMakeLists.txt +++ b/grid_map_costmap_2d/CMakeLists.txt @@ -7,6 +7,7 @@ find_package(grid_map_cmake_helpers REQUIRED) find_package(grid_map_core REQUIRED) find_package(geometry_msgs REQUIRED) find_package(nav2_costmap_2d REQUIRED) +find_package(rclcpp REQUIRED) find_package(tf2_ros REQUIRED) find_package(tf2_geometry_msgs REQUIRED) @@ -34,9 +35,9 @@ target_link_libraries(${PROJECT_NAME} grid_map_core::grid_map_core ${geometry_msgs_TARGETS} ${tf2_geometry_msgs_TARGETS} - nav2_costmap_2d::nav2_costmap_2d_core tf2_ros::tf2_ros ) +ament_target_dependencies(${PROJECT_NAME} INTERFACE nav2_costmap_2d) target_include_directories(${PROJECT_NAME} INTERFACE diff --git a/grid_map_costmap_2d/test/CMakeLists.txt b/grid_map_costmap_2d/test/CMakeLists.txt index 99953741..99f19c9e 100644 --- a/grid_map_costmap_2d/test/CMakeLists.txt +++ b/grid_map_costmap_2d/test/CMakeLists.txt @@ -5,6 +5,8 @@ ament_add_gtest(${PROJECT_NAME}-test target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}::${PROJECT_NAME} + tf2_ros::tf2_ros + rclcpp::rclcpp ) ament_add_gtest(costmap-2d-ros-test