File tree Expand file tree Collapse file tree 3 files changed +18
-16
lines changed
diagnostic_remote_logging Expand file tree Collapse file tree 3 files changed +18
-16
lines changed Original file line number Diff line number Diff line change @@ -50,7 +50,12 @@ if(BUILD_TESTING)
5050 find_package (ament_cmake_gtest REQUIRED)
5151 ament_add_gtest(unit_tests test /influx_line_protocol.cpp)
5252 target_include_directories (unit_tests PRIVATE include )
53- target_link_libraries (unit_tests influx_component)
54- ament_target_dependencies(unit_tests ${dependencies} ament_cmake_gtest)
53+ target_link_libraries (unit_tests
54+ influx_component
55+ ${diagnostic_msgs_TARGETS}
56+ rclcpp::rclcpp
57+ rclcpp_components::component
58+ rclcpp_components::component_manager
59+ )
5560endif ()
5661ament_package()
Original file line number Diff line number Diff line change @@ -68,9 +68,8 @@ if(BUILD_TESTING)
6868 $<INSTALL_INTERFACE:include >
6969 )
7070 target_link_libraries (diagnostic_updater_test ${PROJECT_NAME} )
71- ament_target_dependencies(
72- diagnostic_updater_test
73- "rclcpp_lifecycle"
71+ target_link_libraries (diagnostic_updater_test
72+ rclcpp_lifecycle::rclcpp_lifecycle
7473 )
7574
7675 ament_add_gtest(diagnostic_status_wrapper_test test /diagnostic_status_wrapper_test.cpp)
@@ -79,12 +78,11 @@ if(BUILD_TESTING)
7978 $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include >
8079 $<INSTALL_INTERFACE:include >
8180 )
82- ament_target_dependencies(
83- diagnostic_status_wrapper_test
84- "diagnostic_msgs"
85- "rclcpp"
86- "rclcpp_lifecycle"
87- "std_msgs"
81+ target_link_libraries (diagnostic_status_wrapper_test
82+ ${diagnostic_msgs_TARGETS}
83+ ${std_msgs_TARGETS}
84+ rclcpp::rclcpp
85+ rclcpp_lifecycle::rclcpp_lifecycle
8886 )
8987 # SKIPPING FLAKY TEST
9088 # ament_add_gtest(status_msg_test test/status_msg_test.cpp)
Original file line number Diff line number Diff line change @@ -3,11 +3,10 @@ find_package(ament_cmake_gtest REQUIRED)
33macro (add_self_test target_name file_path)
44 ament_add_gtest(${target_name} ${file_path} )
55 if (TARGET ${target_name} )
6- ament_target_dependencies(
7- ${target_name}
8- "diagnostic_msgs"
9- "diagnostic_updater"
10- "rclcpp"
6+ target_link_libraries (${target_name}
7+ ${diagnostic_msgs_TARGETS}
8+ diagnostic_updater::diagnostic_updater
9+ rclcpp::rclcpp
1110 )
1211 target_include_directories (${target_name}
1312 PUBLIC
You can’t perform that action at this time.
0 commit comments