Skip to content

Commit 2ccffbb

Browse files
authored
Make sure to ament_target_dependencies on rclcpp_components (#209)
Signed-off-by: Chris Lalancette <[email protected]>
1 parent 51cf601 commit 2ccffbb

File tree

1 file changed

+1
-2
lines changed

1 file changed

+1
-2
lines changed

spacenav/CMakeLists.txt

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ find_package(rclcpp_components REQUIRED)
1818
find_package(sensor_msgs REQUIRED)
1919
find_package(SPNAV REQUIRED)
2020

21-
include_directories(include)
2221
add_library(spacenav
2322
SHARED
2423
src/spacenav.cpp)
@@ -29,6 +28,7 @@ target_include_directories(spacenav
2928
ament_target_dependencies(spacenav
3029
"geometry_msgs"
3130
"rclcpp"
31+
"rclcpp_components"
3232
"sensor_msgs")
3333

3434
target_link_libraries(spacenav spnav)
@@ -55,5 +55,4 @@ if(BUILD_TESTING)
5555
ament_lint_auto_find_test_dependencies()
5656
endif()
5757

58-
5958
ament_package()

0 commit comments

Comments
 (0)