@@ -19,124 +19,127 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
19
19
add_compile_options (-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual)
20
20
endif ()
21
21
22
- find_package (ament_cmake_gtest REQUIRED)
23
- find_package (builtin_interfaces REQUIRED)
22
+ if (BUILD_TESTING)
23
+ find_package (ament_cmake_gtest REQUIRED)
24
+ find_package (builtin_interfaces REQUIRED)
24
25
# Work around broken find module in AlmaLinux/RHEL eigen3-devel from PowerTools repo
25
- find_package (Eigen3 QUIET NO_MODULE)
26
- if (NOT Eigen3_FOUND)
27
- find_package (Eigen3 REQUIRED)
28
- endif ()
29
- find_package (geometry_msgs REQUIRED)
30
- find_package (launch_testing_ament_cmake REQUIRED)
31
- find_package (rclcpp REQUIRED)
32
- find_package (tf2 REQUIRED)
33
- find_package (tf2_bullet REQUIRED)
34
- find_package (tf2_eigen REQUIRED)
35
- find_package (tf2_geometry_msgs REQUIRED)
36
- find_package (tf2_kdl REQUIRED)
37
- find_package (tf2_ros REQUIRED)
38
-
39
- ament_find_gtest()
40
-
41
- ament_add_gtest(buffer_core_test test /buffer_core_test.cpp)
42
- if (TARGET buffer_core_test)
43
- target_link_libraries (buffer_core_test
44
- ${builtin_interfaces_TARGETS}
45
- ${geometry_msgs_TARGETS}
46
- rclcpp::rclcpp
47
- tf2::tf2
48
- ${tf2_geometry_msgs_TARGETS}
49
- tf2_ros::tf2_ros)
50
- endif ()
26
+ find_package (Eigen3 QUIET NO_MODULE)
27
+ if (NOT Eigen3_FOUND)
28
+ find_package (Eigen3 REQUIRED)
29
+ endif ()
30
+ find_package (geometry_msgs REQUIRED)
31
+ find_package (launch_testing_ament_cmake REQUIRED)
32
+ find_package (rclcpp REQUIRED)
33
+ find_package (tf2 REQUIRED)
34
+ find_package (tf2_bullet REQUIRED)
35
+ find_package (tf2_eigen REQUIRED)
36
+ find_package (tf2_geometry_msgs REQUIRED)
37
+ find_package (tf2_kdl REQUIRED)
38
+ find_package (tf2_ros REQUIRED)
39
+
40
+ ament_find_gtest()
41
+
42
+ ament_add_gtest(buffer_core_test test /buffer_core_test.cpp)
43
+ if (TARGET buffer_core_test)
44
+ target_link_libraries (buffer_core_test
45
+ ${builtin_interfaces_TARGETS}
46
+ ${geometry_msgs_TARGETS}
47
+ rclcpp::rclcpp
48
+ tf2::tf2
49
+ ${tf2_geometry_msgs_TARGETS}
50
+ tf2_ros::tf2_ros)
51
+ endif ()
51
52
52
- ament_add_gtest(test_message_filter test /test_message_filter.cpp)
53
- if (TARGET test_message_filter)
54
- target_link_libraries (test_message_filter
55
- ${builtin_interfaces_TARGETS}
56
- ${geometry_msgs_TARGETS}
57
- rclcpp::rclcpp
58
- tf2::tf2
59
- tf2_ros::tf2_ros)
60
- endif ()
53
+ ament_add_gtest(test_message_filter test /test_message_filter.cpp)
54
+ if (TARGET test_message_filter)
55
+ target_link_libraries (test_message_filter
56
+ ${builtin_interfaces_TARGETS}
57
+ ${geometry_msgs_TARGETS}
58
+ rclcpp::rclcpp
59
+ tf2::tf2
60
+ tf2_ros::tf2_ros)
61
+ endif ()
61
62
62
- ament_add_gtest(test_convert test /test_convert.cpp)
63
- if (TARGET test_convert)
64
- target_link_libraries (test_convert
65
- ${geometry_msgs_TARGETS}
66
- tf2::tf2
67
- tf2_bullet::tf2_bullet
68
- tf2_eigen::tf2_eigen
69
- ${tf2_geometry_msgs_TARGETS}
70
- tf2_kdl::tf2_kdl)
71
- if (TARGET Eigen3::Eigen)
72
- # TODO(sloretz) require target to exist when https://github.com/ros2/choco-packages/issues/19 is addressed
73
- target_link_libraries (test_convert Eigen3::Eigen)
74
- else ()
75
- target_include_directories (test_convert PRIVATE ${Eigen3_INCLUDE_DIRS} )
63
+ ament_add_gtest(test_convert test /test_convert.cpp)
64
+ if (TARGET test_convert)
65
+ target_link_libraries (test_convert
66
+ ${geometry_msgs_TARGETS}
67
+ tf2::tf2
68
+ tf2_bullet::tf2_bullet
69
+ tf2_eigen::tf2_eigen
70
+ ${tf2_geometry_msgs_TARGETS}
71
+ tf2_kdl::tf2_kdl)
72
+ if (TARGET Eigen3::Eigen)
73
+ # TODO(sloretz) require target to exist when https://github.com/ros2/choco-packages/issues/19 is addressed
74
+ target_link_libraries (test_convert Eigen3::Eigen)
75
+ else ()
76
+ target_include_directories (test_convert PRIVATE ${Eigen3_INCLUDE_DIRS} )
77
+ endif ()
76
78
endif ()
77
- endif ()
78
79
79
- ament_add_gtest(test_utils test /test_utils.cpp)
80
- if (TARGET test_utils)
81
- target_link_libraries (test_utils
82
- ${geometry_msgs_TARGETS}
83
- tf2::tf2
84
- ${tf2_geometry_msgs_TARGETS}
85
- tf2_kdl::tf2_kdl)
86
- endif ()
80
+ ament_add_gtest(test_utils test /test_utils.cpp)
81
+ if (TARGET test_utils)
82
+ target_link_libraries (test_utils
83
+ ${geometry_msgs_TARGETS}
84
+ tf2::tf2
85
+ ${tf2_geometry_msgs_TARGETS}
86
+ tf2_kdl::tf2_kdl)
87
+ endif ()
87
88
88
- add_executable (test_buffer_server test /test_buffer_server.cpp)
89
- if (TARGET test_buffer_server)
90
- target_link_libraries (test_buffer_server
91
- rclcpp::rclcpp
92
- tf2_ros::tf2_ros)
93
- endif ()
89
+ add_executable (test_buffer_server test /test_buffer_server.cpp)
90
+ if (TARGET test_buffer_server)
91
+ target_link_libraries (test_buffer_server
92
+ rclcpp::rclcpp
93
+ tf2_ros::tf2_ros)
94
+ endif ()
94
95
95
- add_executable (test_buffer_client test /test_buffer_client.cpp)
96
- if (TARGET test_buffer_client)
97
- target_link_libraries (test_buffer_client
98
- ${GTEST_LIBRARIES}
99
- rclcpp::rclcpp
100
- tf2_bullet::tf2_bullet
101
- ${tf2_geometry_msgs_TARGETS}
102
- tf2_kdl::tf2_kdl
103
- tf2_ros::tf2_ros)
104
- add_launch_test(test /buffer_client_tester.launch.py)
105
- endif ()
96
+ add_executable (test_buffer_client test /test_buffer_client.cpp)
97
+ if (TARGET test_buffer_client)
98
+ target_link_libraries (test_buffer_client
99
+ ${GTEST_LIBRARIES}
100
+ rclcpp::rclcpp
101
+ tf2_bullet::tf2_bullet
102
+ ${tf2_geometry_msgs_TARGETS}
103
+ tf2_kdl::tf2_kdl
104
+ tf2_ros::tf2_ros)
105
+ add_launch_test(test /buffer_client_tester.launch.py)
106
+ endif ()
106
107
107
- add_executable (test_static_publisher test /test_static_publisher.cpp)
108
- if (TARGET test_static_publisher)
109
- target_link_libraries (test_static_publisher
110
- ${GTEST_LIBRARIES}
111
- ${geometry_msgs_TARGETS}
112
- rclcpp::rclcpp
113
- tf2::tf2
114
- tf2_ros::tf2_ros)
115
- add_launch_test(test /static_publisher.launch.py)
116
- endif ()
108
+ add_executable (test_static_publisher test /test_static_publisher.cpp)
109
+ if (TARGET test_static_publisher)
110
+ target_link_libraries (test_static_publisher
111
+ ${GTEST_LIBRARIES}
112
+ ${geometry_msgs_TARGETS}
113
+ rclcpp::rclcpp
114
+ tf2::tf2
115
+ tf2_ros::tf2_ros)
116
+ add_launch_test(test /static_publisher.launch.py)
117
+ endif ()
117
118
118
- ament_add_gtest(test_tf2_bullet test /test_tf2_bullet.cpp)
119
- if (TARGET test_tf2_bullet)
120
- target_link_libraries (test_tf2_bullet
121
- rclcpp::rclcpp
122
- tf2_bullet::tf2_bullet
123
- tf2_ros::tf2_ros
124
- tf2::tf2)
125
- endif ()
119
+ ament_add_gtest(test_tf2_bullet test /test_tf2_bullet.cpp)
120
+ if (TARGET test_tf2_bullet)
121
+ target_link_libraries (test_tf2_bullet
122
+ rclcpp::rclcpp
123
+ tf2_bullet::tf2_bullet
124
+ tf2_ros::tf2_ros
125
+ tf2::tf2)
126
+ endif ()
126
127
127
128
# TODO(ahcorde): enable once python part of tf2_geometry_msgs is working
128
129
# add_launch_test(test/test_buffer_client.launch.py)
129
130
130
131
# install executables
131
- install (TARGETS
132
- test_buffer_client
133
- test_buffer_server
134
- test_static_publisher
135
- DESTINATION lib/${PROJECT_NAME}
136
- )
137
- install (PROGRAMS
138
- test /test_buffer_client.py
139
- DESTINATION lib/${PROJECT_NAME}
140
- )
132
+ install (TARGETS
133
+ test_buffer_client
134
+ test_buffer_server
135
+ test_static_publisher
136
+ DESTINATION lib/${PROJECT_NAME}
137
+ )
138
+ install (PROGRAMS
139
+ test /test_buffer_client.py
140
+ DESTINATION lib/${PROJECT_NAME}
141
+ )
142
+
143
+ endif ()
141
144
142
145
ament_package()
0 commit comments