Skip to content

Commit 34b6689

Browse files
committed
Fix missing dependencies
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
1 parent e3fad51 commit 34b6689

File tree

2 files changed

+4
-1
lines changed

2 files changed

+4
-1
lines changed

grid_map_costmap_2d/CMakeLists.txt

+2-1
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ find_package(grid_map_cmake_helpers REQUIRED)
77
find_package(grid_map_core REQUIRED)
88
find_package(geometry_msgs REQUIRED)
99
find_package(nav2_costmap_2d REQUIRED)
10+
find_package(rclcpp REQUIRED)
1011
find_package(tf2_ros REQUIRED)
1112
find_package(tf2_geometry_msgs REQUIRED)
1213

@@ -34,8 +35,8 @@ target_link_libraries(${PROJECT_NAME}
3435
grid_map_core::grid_map_core
3536
${geometry_msgs_TARGETS}
3637
${tf2_geometry_msgs_TARGETS}
37-
nav2_costmap_2d::nav2_costmap_2d_core
3838
tf2_ros::tf2_ros
39+
nav2_costmap_2d::nav2_costmap_2d_core
3940
)
4041

4142
target_include_directories(${PROJECT_NAME}

grid_map_costmap_2d/test/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,8 @@ ament_add_gtest(${PROJECT_NAME}-test
55

66
target_link_libraries(${PROJECT_NAME}-test
77
${PROJECT_NAME}::${PROJECT_NAME}
8+
tf2_ros::tf2_ros
9+
rclcpp::rclcpp
810
)
911

1012
ament_add_gtest(costmap-2d-ros-test

0 commit comments

Comments
 (0)