Skip to content

Commit 64522c7

Browse files
authored
Remove ament target deps for the new game_controller node. (#272)
Just use standard target_link_libraries, which allows us to hide some of the dependencies from downstream. Signed-off-by: Chris Lalancette <[email protected]>
1 parent b0bc9d7 commit 64522c7

File tree

1 file changed

+6
-11
lines changed

1 file changed

+6
-11
lines changed

joy/CMakeLists.txt

Lines changed: 6 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -27,13 +27,11 @@ target_link_libraries(joy PUBLIC
2727
SDL2::SDL2)
2828
target_link_libraries(joy PRIVATE
2929
rclcpp_components::component)
30-
3130
install(TARGETS joy EXPORT export_joy
3231
LIBRARY DESTINATION lib
3332
ARCHIVE DESTINATION lib
3433
RUNTIME DESTINATION bin
3534
)
36-
3735
rclcpp_components_register_node(joy
3836
PLUGIN "joy::Joy"
3937
EXECUTABLE joy_node)
@@ -42,28 +40,25 @@ add_library(game_controller SHARED src/game_controller.cpp)
4240
target_include_directories(game_controller PUBLIC
4341
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
4442
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
45-
ament_target_dependencies(game_controller
46-
rclcpp
47-
rclcpp_components
48-
sensor_msgs)
49-
target_link_libraries(game_controller
43+
target_link_libraries(game_controller PUBLIC
44+
rclcpp::rclcpp
45+
${sensor_msgs_TARGETS}
5046
SDL2::SDL2)
51-
47+
target_link_libraries(game_controller PRIVATE
48+
rclcpp_components::component)
5249
install(TARGETS game_controller EXPORT export_game_controller
5350
LIBRARY DESTINATION lib
5451
ARCHIVE DESTINATION lib
5552
RUNTIME DESTINATION bin
5653
)
57-
5854
rclcpp_components_register_node(game_controller
5955
PLUGIN "joy::GameController"
6056
EXECUTABLE game_controller_node)
6157

6258
add_executable(joy_enumerate_devices
6359
src/joy_enumerate_devices.cpp)
64-
target_link_libraries(joy_enumerate_devices
60+
target_link_libraries(joy_enumerate_devices PRIVATE
6561
SDL2::SDL2)
66-
6762
install(TARGETS joy_enumerate_devices
6863
DESTINATION lib/${PROJECT_NAME})
6964

0 commit comments

Comments
 (0)