Skip to content

Commit a55155a

Browse files
Use target_link_libraries instead of ament_target_dependencies (#815)
1 parent 87d464a commit a55155a

File tree

17 files changed

+88
-55
lines changed

17 files changed

+88
-55
lines changed

example_1/CMakeLists.txt

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,11 @@ target_include_directories(ros2_control_demo_example_1 PUBLIC
3939
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4040
$<INSTALL_INTERFACE:include/ros2_control_demo_example_1>
4141
)
42-
ament_target_dependencies(
43-
ros2_control_demo_example_1 PUBLIC
44-
${THIS_PACKAGE_INCLUDE_DEPENDS}
42+
target_link_libraries(ros2_control_demo_example_1 PUBLIC
43+
hardware_interface::hardware_interface
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_lifecycle::rclcpp_lifecycle
4547
)
4648

4749
# Export hardware plugins

example_10/CMakeLists.txt

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,6 @@ export_windows_symbols()
88
# find dependencies
99
set(THIS_PACKAGE_INCLUDE_DEPENDS
1010
hardware_interface
11-
control_msgs
12-
std_msgs
1311
pluginlib
1412
rclcpp
1513
rclcpp_lifecycle
@@ -41,9 +39,11 @@ target_include_directories(ros2_control_demo_example_10 PUBLIC
4139
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4240
$<INSTALL_INTERFACE:include/ros2_control_demo_example_10>
4341
)
44-
ament_target_dependencies(
45-
ros2_control_demo_example_10 PUBLIC
46-
${THIS_PACKAGE_INCLUDE_DEPENDS}
42+
target_link_libraries(ros2_control_demo_example_10 PUBLIC
43+
hardware_interface::hardware_interface
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_lifecycle::rclcpp_lifecycle
4747
)
4848

4949
# Export hardware plugins

example_11/CMakeLists.txt

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,11 @@ target_include_directories(ros2_control_demo_example_11 PUBLIC
3939
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4040
$<INSTALL_INTERFACE:include/ros2_control_demo_example_11>
4141
)
42-
ament_target_dependencies(
43-
ros2_control_demo_example_11 PUBLIC
44-
${THIS_PACKAGE_INCLUDE_DEPENDS}
42+
target_link_libraries(ros2_control_demo_example_11 PUBLIC
43+
hardware_interface::hardware_interface
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_lifecycle::rclcpp_lifecycle
4547
)
4648

4749
# Export hardware plugins

example_12/CMakeLists.txt

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1111
pluginlib
1212
rclcpp
1313
rclcpp_lifecycle
14-
control_msgs
1514
generate_parameter_library
1615
controller_interface
1716
parameter_traits
@@ -45,9 +44,11 @@ target_include_directories(ros2_control_demo_example_12 PUBLIC
4544
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4645
$<INSTALL_INTERFACE:include/ros2_control_demo_example_12>
4746
)
48-
ament_target_dependencies(
49-
ros2_control_demo_example_12 PUBLIC
50-
${THIS_PACKAGE_INCLUDE_DEPENDS}
47+
target_link_libraries(ros2_control_demo_example_12 PUBLIC
48+
hardware_interface::hardware_interface
49+
pluginlib::pluginlib
50+
rclcpp::rclcpp
51+
rclcpp_lifecycle::rclcpp_lifecycle
5152
)
5253

5354
# Export hardware plugins
@@ -65,9 +66,15 @@ target_include_directories(passthrough_controller PUBLIC
6566
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/controllers/include>
6667
$<INSTALL_INTERFACE:include/passthrough_controller>
6768
)
68-
target_link_libraries(passthrough_controller PUBLIC passthrough_controller_parameters)
69-
ament_target_dependencies(passthrough_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
70-
69+
target_link_libraries(passthrough_controller PUBLIC
70+
passthrough_controller_parameters
71+
${std_msgs_TARGETS}
72+
controller_interface::controller_interface
73+
pluginlib::pluginlib
74+
rclcpp::rclcpp
75+
rclcpp_lifecycle::rclcpp_lifecycle
76+
realtime_tools::realtime_tools
77+
)
7178
pluginlib_export_plugin_description_file(controller_interface passthrough_controller.xml)
7279

7380

example_12/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<depend>pluginlib</depend>
2424
<depend>rclcpp</depend>
2525
<depend>rclcpp_lifecycle</depend>
26+
<depend>std_msgs</depend>
2627

2728
<exec_depend>controller_manager</exec_depend>
2829
<exec_depend>forward_command_controller</exec_depend>

example_14/CMakeLists.txt

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -41,9 +41,12 @@ target_include_directories(ros2_control_demo_example_14 PUBLIC
4141
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4242
$<INSTALL_INTERFACE:include/ros2_control_demo_example_14>
4343
)
44-
ament_target_dependencies(
45-
ros2_control_demo_example_14 PUBLIC
46-
${THIS_PACKAGE_INCLUDE_DEPENDS}
44+
target_link_libraries(ros2_control_demo_example_14 PUBLIC
45+
hardware_interface::hardware_interface
46+
pluginlib::pluginlib
47+
rclcpp::rclcpp
48+
rclcpp_lifecycle::rclcpp_lifecycle
49+
realtime_tools::realtime_tools
4750
)
4851

4952
# Export hardware plugins

example_16/CMakeLists.txt

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,11 @@ target_include_directories(ros2_control_demo_example_16 PUBLIC
3939
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4040
$<INSTALL_INTERFACE:include/ros2_control_demo_example_16>
4141
)
42-
ament_target_dependencies(
43-
ros2_control_demo_example_16 PUBLIC
44-
${THIS_PACKAGE_INCLUDE_DEPENDS}
42+
target_link_libraries(ros2_control_demo_example_16 PUBLIC
43+
hardware_interface::hardware_interface
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_lifecycle::rclcpp_lifecycle
4547
)
4648

4749
# Export hardware plugins

example_2/CMakeLists.txt

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,11 @@ target_include_directories(ros2_control_demo_example_2 PUBLIC
3939
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4040
$<INSTALL_INTERFACE:include/ros2_control_demo_example_2>
4141
)
42-
ament_target_dependencies(
43-
ros2_control_demo_example_2 PUBLIC
44-
${THIS_PACKAGE_INCLUDE_DEPENDS}
42+
target_link_libraries(ros2_control_demo_example_2 PUBLIC
43+
hardware_interface::hardware_interface
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_lifecycle::rclcpp_lifecycle
4547
)
4648

4749
# Export hardware plugins

example_3/CMakeLists.txt

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,11 @@ target_include_directories(ros2_control_demo_example_3 PUBLIC
3939
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4040
$<INSTALL_INTERFACE:include/ros2_control_demo_example_3>
4141
)
42-
ament_target_dependencies(
43-
ros2_control_demo_example_3 PUBLIC
44-
${THIS_PACKAGE_INCLUDE_DEPENDS}
42+
target_link_libraries(ros2_control_demo_example_3 PUBLIC
43+
hardware_interface::hardware_interface
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_lifecycle::rclcpp_lifecycle
4547
)
4648

4749
# Export hardware plugins

example_4/CMakeLists.txt

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,11 @@ target_include_directories(ros2_control_demo_example_4 PUBLIC
3939
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
4040
$<INSTALL_INTERFACE:include/ros2_control_demo_example_4>
4141
)
42-
ament_target_dependencies(
43-
ros2_control_demo_example_4 PUBLIC
44-
${THIS_PACKAGE_INCLUDE_DEPENDS}
42+
target_link_libraries(ros2_control_demo_example_4 PUBLIC
43+
hardware_interface::hardware_interface
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_lifecycle::rclcpp_lifecycle
4547
)
4648

4749
# Export hardware plugins

0 commit comments

Comments
 (0)