Skip to content

Commit

Permalink
Remove the last use of ament_target_dependencies. (#264)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Sep 14, 2023
1 parent e086fb6 commit be48a0d
Showing 1 changed file with 6 additions and 5 deletions.
11 changes: 6 additions & 5 deletions joy_linux/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,12 @@ if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux")
if(HAVE_LINUX_JOYSTICK_H)
include_directories(msg/cpp ${catkin_INCLUDE_DIRS})
add_executable(joy_linux_node src/joy_linux_node.cpp)
ament_target_dependencies(joy_linux_node
"diagnostic_msgs"
"diagnostic_updater"
"rclcpp"
"sensor_msgs")
target_link_libraries(joy_linux_node PRIVATE
${diagnostic_msgs_TARGETS}
diagnostic_updater::diagnostic_updater
rclcpp::rclcpp
${sensor_msgs_TARGETS}
)
install(TARGETS joy_linux_node DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
Expand Down

0 comments on commit be48a0d

Please sign in to comment.