diff --git a/diagnostic_remote_logging/CMakeLists.txt b/diagnostic_remote_logging/CMakeLists.txt index 70a50048..a0bdc00e 100644 --- a/diagnostic_remote_logging/CMakeLists.txt +++ b/diagnostic_remote_logging/CMakeLists.txt @@ -50,7 +50,12 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(unit_tests test/influx_line_protocol.cpp) target_include_directories(unit_tests PRIVATE include) - target_link_libraries(unit_tests influx_component) - ament_target_dependencies(unit_tests ${dependencies} ament_cmake_gtest) + target_link_libraries(unit_tests + influx_component + ${diagnostic_msgs_TARGETS} + rclcpp::rclcpp + rclcpp_components::component + rclcpp_components::component_manager + ) endif() ament_package() diff --git a/diagnostic_updater/CMakeLists.txt b/diagnostic_updater/CMakeLists.txt index 8c8861ed..19105f6f 100644 --- a/diagnostic_updater/CMakeLists.txt +++ b/diagnostic_updater/CMakeLists.txt @@ -68,9 +68,8 @@ if(BUILD_TESTING) $ ) target_link_libraries(diagnostic_updater_test ${PROJECT_NAME}) - ament_target_dependencies( - diagnostic_updater_test - "rclcpp_lifecycle" + target_link_libraries(diagnostic_updater_test + rclcpp_lifecycle::rclcpp_lifecycle ) ament_add_gtest(diagnostic_status_wrapper_test test/diagnostic_status_wrapper_test.cpp) @@ -79,12 +78,11 @@ if(BUILD_TESTING) $ $ ) - ament_target_dependencies( - diagnostic_status_wrapper_test - "diagnostic_msgs" - "rclcpp" - "rclcpp_lifecycle" - "std_msgs" + target_link_libraries(diagnostic_status_wrapper_test + ${diagnostic_msgs_TARGETS} + ${std_msgs_TARGETS} + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle ) # SKIPPING FLAKY TEST # ament_add_gtest(status_msg_test test/status_msg_test.cpp) diff --git a/self_test/test/CMakeLists.txt b/self_test/test/CMakeLists.txt index baf11fa4..a81746b6 100644 --- a/self_test/test/CMakeLists.txt +++ b/self_test/test/CMakeLists.txt @@ -3,11 +3,10 @@ find_package(ament_cmake_gtest REQUIRED) macro(add_self_test target_name file_path) ament_add_gtest(${target_name} ${file_path}) if(TARGET ${target_name}) - ament_target_dependencies( - ${target_name} - "diagnostic_msgs" - "diagnostic_updater" - "rclcpp" + target_link_libraries(${target_name} + ${diagnostic_msgs_TARGETS} + diagnostic_updater::diagnostic_updater + rclcpp::rclcpp ) target_include_directories(${target_name} PUBLIC