@@ -24,26 +24,27 @@ find_package(std_msgs REQUIRED)
24
24
find_package (tf2_ros REQUIRED)
25
25
find_package (urdf REQUIRED)
26
26
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
-
40
27
add_library (
41
28
${PROJECT_NAME} _node SHARED
42
29
src/robot_state_publisher.cpp)
43
30
target_include_directories (${PROJECT_NAME} _node PUBLIC
44
31
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include>"
45
32
"$<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
+ )
47
48
ament_export_targets(export_${PROJECT_NAME} _node)
48
49
49
50
rclcpp_components_register_node(${PROJECT_NAME} _node
@@ -75,46 +76,38 @@ if(BUILD_TESTING)
75
76
ament_find_gtest()
76
77
77
78
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
- )
82
79
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 )
84
81
add_launch_test(test /two_links_fixed_joint-launch.py
85
82
ARGS "test_exe:=$<TARGET_FILE:test_two_links_fixed_joint>" )
86
83
87
84
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
- )
92
85
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 )
94
87
add_launch_test(test /two_links_fixed_joint_prefix-launch.py
95
88
ARGS "test_exe:=$<TARGET_FILE:test_two_links_fixed_joint_prefix>" )
96
89
97
90
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
- )
103
91
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 )
105
93
add_launch_test(test /two_links_moving_joint-launch.py
106
94
ARGS "test_exe:=$<TARGET_FILE:test_two_links_moving_joint>" )
107
95
108
96
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
- )
113
97
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 )
115
99
add_launch_test(test /two_links_change_fixed_joint-launch.py
116
100
ARGS "test_exe:=$<TARGET_FILE:test_two_links_change_fixed_joint>" )
117
101
endif ()
118
102
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
+ )
120
113
ament_package()
0 commit comments