diff --git a/grid_map_costmap_2d/CMakeLists.txt b/grid_map_costmap_2d/CMakeLists.txt index 201c8760..0f37c4a0 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) 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