Skip to content

Commit d09a5ea

Browse files
authored
Remove ament_target_dependencies. (#209)
Just use target_link_libraries as appropriate. This allows us to reduce the number of dependencies we export to downstream projects. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 9a50d78 commit d09a5ea

File tree

1 file changed

+29
-36
lines changed

1 file changed

+29
-36
lines changed

CMakeLists.txt

+29-36
Original file line numberDiff line numberDiff line change
@@ -24,26 +24,27 @@ find_package(std_msgs REQUIRED)
2424
find_package(tf2_ros REQUIRED)
2525
find_package(urdf REQUIRED)
2626

27-
set(THIS_PACKAGE_INCLUDE_DEPENDS
28-
builtin_interfaces
29-
geometry_msgs
30-
kdl_parser
31-
orocos_kdl
32-
rcl_interfaces
33-
rclcpp
34-
rclcpp_components
35-
sensor_msgs
36-
std_msgs
37-
tf2_ros
38-
urdf)
39-
4027
add_library(
4128
${PROJECT_NAME}_node SHARED
4229
src/robot_state_publisher.cpp)
4330
target_include_directories(${PROJECT_NAME}_node PUBLIC
4431
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
4532
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
46-
ament_target_dependencies(${PROJECT_NAME}_node ${THIS_PACKAGE_INCLUDE_DEPENDS})
33+
target_link_libraries(${PROJECT_NAME}_node PUBLIC
34+
${builtin_interfaces_TARGETS}
35+
orocos-kdl
36+
${rcl_interfaces_TARGETS}
37+
rclcpp::rclcpp
38+
${sensor_msgs_TARGETS}
39+
${std_msgs_TARGETS}
40+
tf2_ros::tf2_ros
41+
urdf::urdf
42+
)
43+
target_link_libraries(${PROJECT_NAME}_node PRIVATE
44+
${geometry_msgs_TARGETS}
45+
kdl_parser::kdl_parser
46+
rclcpp_components::component
47+
)
4748
ament_export_targets(export_${PROJECT_NAME}_node)
4849

4950
rclcpp_components_register_node(${PROJECT_NAME}_node
@@ -75,46 +76,38 @@ if(BUILD_TESTING)
7576
ament_find_gtest()
7677

7778
add_executable(test_two_links_fixed_joint test/test_two_links_fixed_joint.cpp)
78-
ament_target_dependencies(test_two_links_fixed_joint
79-
rclcpp
80-
tf2_ros
81-
)
8279
target_include_directories(test_two_links_fixed_joint PRIVATE ${GTEST_INCLUDE_DIRS})
83-
target_link_libraries(test_two_links_fixed_joint ${GTEST_LIBRARIES})
80+
target_link_libraries(test_two_links_fixed_joint PRIVATE ${GTEST_LIBRARIES} rclcpp::rclcpp tf2_ros::tf2_ros)
8481
add_launch_test(test/two_links_fixed_joint-launch.py
8582
ARGS "test_exe:=$<TARGET_FILE:test_two_links_fixed_joint>")
8683

8784
add_executable(test_two_links_fixed_joint_prefix test/test_two_links_fixed_joint_prefix.cpp)
88-
ament_target_dependencies(test_two_links_fixed_joint_prefix
89-
rclcpp
90-
tf2_ros
91-
)
9285
target_include_directories(test_two_links_fixed_joint PRIVATE ${GTEST_INCLUDE_DIRS})
93-
target_link_libraries(test_two_links_fixed_joint_prefix ${GTEST_LIBRARIES})
86+
target_link_libraries(test_two_links_fixed_joint_prefix PRIVATE ${GTEST_LIBRARIES} rclcpp::rclcpp tf2_ros::tf2_ros)
9487
add_launch_test(test/two_links_fixed_joint_prefix-launch.py
9588
ARGS "test_exe:=$<TARGET_FILE:test_two_links_fixed_joint_prefix>")
9689

9790
add_executable(test_two_links_moving_joint test/test_two_links_moving_joint.cpp)
98-
ament_target_dependencies(test_two_links_moving_joint
99-
rclcpp
100-
sensor_msgs
101-
tf2_ros
102-
)
10391
target_include_directories(test_two_links_fixed_joint PRIVATE ${GTEST_INCLUDE_DIRS})
104-
target_link_libraries(test_two_links_moving_joint ${GTEST_LIBRARIES})
92+
target_link_libraries(test_two_links_moving_joint PRIVATE ${GTEST_LIBRARIES} rclcpp::rclcpp ${sensor_msgs_TARGETS} tf2_ros::tf2_ros)
10593
add_launch_test(test/two_links_moving_joint-launch.py
10694
ARGS "test_exe:=$<TARGET_FILE:test_two_links_moving_joint>")
10795

10896
add_executable(test_two_links_change_fixed_joint test/test_two_links_change_fixed_joint.cpp)
109-
ament_target_dependencies(test_two_links_change_fixed_joint
110-
rclcpp
111-
tf2_ros
112-
)
11397
target_include_directories(test_two_links_change_fixed_joint PRIVATE ${GTEST_INCLUDE_DIRS})
114-
target_link_libraries(test_two_links_change_fixed_joint ${GTEST_LIBRARIES})
98+
target_link_libraries(test_two_links_change_fixed_joint PRIVATE ${GTEST_LIBRARIES} rclcpp::rclcpp tf2_ros::tf2_ros)
11599
add_launch_test(test/two_links_change_fixed_joint-launch.py
116100
ARGS "test_exe:=$<TARGET_FILE:test_two_links_change_fixed_joint>")
117101
endif()
118102

119-
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
103+
ament_export_dependencies(
104+
builtin_interfaces
105+
orocos_kdl
106+
rcl_interfaces
107+
rclcpp
108+
sensor_msgs
109+
std_msgs
110+
tf2_ros
111+
urdf
112+
)
120113
ament_package()

0 commit comments

Comments
 (0)