@@ -40,9 +40,23 @@ target_compile_features(hardware_interface PUBLIC cxx_std_17)
4040target_include_directories (hardware_interface PUBLIC
4141 $<BUILD_INTERFACE:${PROJECT_SOURCE_DIR} /include >
4242 $<INSTALL_INTERFACE:include /hardware_interface>
43+ ${pal_statistics_INCLUDE_DIRS}
4344)
44- target_link_libraries (hardware_interface PUBLIC fmt::fmt)
45- ament_target_dependencies(hardware_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS} )
45+ target_link_libraries (hardware_interface PUBLIC
46+ rclcpp::rclcpp
47+ rclcpp_lifecycle::rclcpp_lifecycle
48+ pluginlib::pluginlib
49+ urdf::urdf
50+ realtime_tools::realtime_tools
51+ rcutils::rcutils
52+ rcpputils::rcpputils
53+ ${joint_limits_TARGETS}
54+ ${TinyXML2_LIBRARIES}
55+ ${tinyxml2_vendor_LIBRARIES}
56+ ${pal_statistics_LIBRARIES}
57+ ${control_msgs_TARGETS}
58+ ${lifecycle_msgs_TARGETS}
59+ fmt::fmt)
4660
4761add_library (mock_components SHARED
4862 src/mock_components/generic_system.cpp
@@ -53,7 +67,6 @@ target_include_directories(mock_components PUBLIC
5367 $<INSTALL_INTERFACE:include /hardware_interface>
5468)
5569target_link_libraries (mock_components PUBLIC hardware_interface)
56- ament_target_dependencies(mock_components PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS} )
5770
5871pluginlib_export_plugin_description_file(
5972 hardware_interface mock_components_plugin_description.xml)
@@ -65,31 +78,26 @@ if(BUILD_TESTING)
6578
6679 ament_add_gmock(test_macros test /test_macros.cpp)
6780 target_include_directories (test_macros PRIVATE include )
68- ament_target_dependencies (test_macros rcpputils)
81+ target_link_libraries (test_macros rcpputils:: rcpputils)
6982
7083 ament_add_gmock(test_inst_hardwares test /test_inst_hardwares.cpp)
71- target_link_libraries (test_inst_hardwares hardware_interface)
72- ament_target_dependencies(test_inst_hardwares rcpputils)
84+ target_link_libraries (test_inst_hardwares hardware_interface rcpputils::rcpputils)
7385
7486 ament_add_gmock(test_joint_handle test /test_handle.cpp)
75- target_link_libraries (test_joint_handle hardware_interface)
76- ament_target_dependencies(test_joint_handle rcpputils)
87+ target_link_libraries (test_joint_handle hardware_interface rcpputils::rcpputils)
7788
7889 # Test helper methods
7990 ament_add_gmock(test_helpers test /test_helpers.cpp)
8091 target_link_libraries (test_helpers hardware_interface)
8192
8293 ament_add_gmock(test_component_interfaces test /test_component_interfaces.cpp)
83- target_link_libraries (test_component_interfaces hardware_interface)
84- ament_target_dependencies(test_component_interfaces ros2_control_test_assets)
94+ target_link_libraries (test_component_interfaces hardware_interface ros2_control_test_assets::ros2_control_test_assets)
8595
8696 ament_add_gmock(test_component_interfaces_custom_export test /test_component_interfaces_custom_export.cpp)
87- target_link_libraries (test_component_interfaces_custom_export hardware_interface)
88- ament_target_dependencies(test_component_interfaces_custom_export ros2_control_test_assets)
97+ target_link_libraries (test_component_interfaces_custom_export hardware_interface ros2_control_test_assets::ros2_control_test_assets)
8998
9099 ament_add_gmock(test_component_parser test /test_component_parser.cpp)
91- target_link_libraries (test_component_parser hardware_interface)
92- ament_target_dependencies(test_component_parser ros2_control_test_assets)
100+ target_link_libraries (test_component_parser hardware_interface ros2_control_test_assets::ros2_control_test_assets)
93101
94102 add_library (test_hardware_components SHARED
95103 test /test_hardware_components/test_single_joint_actuator.cpp
@@ -99,8 +107,6 @@ if(BUILD_TESTING)
99107 test /test_hardware_components/test_system_with_command_modes.cpp
100108 )
101109 target_link_libraries (test_hardware_components hardware_interface)
102- ament_target_dependencies(test_hardware_components
103- pluginlib)
104110 install (TARGETS test_hardware_components
105111 DESTINATION lib
106112 )
@@ -110,11 +116,7 @@ if(BUILD_TESTING)
110116
111117 ament_add_gmock(test_generic_system test /mock_components/test_generic_system.cpp)
112118 target_include_directories (test_generic_system PRIVATE include )
113- target_link_libraries (test_generic_system hardware_interface)
114- ament_target_dependencies(test_generic_system
115- pluginlib
116- ros2_control_test_assets
117- )
119+ target_link_libraries (test_generic_system hardware_interface ros2_control_test_assets::ros2_control_test_assets)
118120endif ()
119121
120122install (
0 commit comments