From 2144c027383ff7c08c88c47aadaefcc701490d7c Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Thu, 15 Feb 2024 08:38:51 -0500 Subject: [PATCH] Revamp test_rclcpp to compile far few files. (#535) Instead of recompiling the tests multiple times for each RMW, instead just compile it once and use the RMW_IMPLEMENTATION environment variable to control which RMW gets used. On my machine, this sped up compilation by about 2x, and should reduce the number of times our coverage jobs fail because they run out of memory. Signed-off-by: Chris Lalancette --- test_rclcpp/CMakeLists.txt | 379 ++++++++++++------ test_rclcpp/test/node_check_names.cpp | 1 + ...st_avoid_ros_namespace_conventions_qos.cpp | 16 +- test_rclcpp/test/test_client_scope_client.cpp | 12 +- .../test_client_scope_consistency_client.cpp | 15 +- .../test_client_wait_for_service_shutdown.cpp | 12 +- test_rclcpp/test/test_executor.cpp | 24 +- test_rclcpp/test/test_intra_process.cpp | 13 +- test_rclcpp/test/test_local_parameters.cpp | 41 +- .../test/test_multiple_service_calls.cpp | 20 +- test_rclcpp/test/test_multithreaded.cpp | 24 +- test_rclcpp/test/test_publisher.cpp | 12 +- test_rclcpp/test/test_remote_parameters.cpp | 30 +- .../test_repeated_publisher_subscriber.cpp | 15 +- test_rclcpp/test/test_services_client.cpp | 24 +- .../test/test_services_in_constructor.cpp | 15 +- test_rclcpp/test/test_services_server.cpp | 2 + test_rclcpp/test/test_sigint_handler.cpp | 4 +- test_rclcpp/test/test_sigterm_handler.cpp | 4 +- test_rclcpp/test/test_spin.cpp | 24 +- test_rclcpp/test/test_subscription.cpp | 37 +- test_rclcpp/test/test_timeout_subscriber.cpp | 12 +- test_rclcpp/test/test_timer.cpp | 18 +- test_rclcpp/test/test_waitable.cpp | 13 +- 24 files changed, 396 insertions(+), 371 deletions(-) diff --git a/test_rclcpp/CMakeLists.txt b/test_rclcpp/CMakeLists.txt index 97388b7b..0b051310 100644 --- a/test_rclcpp/CMakeLists.txt +++ b/test_rclcpp/CMakeLists.txt @@ -15,12 +15,19 @@ find_package(ament_cmake REQUIRED) if(BUILD_TESTING) find_package(rclcpp REQUIRED) + find_package(rcpputils REQUIRED) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() find_package(launch_testing_ament_cmake REQUIRED) + find_package(ament_cmake_gtest REQUIRED) + + # finding gtest once in the highest scope + # prevents finding it repeatedly in each local scope + ament_find_gtest() + set(message_files "msg/UInt32.msg" ) @@ -35,42 +42,116 @@ if(BUILD_TESTING) SKIP_INSTALL ) - # get the rmw implementations ahead of time - find_package(rmw_implementation_cmake REQUIRED) - get_available_rmw_implementations(rmw_implementations) - foreach(rmw_implementation ${rmw_implementations}) - find_package("${rmw_implementation}" REQUIRED) - endforeach() - rosidl_get_typesupport_target(cpp_typesupport_target "${PROJECT_NAME}" "rosidl_typesupport_cpp") - macro(custom_gtest target) - ament_add_gtest(${target}${target_suffix} ${ARGN} - APPEND_LIBRARY_DIRS "${append_library_dirs}" - ENV - RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} - RMW_IMPLEMENTATION=${rmw_implementation}) - if(TARGET ${target}${target_suffix}) - target_compile_definitions(${target}${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(${target}${target_suffix} "${cpp_typesupport_target}" rclcpp::rclcpp) - target_include_directories(${target}${target_suffix} PUBLIC include) - endif() - endmacro() + set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR}") + if(WIN32) + set(append_library_dirs "${append_library_dirs}/$") + endif() - function(custom_executable target) - add_executable(${target} ${ARGN}) - target_compile_definitions(${target} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(${target} "${cpp_typesupport_target}" rclcpp::rclcpp) - endfunction() + ament_add_gtest_executable(gtest_avoid_ros_namespace_conventions_qos + test/test_avoid_ros_namespace_conventions_qos.cpp + ) + target_include_directories(gtest_avoid_ros_namespace_conventions_qos PRIVATE include) + target_link_libraries(gtest_avoid_ros_namespace_conventions_qos "${cpp_typesupport_target}" rclcpp::rclcpp) - function(custom_gtest_executable target) - ament_add_gtest_executable(${target} ${ARGN}) - target_compile_definitions(${target} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(${target} "${cpp_typesupport_target}" rclcpp::rclcpp) - endfunction() + ament_add_gtest_executable(gtest_publisher test/test_publisher.cpp) + target_include_directories(gtest_publisher PRIVATE include) + target_link_libraries(gtest_publisher "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_client_wait_for_service_shutdown + test/test_client_wait_for_service_shutdown.cpp + ) + target_include_directories(gtest_client_wait_for_service_shutdown PRIVATE include) + target_link_libraries(gtest_client_wait_for_service_shutdown "${cpp_typesupport_target}" rclcpp::rclcpp rcpputils::rcpputils) + + ament_add_gtest_executable(gtest_executor test/test_executor.cpp) + target_include_directories(gtest_executor PRIVATE include) + target_link_libraries(gtest_executor "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_repeated_publisher_subscriber test/test_repeated_publisher_subscriber.cpp) + target_include_directories(gtest_repeated_publisher_subscriber PRIVATE include) + target_link_libraries(gtest_repeated_publisher_subscriber "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_spin test/test_spin.cpp) + target_include_directories(gtest_spin PRIVATE include) + target_link_libraries(gtest_spin "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_subscription test/test_subscription.cpp) + target_include_directories(gtest_subscription PRIVATE include) + target_link_libraries(gtest_subscription "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_multiple_service_calls test/test_multiple_service_calls.cpp) + target_include_directories(gtest_multiple_service_calls PRIVATE include) + target_link_libraries(gtest_multiple_service_calls "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_timer test/test_timer.cpp) + target_include_directories(gtest_timer PRIVATE include) + target_link_libraries(gtest_timer rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_timeout_subscriber test/test_timeout_subscriber.cpp) + target_include_directories(gtest_timeout_subscriber PRIVATE include) + target_link_libraries(gtest_timeout_subscriber "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_intra_process test/test_intra_process.cpp) + target_include_directories(gtest_intra_process PRIVATE include) + target_link_libraries(gtest_intra_process "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_multithreaded test/test_multithreaded.cpp) + target_include_directories(gtest_multithreaded PRIVATE include) + target_link_libraries(gtest_multithreaded "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_local_parameters test/test_local_parameters.cpp) + target_include_directories(gtest_local_parameters PRIVATE include) + target_link_libraries(gtest_local_parameters rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_services_in_constructor test/test_services_in_constructor.cpp) + target_include_directories(gtest_services_in_constructor PRIVATE include) + target_link_libraries(gtest_services_in_constructor "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(gtest_waitable test/test_waitable.cpp) + target_include_directories(gtest_waitable PRIVATE include) + target_link_libraries(gtest_waitable rclcpp::rclcpp) + + # Test node names + add_executable(node_with_name test/node_with_name.cpp) + target_link_libraries(node_with_name rclcpp::rclcpp) + add_executable(node_name_list test/node_name_list.cpp) + target_link_libraries(node_name_list rclcpp::rclcpp) + add_executable(node_check_names test/node_check_names.cpp) + target_link_libraries(node_check_names rclcpp::rclcpp) + + add_executable(test_sigint_handler test/test_sigint_handler.cpp) + target_link_libraries(test_sigint_handler rclcpp::rclcpp) + + add_executable(test_sigterm_handler test/test_sigterm_handler.cpp) + target_link_libraries(test_sigterm_handler rclcpp::rclcpp) + + # Parameter tests single implementation + add_executable(test_parameters_server_cpp test/test_parameters_server.cpp) + target_link_libraries(test_parameters_server_cpp rclcpp::rclcpp) + + ament_add_gtest_executable(test_remote_parameters_cpp test/test_remote_parameters.cpp) + target_link_libraries(test_remote_parameters_cpp rclcpp::rclcpp) + + # Service tests single implementation + add_executable(test_services_server_cpp test/test_services_server.cpp) + target_link_libraries(test_services_server_cpp "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(test_services_client_cpp test/test_services_client.cpp) + target_link_libraries(test_services_client_cpp "${cpp_typesupport_target}" rclcpp::rclcpp) + + add_executable(test_client_scope_server_cpp test/test_client_scope_server.cpp) + target_link_libraries(test_client_scope_server_cpp "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(test_client_scope_client_cpp test/test_client_scope_client.cpp) + target_link_libraries(test_client_scope_client_cpp "${cpp_typesupport_target}" rclcpp::rclcpp) + + add_executable(test_client_scope_consistency_server_cpp test/test_client_scope_consistency_server.cpp) + target_link_libraries(test_client_scope_consistency_server_cpp "${cpp_typesupport_target}" rclcpp::rclcpp) + + ament_add_gtest_executable(test_client_scope_consistency_client_cpp test/test_client_scope_consistency_client.cpp) + target_link_libraries(test_client_scope_consistency_client_cpp "${cpp_typesupport_target}" rclcpp::rclcpp) macro(custom_launch_test_two_executables test_name executable1 executable2) cmake_parse_arguments(_ARG "" "ARGS1;ARGS2;RMW1;RMW2" "" ${ARGN}) @@ -163,8 +244,7 @@ if(BUILD_TESTING) ${_ARG_UNPARSED_ARGUMENTS} APPEND_LIBRARY_DIRS "${append_library_dirs}" ENV - RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} - RMW_IMPLEMENTATION=${rmw_implementation} + RMW_IMPLEMENTATION=${rmw_implementation} ) if(TEST ${test_name}${target_suffix}) set_tests_properties(${test_name}${target_suffix} @@ -236,87 +316,163 @@ if(BUILD_TESTING) ${_crt_SKIP_TEST}) endmacro() - macro(targets) - custom_gtest(gtest_publisher - "test/test_publisher.cpp" - TIMEOUT 15) - custom_gtest(gtest_avoid_ros_namespace_conventions_qos - "test/test_avoid_ros_namespace_conventions_qos.cpp" - TIMEOUT 15) - custom_gtest(gtest_client_wait_for_service_shutdown - "test/test_client_wait_for_service_shutdown.cpp" - TIMEOUT 15) - custom_gtest(gtest_executor - "test/test_executor.cpp" - TIMEOUT 60) - custom_gtest(gtest_repeated_publisher_subscriber - "test/test_repeated_publisher_subscriber.cpp" - TIMEOUT 15) - custom_gtest(gtest_spin - "test/test_spin.cpp" - TIMEOUT 30) - custom_gtest(gtest_subscription - "test/test_subscription.cpp" - TIMEOUT 60) - custom_gtest(gtest_multiple_service_calls - "test/test_multiple_service_calls.cpp" - TIMEOUT 60) - custom_gtest(gtest_timer - "test/test_timer.cpp" - TIMEOUT 30) - custom_gtest(gtest_timeout_subscriber - "test/test_timeout_subscriber.cpp" - TIMEOUT 30) - custom_gtest(gtest_intra_process - "test/test_intra_process.cpp" - TIMEOUT 15) - custom_gtest(gtest_multithreaded - "test/test_multithreaded.cpp" - TIMEOUT 90) - custom_gtest(gtest_local_parameters - "test/test_local_parameters.cpp" - TIMEOUT 300) - custom_gtest(gtest_services_in_constructor - "test/test_services_in_constructor.cpp" - TIMEOUT 30) - custom_gtest(gtest_waitable - "test/test_waitable.cpp" - TIMEOUT 30) + function(test_target) + set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) + + ament_add_gtest_test(gtest_avoid_ros_namespace_conventions_qos + TEST_NAME gtest_avoid_ros_namespace_conventions_qos${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 15 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_publisher + TEST_NAME gtest_publisher${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 15 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_client_wait_for_service_shutdown + TEST_NAME gtest_client_wait_for_service_shutdown${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_executor + TEST_NAME gtest_executor${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 60 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_repeated_publisher_subscriber + TEST_NAME gtest_repeated_publisher_subscriber${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 15 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_spin + TEST_NAME gtest_spin${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 30 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_subscription + TEST_NAME gtest_subscription${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 60 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_multiple_service_calls + TEST_NAME gtest_multiple_service_calls${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 60 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_timer + TEST_NAME gtest_timer${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 30 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_timeout_subscriber + TEST_NAME gtest_timeout_subscriber${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 30 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_intra_process + TEST_NAME gtest_intra_process${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 15 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_multithreaded + TEST_NAME gtest_multithreaded${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 90 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_local_parameters + TEST_NAME gtest_local_parameters${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 300 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_services_in_constructor + TEST_NAME gtest_services_in_constructor${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 30 + ENV + ${rmw_implementation_env_var} + ) + + ament_add_gtest_test(gtest_waitable + TEST_NAME gtest_waitable${target_suffix} + APPEND_LIBRARY_DIRS "${append_library_dirs}" + TIMEOUT 300 + ENV + ${rmw_implementation_env_var} + ) # Parameter tests single implementation custom_launch_test_two_executables(test_parameter_server_cpp test_parameters_server_cpp test_remote_parameters_cpp + TIMEOUT 60 ENV - RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} - RMW_IMPLEMENTATION=${rmw_implementation} - TIMEOUT 60) + ${rmw_implementation_env_var} + ) # Service tests single implementation custom_launch_test_two_executables(test_services_cpp test_services_server_cpp test_services_client_cpp + TIMEOUT 60 ENV - RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} - RMW_IMPLEMENTATION=${rmw_implementation} - TIMEOUT 60) + ${rmw_implementation_env_var} + ) custom_launch_test_two_executables(test_client_scope_cpp test_client_scope_server_cpp test_client_scope_client_cpp + TIMEOUT 60 ENV - RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} - RMW_IMPLEMENTATION=${rmw_implementation} - TIMEOUT 60) + ${rmw_implementation_env_var} + ) custom_launch_test_two_executables(test_client_scope_consistency_cpp test_client_scope_consistency_server_cpp test_client_scope_consistency_client_cpp + TIMEOUT 60 ENV - RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} - RMW_IMPLEMENTATION=${rmw_implementation} - TIMEOUT 60) + ${rmw_implementation_env_var} + ) custom_launch_n_nodes(10 - TIMEOUT 15) + TIMEOUT 15 + ) - # Note (dhood): signal handler tests will be skipped on Windows because there is no opportunity + # Note (dhood): signal handler tests are skipped on Windows because there is no opportunity # for signal handling once shutdown is triggered by launch_testing. set(SKIP_TEST "") if(WIN32) @@ -357,39 +513,10 @@ if(BUILD_TESTING) foreach(rmw_implementation2 ${rmw_implementations}) cross_rmw_tests() endforeach() - endmacro() - - set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR}") - if(WIN32) - set(append_library_dirs "${append_library_dirs}/$") - endif() - - # Test node names - add_executable(node_with_name "test/node_with_name.cpp") - target_link_libraries(node_with_name rclcpp::rclcpp) - add_executable(node_name_list "test/node_name_list.cpp") - target_link_libraries(node_name_list rclcpp::rclcpp) - add_executable(node_check_names "test/node_check_names.cpp") - target_link_libraries(node_check_names rclcpp::rclcpp) - - call_for_each_rmw_implementation(targets) - - custom_executable(test_sigint_handler "test/test_sigint_handler.cpp") - custom_executable(test_sigterm_handler "test/test_sigterm_handler.cpp") - - # Parameter tests single implementation - custom_executable(test_parameters_server_cpp "test/test_parameters_server.cpp") - custom_gtest_executable(test_remote_parameters_cpp "test/test_remote_parameters.cpp") - - # Service tests single implementation - custom_executable(test_services_server_cpp "test/test_services_server.cpp") - custom_gtest_executable(test_services_client_cpp "test/test_services_client.cpp") - - custom_executable(test_client_scope_server_cpp "test/test_client_scope_server.cpp") - custom_gtest_executable(test_client_scope_client_cpp "test/test_client_scope_client.cpp") + endfunction() - custom_executable(test_client_scope_consistency_server_cpp "test/test_client_scope_consistency_server.cpp") - custom_gtest_executable(test_client_scope_consistency_client_cpp "test/test_client_scope_consistency_client.cpp") + get_available_rmw_implementations(rmw_implementations) + call_for_each_rmw_implementation(test_target) # TODO(clalancette): Under load, the gtest_subscription__rmw_connextdds test fails deep in the # bowels of Connext; see https://github.com/ros2/rmw_connextdds/issues/136 for details. Mark it diff --git a/test_rclcpp/test/node_check_names.cpp b/test_rclcpp/test/node_check_names.cpp index 262b7d78..8a315993 100644 --- a/test_rclcpp/test/node_check_names.cpp +++ b/test_rclcpp/test/node_check_names.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include "rclcpp/rclcpp.hpp" diff --git a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp index 0f1c66db..57d79bee 100644 --- a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp +++ b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp @@ -25,15 +25,7 @@ #include "./pub_sub_fixtures.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -class CLASSNAME (test_avoid_ros_namespace_conventions_qos, RMW_IMPLEMENTATION) - : public ::testing::Test +class test_avoid_ros_namespace_conventions_qos : public ::testing::Test { public: static void SetUpTestCase() @@ -48,10 +40,8 @@ class CLASSNAME (test_avoid_ros_namespace_conventions_qos, RMW_IMPLEMENTATION) }; // Test communciation works with the avoid_ros_namespace_conventions QoS enabled. -TEST_F( - CLASSNAME(test_avoid_ros_namespace_conventions_qos, RMW_IMPLEMENTATION), - pub_sub_works -) { +TEST_F(test_avoid_ros_namespace_conventions_qos, pub_sub_works) +{ // topic name std::string topic_name = "test_avoid_ros_namespace_conventions_qos"; // code to create the callback and subscription diff --git a/test_rclcpp/test/test_client_scope_client.cpp b/test_rclcpp/test/test_client_scope_client.cpp index f5574247..388f4f1e 100644 --- a/test_rclcpp/test/test_client_scope_client.cpp +++ b/test_rclcpp/test/test_client_scope_client.cpp @@ -21,16 +21,9 @@ #include "rclcpp/rclcpp.hpp" #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test +class service_client : public ::testing::Test { public: static void SetUpTestCase() @@ -44,7 +37,8 @@ class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test) { +TEST_F(service_client, client_scope_regression_test) +{ auto node = rclcpp::Node::make_shared("client_scope_regression_test"); // Extra scope so the first client will be deleted afterwards diff --git a/test_rclcpp/test/test_client_scope_consistency_client.cpp b/test_rclcpp/test/test_client_scope_consistency_client.cpp index 509d1ca0..b73e13dc 100644 --- a/test_rclcpp/test/test_client_scope_consistency_client.cpp +++ b/test_rclcpp/test/test_client_scope_consistency_client.cpp @@ -12,9 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include - #include +#include #include #include @@ -23,16 +22,9 @@ #include "rclcpp/rclcpp.hpp" #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test +class service_client : public ::testing::Test { public: static void SetUpTestCase() @@ -48,7 +40,8 @@ class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test // This test is concerned with the consistency of the two clients' behavior, not necessarily whether // or not they are successful. -TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_regression_test) { +TEST_F(service_client, client_scope_consistency_regression_test) +{ auto node = rclcpp::Node::make_shared("client_scope_consistency_regression_test"); // Replicate the settings that caused https://github.com/ros2/system_tests/issues/153 diff --git a/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp b/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp index 281bdc09..89450edf 100644 --- a/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp +++ b/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp @@ -20,16 +20,9 @@ #include "rcpputils/scope_exit.hpp" #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test +class service_client : public ::testing::Test { public: static void SetUpTestCase() @@ -44,7 +37,8 @@ class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test }; // rclcpp::shutdown() should wake up wait_for_service, even without spin. -TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) { +TEST_F(service_client, wait_for_service_shutdown) +{ auto node = rclcpp::Node::make_shared("wait_for_service_shutdown"); auto client = node->create_client("wait_for_service_shutdown"); diff --git a/test_rclcpp/test/test_executor.cpp b/test_rclcpp/test/test_executor.cpp index e8f5c46c..e23f1b5b 100644 --- a/test_rclcpp/test/test_executor.cpp +++ b/test_rclcpp/test/test_executor.cpp @@ -31,16 +31,9 @@ #include "test_rclcpp/msg/u_int32.hpp" #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (test_executor, RMW_IMPLEMENTATION) : public ::testing::Test +class test_executor : public ::testing::Test { public: static void SetUpTestCase() @@ -54,7 +47,8 @@ class CLASSNAME (test_executor, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) { +TEST_F(test_executor, recursive_spin_call) +{ rclcpp::executors::SingleThreadedExecutor executor; auto node = rclcpp::Node::make_shared("recursive_spin_call"); auto timer = node->create_wall_timer( @@ -69,7 +63,8 @@ TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) { executor.spin(); } -TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) { +TEST_F(test_executor, spin_some_max_duration) +{ rclcpp::executors::SingleThreadedExecutor executor; auto node = rclcpp::Node::make_shared("spin_some_max_duration"); auto lambda = []() { @@ -92,7 +87,8 @@ TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) { ASSERT_GT(max_duration + 500ms, end - start); } -TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) { +TEST_F(test_executor, multithreaded_spin_call) +{ rclcpp::executors::SingleThreadedExecutor executor; auto node = rclcpp::Node::make_shared("multithreaded_spin_call"); std::mutex m; @@ -124,7 +120,8 @@ TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) { } // Try spinning 2 single-threaded executors in two separate threads. -TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multiple_executors) { +TEST_F(test_executor, multiple_executors) +{ std::atomic_uint counter1; counter1 = 0; std::atomic_uint counter2; @@ -184,7 +181,8 @@ TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multiple_executors) { // Check that the executor is notified when a node adds a new timer, publisher, subscription, // service or client. -TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), notify) { +TEST_F(test_executor, notify) +{ rclcpp::executors::SingleThreadedExecutor executor; auto executor_spin_lambda = [&executor]() { executor.spin(); diff --git a/test_rclcpp/test/test_intra_process.cpp b/test_rclcpp/test/test_intra_process.cpp index f0d05160..3559852e 100644 --- a/test_rclcpp/test/test_intra_process.cpp +++ b/test_rclcpp/test/test_intra_process.cpp @@ -22,18 +22,10 @@ #include "test_rclcpp/msg/u_int32.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - - static const std::chrono::milliseconds sleep_per_loop(10); static const int max_loops = 200; -class CLASSNAME (test_intra_process_within_one_node, RMW_IMPLEMENTATION) : public ::testing::Test +class test_intra_process_within_one_node : public ::testing::Test { public: static void SetUpTestCase() @@ -47,7 +39,8 @@ class CLASSNAME (test_intra_process_within_one_node, RMW_IMPLEMENTATION) : publi } }; -TEST_F(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_usage) { +TEST_F(test_intra_process_within_one_node, nominal_usage) +{ // use intra process = true auto node = rclcpp::Node::make_shared( "test_intra_process", diff --git a/test_rclcpp/test/test_local_parameters.cpp b/test_rclcpp/test/test_local_parameters.cpp index 6484223c..4ca498b3 100644 --- a/test_rclcpp/test/test_local_parameters.cpp +++ b/test_rclcpp/test/test_local_parameters.cpp @@ -27,14 +27,7 @@ using namespace std::chrono_literals; -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -class CLASSNAME (test_local_parameters, RMW_IMPLEMENTATION) : public ::testing::Test +class test_local_parameters : public ::testing::Test { public: static void SetUpTestCase() @@ -48,7 +41,8 @@ class CLASSNAME (test_local_parameters, RMW_IMPLEMENTATION) : public ::testing:: } }; -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) { +TEST_F(test_local_parameters, to_string) +{ rclcpp::Parameter pv("foo", "bar"); rclcpp::Parameter pv2("foo2", "bar2"); std::string json_dict = std::to_string(pv); @@ -79,7 +73,8 @@ TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) { std::to_string(pv).c_str()); } -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) { +TEST_F(test_local_parameters, local_synchronous) +{ auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous"); declare_test_parameters(node); auto parameters_client = std::make_shared(node); @@ -90,7 +85,8 @@ TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) test_get_parameters_sync(parameters_client); } -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) { +TEST_F(test_local_parameters, local_synchronous_repeated) +{ auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated"); declare_test_parameters(node); auto parameters_client = std::make_shared(node); @@ -104,7 +100,8 @@ TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_r } } -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) { +TEST_F(test_local_parameters, local_asynchronous) +{ auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous")); declare_test_parameters(node); auto parameters_client = std::make_shared(node); @@ -164,7 +161,8 @@ class ParametersAsyncNode : public rclcpp::Node // Regression test for calling parameter client async services, but having the specified callback // go out of scope before it gets called: see https://github.com/ros2/rclcpp/pull/414 -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_callback) { +TEST_F(test_local_parameters, local_async_with_callback) +{ auto node = std::make_shared(); if (!node->parameters_client_->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -176,7 +174,8 @@ TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_ca executor.spin(); } -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { +TEST_F(test_local_parameters, helpers) +{ auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); node->declare_parameter("foo", 0); node->declare_parameter("bar", ""); @@ -299,7 +298,8 @@ TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { EXPECT_EQ(barfoo[2], 5); } -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) { +TEST_F(test_local_parameters, get_from_node_primitive_type) +{ auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); node->declare_parameter("foo", 0); node->declare_parameter("bar", ""); @@ -372,7 +372,8 @@ TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primi EXPECT_EQ(barfoo[2], 5); } -TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant_type) { +TEST_F(test_local_parameters, get_from_node_variant_type) +{ using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); @@ -437,11 +438,3 @@ TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_varia EXPECT_NO_THROW(got_param = node->get_parameter("barfoo", barfoo)); EXPECT_EQ(true, got_param); } - -int main(int argc, char ** argv) -{ - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - return ret; -} diff --git a/test_rclcpp/test/test_multiple_service_calls.cpp b/test_rclcpp/test/test_multiple_service_calls.cpp index 85167652..d402416c 100644 --- a/test_rclcpp/test/test_multiple_service_calls.cpp +++ b/test_rclcpp/test/test_multiple_service_calls.cpp @@ -27,13 +27,6 @@ #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; void handle_add_two_ints( @@ -43,7 +36,7 @@ void handle_add_two_ints( response->sum = request->a + request->b; } -class CLASSNAME (test_two_service_calls, RMW_IMPLEMENTATION) : public ::testing::Test +class test_two_service_calls : public ::testing::Test { public: static void SetUpTestCase() @@ -57,7 +50,8 @@ class CLASSNAME (test_two_service_calls, RMW_IMPLEMENTATION) : public ::testing: } }; -TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls) { +TEST_F(test_two_service_calls, two_service_calls) +{ auto node = rclcpp::Node::make_shared("test_two_service_calls"); auto service = node->create_service( @@ -97,7 +91,8 @@ TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls) // Regression test for async client not being able to queue another request in a response callback. // See https://github.com/ros2/rclcpp/pull/415 -TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_call) { +TEST_F(test_two_service_calls, recursive_service_call) +{ auto node = rclcpp::Node::make_shared("test_recursive_service_call"); auto service = node->create_service( @@ -144,7 +139,7 @@ TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_ EXPECT_TRUE(second_result_received); } -class CLASSNAME (test_multiple_service_calls, RMW_IMPLEMENTATION) : public ::testing::Test +class test_multiple_service_calls : public ::testing::Test { public: static void SetUpTestCase() @@ -158,7 +153,8 @@ class CLASSNAME (test_multiple_service_calls, RMW_IMPLEMENTATION) : public ::tes } }; -TEST_F(CLASSNAME(test_multiple_service_calls, RMW_IMPLEMENTATION), multiple_clients) { +TEST_F(test_multiple_service_calls, multiple_clients) +{ const uint32_t n = 5; auto node = rclcpp::Node::make_shared("test_multiple_clients"); diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index f23d4a2f..bcf1dcd6 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -31,16 +31,9 @@ #include "test_rclcpp/msg/u_int32.hpp" #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (test_multithreaded, RMW_IMPLEMENTATION) : public ::testing::Test +class test_multithreaded : public ::testing::Test { public: void SetUp() @@ -154,12 +147,14 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) EXPECT_EQ(expected_count, counter.load()); } -TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_single_producer) { +TEST_F(test_multithreaded, multi_consumer_single_producer) +{ // multiple subscriptions, single publisher multi_consumer_pub_sub_test(false); } -TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_intra_process) { +TEST_F(test_multithreaded, multi_consumer_intra_process) +{ // multiple subscriptions, single publisher, intra-process multi_consumer_pub_sub_test(true); } @@ -167,7 +162,8 @@ TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_intra_p // TODO(brawner) On high core-count machines, this test fails with rmw_cyclonedds_cpp because // cyclonedds hard codes the maximum allowed threads. // For potential resolution, see https://github.com/ros2/rmw_cyclonedds/issues/268 -TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) { +TEST_F(test_multithreaded, multi_consumer_clients) +{ // multiple clients, single server auto node = rclcpp::Node::make_shared("multi_consumer_clients"); rclcpp::executors::MultiThreadedExecutor executor; @@ -425,10 +421,12 @@ static inline void multi_access_publisher(bool intra_process) ASSERT_EQ(num_messages, subscription_counter); } -TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher) { +TEST_F(test_multithreaded, multi_access_publisher) +{ multi_access_publisher(false); } -TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher_intra_process) { +TEST_F(test_multithreaded, multi_access_publisher_intra_process) +{ multi_access_publisher(true); } diff --git a/test_rclcpp/test/test_publisher.cpp b/test_rclcpp/test/test_publisher.cpp index 05482acc..f03edc79 100644 --- a/test_rclcpp/test/test_publisher.cpp +++ b/test_rclcpp/test/test_publisher.cpp @@ -25,14 +25,7 @@ #include "./pub_sub_fixtures.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -class CLASSNAME (test_publisher, RMW_IMPLEMENTATION) : public ::testing::Test +class test_publisher : public ::testing::Test { public: static void SetUpTestCase() @@ -47,7 +40,8 @@ class CLASSNAME (test_publisher, RMW_IMPLEMENTATION) : public ::testing::Test }; // Short test for the const reference publish signature. -TEST_F(CLASSNAME(test_publisher, RMW_IMPLEMENTATION), publish_with_const_reference) { +TEST_F(test_publisher, publish_with_const_reference) +{ // topic name std::string topic_name = "test_publish_with_const_reference"; // code to create the callback and subscription diff --git a/test_rclcpp/test/test_remote_parameters.cpp b/test_rclcpp/test/test_remote_parameters.cpp index 24bde96a..261f5294 100644 --- a/test_rclcpp/test/test_remote_parameters.cpp +++ b/test_rclcpp/test/test_remote_parameters.cpp @@ -22,16 +22,9 @@ #include "parameter_fixtures.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (parameters, RMW_IMPLEMENTATION) : public ::testing::Test +class parameters : public ::testing::Test { public: static void SetUpTestCase() @@ -45,7 +38,8 @@ class CLASSNAME (parameters, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(parameters, RMW_IMPLEMENTATION), test_remote_parameters_async) { +TEST_F(parameters, test_remote_parameters_async) +{ std::string test_server_name = "test_parameters_server_allow_undeclared"; // TODO(tfoote) make test_server name parameterizable // if (argc >= 2) { @@ -65,7 +59,8 @@ TEST_F(CLASSNAME(parameters, RMW_IMPLEMENTATION), test_remote_parameters_async) test_get_parameters_async(node, parameters_client, true); } -TEST_F(CLASSNAME(parameters, RMW_IMPLEMENTATION), test_remote_parameters_sync) { +TEST_F(parameters, test_remote_parameters_sync) +{ std::string test_server_name = "test_parameters_server_allow_undeclared"; auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_sync")); @@ -81,7 +76,8 @@ TEST_F(CLASSNAME(parameters, RMW_IMPLEMENTATION), test_remote_parameters_sync) { test_get_parameters_sync(parameters_client, true); } -TEST_F(CLASSNAME(parameters, RMW_IMPLEMENTATION), test_set_remote_parameters_atomically_sync) { +TEST_F(parameters, test_set_remote_parameters_atomically_sync) +{ std::string test_server_name = "test_parameters_server_allow_undeclared"; auto node = rclcpp::Node::make_shared(std::string("test_set_remote_parameters_atomically_sync")); @@ -97,7 +93,7 @@ TEST_F(CLASSNAME(parameters, RMW_IMPLEMENTATION), test_set_remote_parameters_ato test_get_parameters_sync(parameters_client, true); } -class CLASSNAME (parameters_must_declare, RMW_IMPLEMENTATION) : public ::testing::Test +class parameters_must_declare : public ::testing::Test { public: static void SetUpTestCase() @@ -111,7 +107,8 @@ class CLASSNAME (parameters_must_declare, RMW_IMPLEMENTATION) : public ::testing } }; -TEST_F(CLASSNAME(parameters_must_declare, RMW_IMPLEMENTATION), test_remote_parameters_async) { +TEST_F(parameters_must_declare, test_remote_parameters_async) +{ std::string test_server_name = "test_parameters_server_must_declare"; auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_async")); @@ -126,7 +123,8 @@ TEST_F(CLASSNAME(parameters_must_declare, RMW_IMPLEMENTATION), test_remote_param test_set_parameters_async(node, parameters_client, 0); } -TEST_F(CLASSNAME(parameters_must_declare, RMW_IMPLEMENTATION), test_remote_parameters_sync) { +TEST_F(parameters_must_declare, test_remote_parameters_sync) +{ std::string test_server_name = "test_parameters_server_must_declare"; auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_sync")); @@ -141,9 +139,7 @@ TEST_F(CLASSNAME(parameters_must_declare, RMW_IMPLEMENTATION), test_remote_param test_set_parameters_sync(parameters_client, 0); } -TEST_F( - CLASSNAME(parameters_must_declare, RMW_IMPLEMENTATION), - test_set_remote_parameters_atomically_sync) +TEST_F(parameters_must_declare, test_set_remote_parameters_atomically_sync) { std::string test_server_name = "test_parameters_server_must_declare"; diff --git a/test_rclcpp/test/test_repeated_publisher_subscriber.cpp b/test_rclcpp/test/test_repeated_publisher_subscriber.cpp index a3f7a9f8..af0879ca 100644 --- a/test_rclcpp/test/test_repeated_publisher_subscriber.cpp +++ b/test_rclcpp/test/test_repeated_publisher_subscriber.cpp @@ -22,15 +22,7 @@ #include "test_rclcpp/msg/u_int32.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -class CLASSNAME (test_repeated_publisher_subscriber, RMW_IMPLEMENTATION) - : public ::testing::Test +class test_repeated_publisher_subscriber : public ::testing::Test { public: static void SetUpTestCase() @@ -44,9 +36,7 @@ class CLASSNAME (test_repeated_publisher_subscriber, RMW_IMPLEMENTATION) } }; -TEST_F( - CLASSNAME(test_repeated_publisher_subscriber, RMW_IMPLEMENTATION), - subscription_and_spinning) +TEST_F(test_repeated_publisher_subscriber, subscription_and_spinning) { auto node = rclcpp::Node::make_shared("test_repeated_publisher_subscriber"); @@ -110,5 +100,4 @@ TEST_F( printf("Destroying publisher and subscriber...\n"); fflush(stdout); } - rclcpp::shutdown(); } diff --git a/test_rclcpp/test/test_services_client.cpp b/test_rclcpp/test/test_services_client.cpp index 6e315820..09bc988f 100644 --- a/test_rclcpp/test/test_services_client.cpp +++ b/test_rclcpp/test/test_services_client.cpp @@ -22,16 +22,9 @@ #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (test_services_client, RMW_IMPLEMENTATION) : public ::testing::Test +class test_services_client : public ::testing::Test { public: static void SetUpTestCase() @@ -45,7 +38,8 @@ class CLASSNAME (test_services_client, RMW_IMPLEMENTATION) : public ::testing::T } }; -TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_noreqid) { +TEST_F(test_services_client, test_add_noreqid) +{ auto node = rclcpp::Node::make_shared("test_services_client_no_reqid"); auto client = node->create_client("add_two_ints_noreqid"); @@ -65,7 +59,8 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_noreqid) { EXPECT_EQ(3, result.get()->sum); } -TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_reqid) { +TEST_F(test_services_client, test_add_reqid) +{ auto node = rclcpp::Node::make_shared("test_services_client_add_reqid"); auto client = node->create_client("add_two_ints_reqid"); @@ -85,7 +80,8 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_reqid) { EXPECT_EQ(9, result.get()->sum); } -TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) { +TEST_F(test_services_client, test_return_request) +{ auto node = rclcpp::Node::make_shared("test_services_client_return_request"); auto client = node->create_client( @@ -110,7 +106,8 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); } -TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_two_ints_defered_cb) { +TEST_F(test_services_client, test_add_two_ints_defered_cb) +{ auto node = rclcpp::Node::make_shared("test_services_client_add_two_ints_defered_cb"); auto client = node->create_client( @@ -135,7 +132,8 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_two_ints_de ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); } -TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_two_ints_defcb_with_handle) { +TEST_F(test_services_client, test_add_two_ints_defcb_with_handle) +{ auto node = rclcpp::Node::make_shared("test_services_client_add_two_ints_defered_cb_with_handle"); auto client = node->create_client( diff --git a/test_rclcpp/test/test_services_in_constructor.cpp b/test_rclcpp/test/test_services_in_constructor.cpp index 3a535b0b..0b62c615 100644 --- a/test_rclcpp/test/test_services_in_constructor.cpp +++ b/test_rclcpp/test/test_services_in_constructor.cpp @@ -20,13 +20,6 @@ #include "test_rclcpp/srv/add_two_ints.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - /* The purpose of these tests is to ensure that Services and Clients can be * created within the constructor of a class which inherits from Node. * This is important as it is a common thing users will try to do and was not @@ -53,7 +46,7 @@ class MyNodeWithService : public rclcpp::Node rclcpp::ServiceBase::SharedPtr service_; }; -class CLASSNAME (test_services_in_constructor, RMW_IMPLEMENTATION) : public ::testing::Test +class test_services_in_constructor : public ::testing::Test { public: static void SetUpTestCase() @@ -67,7 +60,8 @@ class CLASSNAME (test_services_in_constructor, RMW_IMPLEMENTATION) : public ::te } }; -TEST_F(CLASSNAME(test_services_in_constructor, RMW_IMPLEMENTATION), service_in_constructor) { +TEST_F(test_services_in_constructor, service_in_constructor) +{ auto n = std::make_shared(); } @@ -84,6 +78,7 @@ class MyNodeWithClient : public rclcpp::Node rclcpp::ClientBase::SharedPtr client_; }; -TEST_F(CLASSNAME(test_services_in_constructor, RMW_IMPLEMENTATION), client_in_constructor) { +TEST_F(test_services_in_constructor, client_in_constructor) +{ auto n = std::make_shared(); } diff --git a/test_rclcpp/test/test_services_server.cpp b/test_rclcpp/test/test_services_server.cpp index e693837a..8f661232 100644 --- a/test_rclcpp/test/test_services_server.cpp +++ b/test_rclcpp/test/test_services_server.cpp @@ -12,7 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include +#include #include #include "rclcpp/rclcpp.hpp" diff --git a/test_rclcpp/test/test_sigint_handler.cpp b/test_rclcpp/test/test_sigint_handler.cpp index f75db5de..dae77ee4 100644 --- a/test_rclcpp/test/test_sigint_handler.cpp +++ b/test_rclcpp/test/test_sigint_handler.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include +#include #include "rclcpp/rclcpp.hpp" diff --git a/test_rclcpp/test/test_sigterm_handler.cpp b/test_rclcpp/test/test_sigterm_handler.cpp index d8143171..e15c5b3d 100644 --- a/test_rclcpp/test/test_sigterm_handler.cpp +++ b/test_rclcpp/test/test_sigterm_handler.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include +#include #include "rclcpp/rclcpp.hpp" diff --git a/test_rclcpp/test/test_spin.cpp b/test_rclcpp/test/test_spin.cpp index f3882f0a..dbeb710b 100644 --- a/test_rclcpp/test/test_spin.cpp +++ b/test_rclcpp/test/test_spin.cpp @@ -24,16 +24,9 @@ #include "test_rclcpp/msg/u_int32.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; -class CLASSNAME (test_spin, RMW_IMPLEMENTATION) : public ::testing::Test +class test_spin : public ::testing::Test { public: void SetUp() @@ -52,7 +45,8 @@ class CLASSNAME (test_spin, RMW_IMPLEMENTATION) : public ::testing::Test /* Ensures that the timeout behavior of spin_until_future_complete is correct. */ -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete_timeout) { +TEST_F(test_spin, test_spin_until_future_complete_timeout) +{ using rclcpp::FutureReturnCode; rclcpp::executors::SingleThreadedExecutor executor; @@ -139,7 +133,8 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete } } -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { +TEST_F(test_spin, spin_until_future_complete) +{ auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -161,7 +156,8 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { EXPECT_EQ(future.get(), true); } -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_timeout) { +TEST_F(test_spin, spin_until_future_complete_timeout) +{ auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -186,7 +182,8 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_time EXPECT_EQ(future.get(), true); } -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_interrupted) { +TEST_F(test_spin, spin_until_future_complete_interrupted) +{ auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -210,7 +207,8 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_inte rclcpp::FutureReturnCode::INTERRUPTED); } -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), cancel) { +TEST_F(test_spin, cancel) +{ auto node = rclcpp::Node::make_shared("cancel"); rclcpp::executors::SingleThreadedExecutor executor; auto pub = node->create_publisher("cancel", 10); diff --git a/test_rclcpp/test/test_subscription.cpp b/test_rclcpp/test/test_subscription.cpp index 19ed386c..d6686867 100644 --- a/test_rclcpp/test/test_subscription.cpp +++ b/test_rclcpp/test/test_subscription.cpp @@ -28,14 +28,6 @@ #include "./pub_sub_fixtures.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) - -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using namespace std::chrono_literals; template @@ -55,7 +47,7 @@ void wait_for_future( " milliseconds\n"; } -class CLASSNAME (test_subscription, RMW_IMPLEMENTATION) : public ::testing::Test +class test_subscription : public ::testing::Test { public: static void SetUpTestCase() @@ -69,7 +61,8 @@ class CLASSNAME (test_subscription, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning) { +TEST_F(test_subscription, subscription_and_spinning) +{ auto node = rclcpp::Node::make_shared("test_subscription"); std::string topic = "test_subscription"; @@ -183,7 +176,8 @@ TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinni } // Shortened version of the test for the ConstSharedPtr callback signature -TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_const) { +TEST_F(test_subscription, subscription_shared_ptr_const) +{ std::string topic_name = "test_subscription_subscription_shared_ptr_const"; // create the callback and subscription int counter = 0; @@ -230,10 +224,8 @@ class CallbackHolder }; // Shortened version of the test for the ConstSharedPtr callback signature in a method -TEST_F( - CLASSNAME(test_subscription, RMW_IMPLEMENTATION), - subscription_shared_ptr_const_method_std_function -) { +TEST_F(test_subscription, subscription_shared_ptr_const_method_std_function) +{ std::string topic_name = "test_subscription_shared_ptr_const_method_std_function"; // create the callback and subscription CallbackHolder cb_holder; @@ -262,10 +254,8 @@ TEST_F( } // Shortened version of the test for the ConstSharedPtr callback signature in a method -TEST_F( - CLASSNAME(test_subscription, RMW_IMPLEMENTATION), - subscription_shared_ptr_const_method_direct -) { +TEST_F(test_subscription, subscription_shared_ptr_const_method_direct) +{ std::string topic_name = "test_subscription_shared_ptr_const_method_direct"; // create the callback and subscription CallbackHolder cb_holder; @@ -294,7 +284,8 @@ TEST_F( } // Shortened version of the test for the ConstSharedPtr with info callback signature -TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_const_with_info) { +TEST_F(test_subscription, subscription_shared_ptr_const_with_info) +{ std::string topic_name = "test_subscription_shared_ptr_const_method_direct"; // create the callback and subscription int counter = 0; @@ -329,7 +320,8 @@ TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr } // Shortened version of the test for subscribing after spinning has started. -TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), spin_before_subscription) { +TEST_F(test_subscription, spin_before_subscription) +{ std::string topic_name = "test_spin_before_subscription"; // create the callback and subscription int counter = 0; @@ -371,7 +363,8 @@ TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), spin_before_subscriptio } // Test of the queue size create_subscription signature. -TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), create_subscription_with_queue_size) { +TEST_F(test_subscription, create_subscription_with_queue_size) +{ auto node = rclcpp::Node::make_shared("test_subscription"); auto callback = [](test_rclcpp::msg::UInt32::ConstSharedPtr) -> void {}; diff --git a/test_rclcpp/test/test_timeout_subscriber.cpp b/test_rclcpp/test/test_timeout_subscriber.cpp index 59eece5e..d5b2e6ba 100644 --- a/test_rclcpp/test/test_timeout_subscriber.cpp +++ b/test_rclcpp/test/test_timeout_subscriber.cpp @@ -21,19 +21,12 @@ #include "rclcpp/rclcpp.hpp" #include "test_rclcpp/msg/u_int32.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - void callback(const test_rclcpp::msg::UInt32::ConstSharedPtr /*msg*/) { throw std::runtime_error("The subscriber received a message but there should be no publisher!"); } -class CLASSNAME (test_timeout_subscriber, RMW_IMPLEMENTATION) : public ::testing::Test +class test_timeout_subscriber : public ::testing::Test { public: static void SetUpTestCase() @@ -47,7 +40,8 @@ class CLASSNAME (test_timeout_subscriber, RMW_IMPLEMENTATION) : public ::testing } }; -TEST_F(CLASSNAME(test_timeout_subscriber, RMW_IMPLEMENTATION), timeout_subscriber) { +TEST_F(test_timeout_subscriber, timeout_subscriber) +{ auto start = std::chrono::steady_clock::now(); auto node = rclcpp::Node::make_shared("test_timeout_subscriber"); diff --git a/test_rclcpp/test/test_timer.cpp b/test_rclcpp/test/test_timer.cpp index 3975eb52..ddfa1521 100644 --- a/test_rclcpp/test/test_timer.cpp +++ b/test_rclcpp/test/test_timer.cpp @@ -19,14 +19,7 @@ #include "rclcpp/rclcpp.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -class CLASSNAME (test_time, RMW_IMPLEMENTATION) : public ::testing::Test +class test_time : public ::testing::Test { public: static void SetUpTestCase() @@ -40,7 +33,8 @@ class CLASSNAME (test_time, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_fire_regularly) { +TEST_F(test_time, timer_fire_regularly) +{ auto node = rclcpp::Node::make_shared("test_timer_fire_regularly"); int counter = 0; @@ -94,7 +88,8 @@ TEST_F(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_fire_regularly) { printf("running for %.3f seconds\n", diff.count()); } -TEST_F(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_during_wait) { +TEST_F(test_time, timer_during_wait) +{ auto node = rclcpp::Node::make_shared("test_timer_during_wait"); int counter = 0; @@ -146,7 +141,8 @@ TEST_F(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_during_wait) { } -TEST_F(CLASSNAME(test_time, RMW_IMPLEMENTATION), finite_timer) { +TEST_F(test_time, finite_timer) +{ auto node = rclcpp::Node::make_shared("finite_timer"); int counter = 0; diff --git a/test_rclcpp/test/test_waitable.cpp b/test_rclcpp/test/test_waitable.cpp index 0871953e..116a99f7 100644 --- a/test_rclcpp/test/test_waitable.cpp +++ b/test_rclcpp/test/test_waitable.cpp @@ -20,14 +20,6 @@ #include "rclcpp/rclcpp.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - - class WaitableWithTimer : public rclcpp::Waitable { public: @@ -99,7 +91,7 @@ class WaitableWithTimer : public rclcpp::Waitable std::promise execute_promise_; }; // class WaitableWithTimer -class CLASSNAME (test_waitable, RMW_IMPLEMENTATION) : public ::testing::Test +class test_waitable : public ::testing::Test { public: static void SetUpTestCase() @@ -113,7 +105,8 @@ class CLASSNAME (test_waitable, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(test_waitable, RMW_IMPLEMENTATION), waitable_with_timer) { +TEST_F(test_waitable, waitable_with_timer) +{ auto node = rclcpp::Node::make_shared("waitable_with_timer"); auto waitable = WaitableWithTimer::make_shared(node->get_clock()); auto group = node->create_callback_group(rclcpp::CallbackGroupType::Reentrant);