diff --git a/test_rmw_implementation/CMakeLists.txt b/test_rmw_implementation/CMakeLists.txt index 514fd22b..3fde4286 100644 --- a/test_rmw_implementation/CMakeLists.txt +++ b/test_rmw_implementation/CMakeLists.txt @@ -26,227 +26,278 @@ if(BUILD_TESTING) find_package(rosidl_runtime_c REQUIRED) find_package(test_msgs REQUIRED) - macro(test_api) - find_package(${rmw_implementation} REQUIRED) + # finding gtest once in the highest scope + # prevents finding it repeatedly in each local scope + ament_find_gtest() + + ament_add_gtest_executable(test_init_shutdown + test/test_init_shutdown.cpp + ) + target_link_libraries(test_init_shutdown + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ) + + ament_add_gtest_executable(test_init_options + test/test_init_options.cpp + ) + target_link_libraries(test_init_options + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ) + + ament_add_gtest_executable(test_create_destroy_node + test/test_create_destroy_node.cpp + ) + target_link_libraries(test_create_destroy_node + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ) + + ament_add_gtest_executable(test_publisher + test/test_publisher.cpp + ) + target_link_libraries(test_publisher + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_subscription + test/test_subscription.cpp + ) + target_link_libraries(test_subscription + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_dds_common::rmw_dds_common_library + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_serialize_deserialize + test/test_serialize_deserialize.cpp + ) + target_link_libraries(test_serialize_deserialize + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rosidl_runtime_c::rosidl_runtime_c + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_publisher_allocator + test/test_publisher_allocator.cpp + ) + target_link_libraries(test_publisher_allocator + rmw::rmw + rmw_implementation::rmw_implementation + ) + + ament_add_gtest_executable(test_subscription_allocator + test/test_subscription_allocator.cpp + ) + target_link_libraries(test_subscription_allocator + rmw::rmw + rmw_implementation::rmw_implementation + ) + + ament_add_gtest_executable(test_wait_set + test/test_wait_set.cpp + ) + target_link_libraries(test_wait_set + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_graph_api + test/test_graph_api.cpp + ) + target_link_libraries(test_graph_api + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_unique_identifiers + test/test_unique_identifiers.cpp + ) + target_link_libraries(test_unique_identifiers + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_service + test/test_service.cpp + ) + target_link_libraries(test_service + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_client + test/test_client.cpp + ) + target_link_libraries(test_client + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_qos_profile_check_compatible + test/test_qos_profile_check_compatible.cpp + ) + target_link_libraries(test_qos_profile_check_compatible + rmw::rmw + rmw_implementation::rmw_implementation + ) + + ament_add_gtest_executable(test_duration_infinite + test/test_duration_infinite.cpp + ) + target_link_libraries(test_duration_infinite + osrf_testing_tools_cpp::memory_tools + rcutils::rcutils + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + ament_add_gtest_executable(test_event + test/test_event.cpp + ) + target_link_libraries(test_event + osrf_testing_tools_cpp::memory_tools + rmw::rmw + rmw_implementation::rmw_implementation + ${test_msgs_TARGETS} + ) + + function(test_api) message(STATUS "Creating API tests for '${rmw_implementation}'") set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) - ament_add_gtest(test_init_shutdown${target_suffix} - test/test_init_shutdown.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_init_shutdown${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_init_shutdown${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation + ament_add_gtest_test(test_init_shutdown + TEST_NAME test_init_shutdown${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_init_options${target_suffix} - test/test_init_options.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_init_options${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_init_options${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation + ament_add_gtest_test(test_init_options + TEST_NAME test_init_options${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_create_destroy_node${target_suffix} - test/test_create_destroy_node.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_create_destroy_node${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_create_destroy_node${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation + ament_add_gtest_test(test_create_destroy_node + TEST_NAME test_create_destroy_node${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_publisher${target_suffix} - test/test_publisher.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_publisher${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_publisher${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ament_add_gtest_test(test_publisher + TEST_NAME test_publisher${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_subscription${target_suffix} - test/test_subscription.cpp - ENV ${rmw_implementation_env_var} + ament_add_gtest_test(test_subscription + TEST_NAME test_subscription${target_suffix} TIMEOUT 120 - ) - target_compile_definitions(test_subscription${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_subscription${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_dds_common::rmw_dds_common_library - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_serialize_deserialize${target_suffix} - test/test_serialize_deserialize.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_serialize_deserialize${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_serialize_deserialize${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rosidl_runtime_c::rosidl_runtime_c - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ament_add_gtest_test(test_serialize_deserialize + TEST_NAME test_serialize_deserialize${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_publisher_allocator${target_suffix} - test/test_publisher_allocator.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_publisher_allocator${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_publisher_allocator${target_suffix} - rmw::rmw - rmw_implementation::rmw_implementation + ament_add_gtest_test(test_publisher_allocator + TEST_NAME test_publisher_allocator${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_subscription_allocator${target_suffix} - test/test_subscription_allocator.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_subscription_allocator${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_subscription_allocator${target_suffix} - rmw::rmw - rmw_implementation::rmw_implementation + ament_add_gtest_test(test_subscription_allocator + TEST_NAME test_subscription_allocator${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_wait_set${target_suffix} - test/test_wait_set.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_wait_set${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_wait_set${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ament_add_gtest_test(test_wait_set + TEST_NAME test_wait_set${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_graph_api${target_suffix} - test/test_graph_api.cpp - ENV ${rmw_implementation_env_var} + ament_add_gtest_test(test_graph_api + TEST_NAME test_graph_api${target_suffix} TIMEOUT 120 - ) - target_compile_definitions(test_graph_api${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_graph_api${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_unique_identifiers${target_suffix} - test/test_unique_identifiers.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_unique_identifiers${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_unique_identifiers${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ament_add_gtest_test(test_unique_identifiers + TEST_NAME test_unique_identifiers${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_service${target_suffix} - test/test_service.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_service${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_service${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ament_add_gtest_test(test_service + TEST_NAME test_service${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_client${target_suffix} - test/test_client.cpp - ENV ${rmw_implementation_env_var} + ament_add_gtest_test(test_client + TEST_NAME test_client${target_suffix} TIMEOUT 120 - ) - target_compile_definitions(test_client${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_client${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_qos_profile_check_compatible${target_suffix} - test/test_qos_profile_check_compatible.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_qos_profile_check_compatible${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_qos_profile_check_compatible${target_suffix} - rmw::rmw - rmw_implementation::rmw_implementation + ament_add_gtest_test(test_qos_profile_check_compatible + TEST_NAME test_qos_profile_check_compatible${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_duration_infinite${target_suffix} - test/test_duration_infinite.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_duration_infinite${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_duration_infinite${target_suffix} - osrf_testing_tools_cpp::memory_tools - rcutils::rcutils - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ament_add_gtest_test(test_duration_infinite + TEST_NAME test_duration_infinite${target_suffix} + ENV + ${rmw_implementation_env_var} ) - ament_add_gtest(test_event${target_suffix} - test/test_event.cpp - ENV ${rmw_implementation_env_var} - ) - target_compile_definitions(test_event${target_suffix} - PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") - target_link_libraries(test_event${target_suffix} - osrf_testing_tools_cpp::memory_tools - rmw::rmw - rmw_implementation::rmw_implementation - ${test_msgs_TARGETS} + ament_add_gtest_test(test_event + TEST_NAME test_event${target_suffix} + ENV + ${rmw_implementation_env_var} ) - endmacro() + endfunction() call_for_each_rmw_implementation(test_api) diff --git a/test_rmw_implementation/test/test_client.cpp b/test_rmw_implementation/test/test_client.cpp index d497e437..ffa6f426 100644 --- a/test_rmw_implementation/test/test_client.cpp +++ b/test_rmw_implementation/test/test_client.cpp @@ -28,14 +28,7 @@ #include "./config.hpp" #include "./testing_macros.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 (TestClient, RMW_IMPLEMENTATION) : public ::testing::Test +class TestClient : public ::testing::Test { protected: void SetUp() override @@ -72,7 +65,7 @@ class CLASSNAME (TestClient, RMW_IMPLEMENTATION) : public ::testing::Test rmw_node_t * node{nullptr}; }; -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_and_destroy) { +TEST_F(TestClient, create_and_destroy) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -83,7 +76,7 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_and_destroy) { EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_and_destroy_native) { +TEST_F(TestClient, create_and_destroy_native) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -96,7 +89,7 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_and_destroy_native) { EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_with_bad_arguments) { +TEST_F(TestClient, create_with_bad_arguments) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -159,7 +152,7 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_with_bad_arguments) { EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_with_internal_errors) { +TEST_F(TestClient, create_with_internal_errors) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -179,7 +172,7 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_with_internal_errors) { }); } -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), destroy_with_internal_errors) { +TEST_F(TestClient, destroy_with_internal_errors) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -197,15 +190,12 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), destroy_with_internal_errors) }); } -class CLASSNAME (TestClientUse, RMW_IMPLEMENTATION) - : public CLASSNAME(TestClient, RMW_IMPLEMENTATION) +class TestClientUse : public TestClient { protected: - using Base = CLASSNAME(TestClient, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestClient::SetUp(); client = rmw_create_client(node, ts, service_name, &qos_profile); ASSERT_NE(nullptr, client) << rmw_get_error_string().str; } @@ -214,7 +204,7 @@ class CLASSNAME (TestClientUse, RMW_IMPLEMENTATION) { rmw_ret_t ret = rmw_destroy_client(node, client); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestClient::TearDown(); } rmw_client_t * client{nullptr}; @@ -224,19 +214,19 @@ class CLASSNAME (TestClientUse, RMW_IMPLEMENTATION) rmw_qos_profile_t qos_profile{rmw_qos_profile_default}; }; -TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), destroy_with_null_node) { +TEST_F(TestClientUse, destroy_with_null_node) { rmw_ret_t ret = rmw_destroy_client(nullptr, client); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rmw_reset_error(); } -TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), destroy_null_client) { +TEST_F(TestClientUse, destroy_null_client) { rmw_ret_t ret = rmw_destroy_client(node, nullptr); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rmw_reset_error(); } -TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), destroy_with_node_of_another_impl) { +TEST_F(TestClientUse, destroy_with_node_of_another_impl) { const char * implementation_identifier = node->implementation_identifier; node->implementation_identifier = "not-an-rmw-implementation-identifier"; rmw_ret_t ret = rmw_destroy_client(node, client); @@ -245,7 +235,7 @@ TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), destroy_with_node_of_anothe rmw_reset_error(); } -TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), destroy_client_of_another_impl) { +TEST_F(TestClientUse, destroy_client_of_another_impl) { const char * implementation_identifier = client->implementation_identifier; client->implementation_identifier = "not-an-rmw-implementation-identifier"; rmw_ret_t ret = rmw_destroy_client(node, client); @@ -254,7 +244,7 @@ TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), destroy_client_of_another_i rmw_reset_error(); } -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), send_request_with_bad_arguments) { +TEST_F(TestClient, send_request_with_bad_arguments) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -296,7 +286,7 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), send_request_with_bad_argument rmw_reset_error(); } -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), take_response_with_bad_arguments) { +TEST_F(TestClient, take_response_with_bad_arguments) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -359,7 +349,7 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), take_response_with_bad_argumen rmw_reset_error(); } -TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), service_server_is_available_bad_args) +TEST_F(TestClientUse, service_server_is_available_bad_args) { bool is_available; rmw_ret_t ret = rmw_service_server_is_available(nullptr, client, &is_available); @@ -382,7 +372,7 @@ TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), service_server_is_available rmw_reset_error(); } -TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), service_server_is_available_good_args) +TEST_F(TestClientUse, service_server_is_available_good_args) { bool is_available = false; rmw_ret_t ret = rmw_service_server_is_available(node, client, &is_available); @@ -409,7 +399,7 @@ TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), service_server_is_available ASSERT_TRUE(is_available); } -TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), check_qos) { +TEST_F(TestClient, check_qos) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); diff --git a/test_rmw_implementation/test/test_create_destroy_node.cpp b/test_rmw_implementation/test/test_create_destroy_node.cpp index 62e84c06..dba2345c 100644 --- a/test_rmw_implementation/test/test_create_destroy_node.cpp +++ b/test_rmw_implementation/test/test_create_destroy_node.cpp @@ -24,15 +24,7 @@ #include "./testing_macros.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 (TestNodeConstructionDestruction, RMW_IMPLEMENTATION) : public ::testing::Test +class TestNodeConstructionDestruction : public ::testing::Test { protected: void SetUp() override @@ -61,7 +53,7 @@ class CLASSNAME (TestNodeConstructionDestruction, RMW_IMPLEMENTATION) : public : rmw_context_t context; }; -TEST_F(CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), create_with_bad_arguments) { +TEST_F(TestNodeConstructionDestruction, create_with_bad_arguments) { const char * const node_name = "my_node"; const char * const node_namespace = "/my_ns"; @@ -107,7 +99,7 @@ TEST_F(CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), create_wi rmw_reset_error(); } -TEST_F(CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), destroy_with_bad_arguments) { +TEST_F(TestNodeConstructionDestruction, destroy_with_bad_arguments) { rmw_ret_t ret = rmw_destroy_node(nullptr); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rmw_reset_error(); @@ -128,7 +120,7 @@ TEST_F(CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), destroy_w EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), create_and_destroy) { +TEST_F(TestNodeConstructionDestruction, create_and_destroy) { const char * const node_name = "my_node"; const char * const node_namespace = "/my_ns"; rmw_node_t * node = rmw_create_node(&context, node_name, node_namespace); @@ -136,8 +128,7 @@ TEST_F(CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), create_an EXPECT_EQ(RMW_RET_OK, rmw_destroy_node(node)) << rmw_get_error_string().str; } -class CLASSNAME (TestLocalhostNodeConstructionDestruction, - RMW_IMPLEMENTATION) : public ::testing::Test +class TestLocalhostNodeConstructionDestruction : public ::testing::Test { protected: void SetUp() override @@ -167,10 +158,7 @@ class CLASSNAME (TestLocalhostNodeConstructionDestruction, rmw_context_t context; }; -TEST_F( - CLASSNAME( - TestLocalhostNodeConstructionDestruction, - RMW_IMPLEMENTATION), create_and_destroy) { +TEST_F(TestLocalhostNodeConstructionDestruction, create_and_destroy) { const char * const node_name = "my_node"; const char * const node_namespace = "/my_ns"; rmw_node_t * node = rmw_create_node(&context, node_name, node_namespace); @@ -178,9 +166,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, rmw_destroy_node(node)) << rmw_get_error_string().str; } -TEST_F( - CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), - create_with_internal_errors) { +TEST_F(TestNodeConstructionDestruction, create_with_internal_errors) { RCUTILS_FAULT_INJECTION_TEST( { constexpr char node_name[] = "my_node"; @@ -198,9 +184,7 @@ TEST_F( }); } -TEST_F( - CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION), - destroy_with_internal_errors) { +TEST_F(TestNodeConstructionDestruction, destroy_with_internal_errors) { RCUTILS_FAULT_INJECTION_TEST( { constexpr char node_name[] = "my_node"; diff --git a/test_rmw_implementation/test/test_duration_infinite.cpp b/test_rmw_implementation/test/test_duration_infinite.cpp index 82d49ae9..6cb841ac 100644 --- a/test_rmw_implementation/test/test_duration_infinite.cpp +++ b/test_rmw_implementation/test/test_duration_infinite.cpp @@ -24,14 +24,7 @@ #include "./config.hpp" #include "./testing_macros.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 (TestDurationInfinite, RMW_IMPLEMENTATION) : public ::testing::Test +class TestDurationInfinite : public ::testing::Test { protected: void SetUp() override @@ -67,7 +60,7 @@ class CLASSNAME (TestDurationInfinite, RMW_IMPLEMENTATION) : public ::testing::T rmw_node_t * node; }; -TEST_F(CLASSNAME(TestDurationInfinite, RMW_IMPLEMENTATION), create_publisher) +TEST_F(TestDurationInfinite, create_publisher) { rmw_ret_t ret = RMW_RET_ERROR; size_t match_count = 0; diff --git a/test_rmw_implementation/test/test_event.cpp b/test_rmw_implementation/test/test_event.cpp index e6f7daab..52bd6fc5 100644 --- a/test_rmw_implementation/test/test_event.cpp +++ b/test_rmw_implementation/test/test_event.cpp @@ -29,14 +29,7 @@ #include "test_msgs/msg/basic_types.h" -#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 (TestEvent, RMW_IMPLEMENTATION) : public ::testing::Test +class TestEvent : public ::testing::Test { protected: void SetUp() override @@ -116,7 +109,7 @@ void event_callback(const void * user_data, size_t number_of_events) } } -TEST_F(CLASSNAME(TestEvent, RMW_IMPLEMENTATION), basic_publisher_matched_event) { +TEST_F(TestEvent, basic_publisher_matched_event) { // Notice: Not support connextdds since it doesn't support rmw_event_set_callback() interface if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { GTEST_SKIP(); @@ -204,7 +197,7 @@ TEST_F(CLASSNAME(TestEvent, RMW_IMPLEMENTATION), basic_publisher_matched_event) EXPECT_EQ(-2, matched_status.current_count_change); } -TEST_F(CLASSNAME(TestEvent, RMW_IMPLEMENTATION), basic_subscription_matched_event) { +TEST_F(TestEvent, basic_subscription_matched_event) { // Notice: Not support connextdds since it doesn't support rmw_event_set_callback() interface if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { GTEST_SKIP(); @@ -295,7 +288,7 @@ TEST_F(CLASSNAME(TestEvent, RMW_IMPLEMENTATION), basic_subscription_matched_even EXPECT_EQ(-2, matched_status.current_count_change); } -TEST_F(CLASSNAME(TestEvent, RMW_IMPLEMENTATION), one_pub_multi_sub_connect_disconnect) { +TEST_F(TestEvent, one_pub_multi_sub_connect_disconnect) { rmw_publisher_t * pub = rmw_create_publisher(node, ts, topic_name, &rmw_qos_profile_default, &pub_options); ASSERT_NE(nullptr, pub) << rmw_get_error_string().str; @@ -354,7 +347,7 @@ TEST_F(CLASSNAME(TestEvent, RMW_IMPLEMENTATION), one_pub_multi_sub_connect_disco EXPECT_EQ(-1, matched_status.current_count_change); } -TEST_F(CLASSNAME(TestEvent, RMW_IMPLEMENTATION), one_sub_multi_pub_matched_unmatched_event) { +TEST_F(TestEvent, one_sub_multi_pub_matched_unmatched_event) { rmw_subscription_t * sub = rmw_create_subscription(node, ts, topic_name, &rmw_qos_profile_default, &sub_options); ASSERT_NE(nullptr, sub) << rmw_get_error_string().str; diff --git a/test_rmw_implementation/test/test_graph_api.cpp b/test_rmw_implementation/test/test_graph_api.cpp index d482f74b..19354fe0 100644 --- a/test_rmw_implementation/test/test_graph_api.cpp +++ b/test_rmw_implementation/test/test_graph_api.cpp @@ -32,14 +32,7 @@ #include "./config.hpp" #include "./testing_macros.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 (TestGraphAPI, RMW_IMPLEMENTATION) : public ::testing::Test +class TestGraphAPI : public ::testing::Test { protected: void SetUp() override @@ -83,7 +76,7 @@ class CLASSNAME (TestGraphAPI, RMW_IMPLEMENTATION) : public ::testing::Test const char * const other_node_namespace = "/my_other_test_ns"; }; -TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), get_node_names_with_bad_arguments) { +TEST_F(TestGraphAPI, get_node_names_with_bad_arguments) { rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array(); rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array(); @@ -140,9 +133,7 @@ TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), get_node_names_with_bad_argu EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_node_names_with_enclaves_with_bad_arguments) { +TEST_F(TestGraphAPI, get_node_names_with_enclaves_with_bad_arguments) { rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array(); rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array(); rcutils_string_array_t enclaves = rcutils_get_zero_initialized_string_array(); @@ -223,9 +214,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_topic_names_and_types_with_bad_arguments) { +TEST_F(TestGraphAPI, get_topic_names_and_types_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rmw_names_and_types_t topic_names_and_types = rmw_get_zero_initialized_names_and_types(); bool no_demangle = false; @@ -269,9 +258,7 @@ TEST_F( rmw_reset_error(); } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_service_names_and_types_with_bad_arguments) { +TEST_F(TestGraphAPI, get_service_names_and_types_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rmw_names_and_types_t service_names_and_types = rmw_get_zero_initialized_names_and_types(); @@ -313,9 +300,7 @@ TEST_F( rmw_reset_error(); } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_subscriber_names_and_types_by_node_with_bad_arguments) { +TEST_F(TestGraphAPI, get_subscriber_names_and_types_by_node_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rmw_names_and_types_t topic_names_and_types = rmw_get_zero_initialized_names_and_types(); bool no_demangle = false; @@ -418,9 +403,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, rmw_names_and_types_check_zero(&topic_names_and_types)); } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_publisher_names_and_types_by_node_with_bad_arguments) { +TEST_F(TestGraphAPI, get_publisher_names_and_types_by_node_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rmw_names_and_types_t topic_names_and_types = rmw_get_zero_initialized_names_and_types(); bool no_demangle = false; @@ -523,9 +506,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, rmw_names_and_types_check_zero(&topic_names_and_types)); } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_service_names_and_types_by_node_with_bad_arguments) { +TEST_F(TestGraphAPI, get_service_names_and_types_by_node_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rmw_names_and_types_t service_names_and_types = rmw_get_zero_initialized_names_and_types(); @@ -626,9 +607,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, rmw_names_and_types_check_zero(&service_names_and_types)); } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_client_names_and_types_by_node_with_bad_arguments) { +TEST_F(TestGraphAPI, get_client_names_and_types_by_node_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rmw_names_and_types_t service_names_and_types = rmw_get_zero_initialized_names_and_types(); @@ -729,9 +708,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, rmw_names_and_types_check_zero(&service_names_and_types)); } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_publishers_info_by_topic_with_bad_arguments) { +TEST_F(TestGraphAPI, get_publishers_info_by_topic_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); constexpr char topic_name[] = "/test_topic"; bool no_mangle = false; @@ -793,9 +770,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F( - CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), - get_subscriptions_info_by_topic_with_bad_arguments) { +TEST_F(TestGraphAPI, get_subscriptions_info_by_topic_with_bad_arguments) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); constexpr char topic_name[] = "/test_topic"; bool no_mangle = false; @@ -858,7 +833,7 @@ TEST_F( EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_publishers_with_bad_arguments) { +TEST_F(TestGraphAPI, count_publishers_with_bad_arguments) { size_t count = 0u; constexpr char topic_name[] = "/test_topic"; @@ -887,7 +862,7 @@ TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_publishers_with_bad_ar rmw_reset_error(); } -TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_subscribers_with_bad_arguments) { +TEST_F(TestGraphAPI, count_subscribers_with_bad_arguments) { size_t count = 0u; constexpr char topic_name[] = "/test_topic"; @@ -916,7 +891,7 @@ TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_subscribers_with_bad_a rmw_reset_error(); } -TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_clients_with_bad_arguments) { +TEST_F(TestGraphAPI, count_clients_with_bad_arguments) { size_t count = 0u; constexpr char service_name[] = "/test_service"; @@ -945,7 +920,7 @@ TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_clients_with_bad_argum rmw_reset_error(); } -TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_services_with_bad_arguments) { +TEST_F(TestGraphAPI, count_services_with_bad_arguments) { size_t count = 0u; constexpr char service_name[] = "/test_service"; // A null node is an invalid argument. @@ -973,7 +948,7 @@ TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_services_with_bad_argu rmw_reset_error(); } -TEST_F(CLASSNAME(TestGraphAPI, RMW_IMPLEMENTATION), count_clients_and_services) { +TEST_F(TestGraphAPI, count_clients_and_services) { constexpr char service_name[] = "/test_service"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); diff --git a/test_rmw_implementation/test/test_init_options.cpp b/test_rmw_implementation/test/test_init_options.cpp index ec976d78..21dfef55 100644 --- a/test_rmw_implementation/test/test_init_options.cpp +++ b/test_rmw_implementation/test/test_init_options.cpp @@ -23,16 +23,7 @@ #include "./allocator_testing_utils.h" -#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 (TestInitOptions, RMW_IMPLEMENTATION) : public ::testing::Test {}; - -TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_copy_fini) { +TEST(TestInitOptions, init_copy_fini) { rmw_init_options_t src_options = rmw_get_zero_initialized_init_options(); rmw_ret_t ret = rmw_init_options_init(&src_options, rcutils_get_default_allocator()); ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; @@ -63,7 +54,7 @@ TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_copy_fini) { rcutils_reset_error(); } -TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_with_bad_arguments) { +TEST(TestInitOptions, init_with_bad_arguments) { rmw_init_options_t options = rmw_get_zero_initialized_init_options(); rmw_ret_t ret = rmw_init_options_init(&options, rcutils_get_zero_initialized_allocator()); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); @@ -80,7 +71,7 @@ TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_with_bad_arguments) EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; } -TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), copy_with_bad_arguments) { +TEST(TestInitOptions, copy_with_bad_arguments) { rmw_init_options_t src_options = rmw_get_zero_initialized_init_options(); rmw_init_options_t dst_options = rmw_get_zero_initialized_init_options(); @@ -118,7 +109,7 @@ TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), copy_with_bad_arguments) EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; } -TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), fini_with_bad_arguments) { +TEST(TestInitOptions, fini_with_bad_arguments) { rmw_init_options_t options = rmw_get_zero_initialized_init_options(); rmw_ret_t ret = rmw_init_options_fini(&options); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); diff --git a/test_rmw_implementation/test/test_init_shutdown.cpp b/test_rmw_implementation/test/test_init_shutdown.cpp index 01394400..1d7e61ec 100644 --- a/test_rmw_implementation/test/test_init_shutdown.cpp +++ b/test_rmw_implementation/test/test_init_shutdown.cpp @@ -26,14 +26,7 @@ #include "./testing_macros.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 (TestInitShutdown, RMW_IMPLEMENTATION) : public ::testing::Test +class TestInitShutdown : public ::testing::Test { protected: void SetUp() override @@ -54,7 +47,7 @@ class CLASSNAME (TestInitShutdown, RMW_IMPLEMENTATION) : public ::testing::Test rmw_init_options_t options; }; -TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_with_bad_arguments) { +TEST_F(TestInitShutdown, init_with_bad_arguments) { rmw_context_t context = rmw_get_zero_initialized_context(); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_init(nullptr, &context)); rcutils_reset_error(); @@ -87,7 +80,7 @@ TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_with_bad_arguments) EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; } -TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), shutdown_with_bad_arguments) { +TEST_F(TestInitShutdown, shutdown_with_bad_arguments) { rmw_ret_t ret = rmw_shutdown(nullptr); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rcutils_reset_error(); @@ -113,7 +106,7 @@ TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), shutdown_with_bad_argume EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; } -TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), context_fini_with_bad_arguments) { +TEST_F(TestInitShutdown, context_fini_with_bad_arguments) { rmw_ret_t ret = rmw_context_fini(nullptr); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rcutils_reset_error(); @@ -139,7 +132,7 @@ TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), context_fini_with_bad_ar EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; } -TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_shutdown) { +TEST_F(TestInitShutdown, init_shutdown) { rmw_context_t context = rmw_get_zero_initialized_context(); rmw_ret_t ret = rmw_init(&options, &context); ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; @@ -177,7 +170,7 @@ TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_shutdown) { EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str; } -TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_with_internal_errors) { +TEST_F(TestInitShutdown, init_with_internal_errors) { RCUTILS_FAULT_INJECTION_TEST( { rmw_context_t context = rmw_get_zero_initialized_context(); @@ -197,7 +190,7 @@ TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_with_internal_error }); } -TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), shutdown_with_internal_errors) { +TEST_F(TestInitShutdown, shutdown_with_internal_errors) { RCUTILS_FAULT_INJECTION_TEST( { rmw_ret_t ret = RMW_RET_OK; @@ -225,7 +218,7 @@ TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), shutdown_with_internal_e }); } -TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), context_fini_with_internal_errors) { +TEST_F(TestInitShutdown, context_fini_with_internal_errors) { RCUTILS_FAULT_INJECTION_TEST( { rmw_context_t context = rmw_get_zero_initialized_context(); diff --git a/test_rmw_implementation/test/test_publisher.cpp b/test_rmw_implementation/test/test_publisher.cpp index 97e1dc92..3354b46b 100644 --- a/test_rmw_implementation/test/test_publisher.cpp +++ b/test_rmw_implementation/test/test_publisher.cpp @@ -29,14 +29,7 @@ #include "./config.hpp" #include "./testing_macros.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 (TestPublisher, RMW_IMPLEMENTATION) : public ::testing::Test +class TestPublisher : public ::testing::Test { protected: void SetUp() override @@ -72,7 +65,7 @@ class CLASSNAME (TestPublisher, RMW_IMPLEMENTATION) : public ::testing::Test rmw_node_t * node; }; -TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_and_destroy) { +TEST_F(TestPublisher, create_and_destroy) { rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -84,7 +77,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_and_destroy) { EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_with_internal_errors) { +TEST_F(TestPublisher, create_with_internal_errors) { constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); @@ -106,7 +99,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_with_internal_errors }); } -TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_and_destroy_native) { +TEST_F(TestPublisher, create_and_destroy_native) { rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic_name[] = "test"; const rosidl_message_type_support_t * ts = @@ -120,7 +113,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_and_destroy_native) EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_with_bad_arguments) { +TEST_F(TestPublisher, create_with_bad_arguments) { rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -187,7 +180,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_with_bad_arguments) EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_bad_arguments) { +TEST_F(TestPublisher, destroy_with_bad_arguments) { rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -218,7 +211,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_bad_arguments) rmw_reset_error(); } -TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_internal_errors) { +TEST_F(TestPublisher, destroy_with_internal_errors) { constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); @@ -238,7 +231,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_internal_error }); } -TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), get_actual_qos_from_system_defaults) { +TEST_F(TestPublisher, get_actual_qos_from_system_defaults) { rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -262,15 +255,12 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), get_actual_qos_from_system_ EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -class CLASSNAME (TestPublisherUse, RMW_IMPLEMENTATION) - : public CLASSNAME(TestPublisher, RMW_IMPLEMENTATION) +class TestPublisherUse : public TestPublisher { protected: - using Base = CLASSNAME(TestPublisher, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestPublisher::SetUp(); // Relax QoS policies to force mismatch. qos_profile.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; rmw_publisher_options_t options = rmw_get_default_publisher_options(); @@ -282,7 +272,7 @@ class CLASSNAME (TestPublisherUse, RMW_IMPLEMENTATION) { rmw_ret_t ret = rmw_destroy_publisher(node, pub); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestPublisher::TearDown(); } rmw_publisher_t * pub{nullptr}; @@ -292,7 +282,7 @@ class CLASSNAME (TestPublisherUse, RMW_IMPLEMENTATION) rmw_qos_profile_t qos_profile{rmw_qos_profile_default}; }; -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos_with_bad_arguments) { +TEST_F(TestPublisherUse, get_actual_qos_with_bad_arguments) { rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; rmw_ret_t ret = rmw_publisher_get_actual_qos(nullptr, &actual_qos_profile); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); @@ -310,7 +300,7 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos_with_bad_ rmw_reset_error(); } -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos) { +TEST_F(TestPublisherUse, get_actual_qos) { rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; rmw_ret_t ret = rmw_publisher_get_actual_qos(pub, &actual_qos_profile); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; @@ -320,7 +310,7 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos) { EXPECT_EQ(qos_profile.durability, actual_qos_profile.durability); } -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), count_matched_subscriptions_with_bad_args) { +TEST_F(TestPublisherUse, count_matched_subscriptions_with_bad_args) { size_t subscription_count = 0u; rmw_ret_t ret = rmw_publisher_count_matched_subscriptions(nullptr, &subscription_count); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); @@ -338,7 +328,7 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), count_matched_subscripti rmw_reset_error(); } -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), count_matched_subscriptions) { +TEST_F(TestPublisherUse, count_matched_subscriptions) { osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_ret_t ret; @@ -388,7 +378,7 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), count_matched_subscripti EXPECT_EQ(0u, subscription_count); } -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), count_mismatched_subscriptions) { +TEST_F(TestPublisherUse, count_mismatched_subscriptions) { osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_ret_t ret; @@ -433,9 +423,7 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), count_mismatched_subscri EXPECT_EQ(0u, subscription_count); } -TEST_F( - CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), - publish_message_with_bad_arguments) { +TEST_F(TestPublisherUse, publish_message_with_bad_arguments) { test_msgs__msg__BasicTypes input_message{}; ASSERT_TRUE(test_msgs__msg__BasicTypes__init(&input_message)); rmw_publisher_allocation_t * null_allocation{nullptr}; // still valid allocation @@ -458,7 +446,7 @@ TEST_F( test_msgs__msg__BasicTypes__fini(&input_message); } -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), publish_with_internal_errors) { +TEST_F(TestPublisherUse, publish_with_internal_errors) { test_msgs__msg__BasicTypes message{}; ASSERT_TRUE(test_msgs__msg__BasicTypes__init(&message)); rmw_publisher_allocation_t * null_allocation{nullptr}; // still a valid allocation @@ -472,9 +460,7 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), publish_with_internal_er }); } -TEST_F( - CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), - publish_serialized_message_with_bad_arguments) { +TEST_F(TestPublisherUse, publish_serialized_message_with_bad_arguments) { rmw_publisher_allocation_t * null_allocation{nullptr}; // still valid allocation rcutils_allocator_t default_allocator = rcutils_get_default_allocator(); rmw_serialized_message_t serialized_message = rmw_get_zero_initialized_serialized_message(); @@ -501,7 +487,7 @@ TEST_F( RMW_RET_OK, rmw_serialized_message_fini(&serialized_message)) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), publish_serialized_with_internal_errors) { +TEST_F(TestPublisherUse, publish_serialized_with_internal_errors) { test_msgs__msg__BasicTypes message{}; ASSERT_TRUE(test_msgs__msg__BasicTypes__init(&message)); rcutils_allocator_t default_allocator = rcutils_get_default_allocator(); @@ -527,8 +513,8 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), publish_serialized_with_ }); } -TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), wait_for_all_acked_with_best_effort) { - // For best effort, alway return RMW_RET_OK immediately +TEST_F(TestPublisherUse, wait_for_all_acked_with_best_effort) { + // For best effort, always return RMW_RET_OK immediately rmw_ret_t ret = rmw_publisher_wait_for_all_acked(pub, {0, 0}); EXPECT_EQ(ret, RMW_RET_OK); @@ -537,15 +523,12 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), wait_for_all_acked_with_ } -class CLASSNAME (TestPublisherUseLoan, RMW_IMPLEMENTATION) - : public CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION) +class TestPublisherUseLoan : public TestPublisherUse { protected: - using Base = CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestPublisherUse::SetUp(); // Check if loaning is supported by the implementation if (!pub->can_loan_messages) { void * msg_pointer = nullptr; @@ -568,13 +551,11 @@ class CLASSNAME (TestPublisherUseLoan, RMW_IMPLEMENTATION) void TearDown() override { - Base::TearDown(); + TestPublisherUse::TearDown(); } }; -TEST_F( - CLASSNAME(TestPublisherUseLoan, RMW_IMPLEMENTATION), - borrow_loaned_message_with_bad_arguments) { +TEST_F(TestPublisherUseLoan, borrow_loaned_message_with_bad_arguments) { void * msg_pointer = nullptr; rmw_ret_t ret = rmw_borrow_loaned_message(nullptr, ts, &msg_pointer); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret) << rmw_get_error_string().str; diff --git a/test_rmw_implementation/test/test_publisher_allocator.cpp b/test_rmw_implementation/test/test_publisher_allocator.cpp index 51b6b18c..00359e7d 100644 --- a/test_rmw_implementation/test/test_publisher_allocator.cpp +++ b/test_rmw_implementation/test/test_publisher_allocator.cpp @@ -15,16 +15,7 @@ #include "rmw/rmw.h" -#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 (TestPublisherAllocator, RMW_IMPLEMENTATION) : public ::testing::Test {}; - -TEST_F(CLASSNAME(TestPublisherAllocator, RMW_IMPLEMENTATION), init_fini_publisher_allocation) +TEST(TestPublisherAllocator, init_fini_publisher_allocation) { if (rmw_init_publisher_allocation(nullptr, nullptr, nullptr) != RMW_RET_UNSUPPORTED) { // Add tests here when the implementation it's supported diff --git a/test_rmw_implementation/test/test_qos_profile_check_compatible.cpp b/test_rmw_implementation/test/test_qos_profile_check_compatible.cpp index 1f710272..9d4b1280 100644 --- a/test_rmw_implementation/test/test_qos_profile_check_compatible.cpp +++ b/test_rmw_implementation/test/test_qos_profile_check_compatible.cpp @@ -16,14 +16,7 @@ #include "rmw/qos_profiles.h" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -TEST(CLASSNAME(TestQoSProfilesAreCompatible, RMW_IMPLEMENTATION), compatible) { +TEST(TestQoSProfilesAreCompatible, compatible) { // A profile without system default or unknown values should be compatible with itself rmw_qos_profile_t qos = { RMW_QOS_POLICY_HISTORY_KEEP_LAST, @@ -44,7 +37,7 @@ TEST(CLASSNAME(TestQoSProfilesAreCompatible, RMW_IMPLEMENTATION), compatible) { EXPECT_EQ(compatible, RMW_QOS_COMPATIBILITY_OK); } -TEST(CLASSNAME(TestQoSProfilesAreCompatible, RMW_IMPLEMENTATION), invalid_input) { +TEST(TestQoSProfilesAreCompatible, invalid_input) { // Error on null 'compatible' parameter { rmw_ret_t ret = rmw_qos_profile_check_compatible( diff --git a/test_rmw_implementation/test/test_serialize_deserialize.cpp b/test_rmw_implementation/test/test_serialize_deserialize.cpp index 53022291..e40e15ac 100644 --- a/test_rmw_implementation/test/test_serialize_deserialize.cpp +++ b/test_rmw_implementation/test/test_serialize_deserialize.cpp @@ -33,24 +33,13 @@ #include "./allocator_testing_utils.h" -#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 (TestSerializeDeserialize, RMW_IMPLEMENTATION) : public ::testing::Test -{ -}; - -TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), get_serialization_format) { +TEST(TestSerializeDeserialize, get_serialization_format) { const char * serialization_format = rmw_get_serialization_format(); EXPECT_NE(nullptr, serialization_format); EXPECT_STREQ(serialization_format, rmw_get_serialization_format()); } -TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), serialize_with_bad_arguments) { +TEST(TestSerializeDeserialize, serialize_with_bad_arguments) { const rosidl_message_type_support_t * ts{ ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes)}; test_msgs__msg__BasicTypes input_message{}; @@ -86,7 +75,7 @@ TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), serialize_with_b rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), clean_round_trip_for_c_message) { +TEST(TestSerializeDeserialize, clean_round_trip_for_c_message) { const rosidl_message_type_support_t * ts{ ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes)}; test_msgs__msg__BasicTypes input_message{}; @@ -119,10 +108,7 @@ TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), clean_round_trip rmw_get_error_string().str; } -TEST_F( - CLASSNAME( - TestSerializeDeserialize, - RMW_IMPLEMENTATION), clean_round_trip_for_c_bounded_message) { +TEST(TestSerializeDeserialize, clean_round_trip_for_c_bounded_message) { const rosidl_message_type_support_t * ts{ ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BoundedPlainSequences)}; test_msgs__msg__BoundedPlainSequences input_message{}; @@ -185,7 +171,7 @@ TEST_F( EXPECT_EQ(input_message.uint16_values.data[0], output_message.uint16_values.data[0]); } -TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), clean_round_trip_for_cpp_message) { +TEST(TestSerializeDeserialize, clean_round_trip_for_cpp_message) { const rosidl_message_type_support_t * ts = rosidl_typesupport_cpp::get_message_type_support_handle(); test_msgs::msg::BasicTypes input_message{}; @@ -214,10 +200,7 @@ TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), clean_round_trip rmw_get_error_string().str; } -TEST_F( - CLASSNAME( - TestSerializeDeserialize, - RMW_IMPLEMENTATION), clean_round_trip_for_cpp_bounded_message) { +TEST(TestSerializeDeserialize, clean_round_trip_for_cpp_bounded_message) { using TestMessage = test_msgs::msg::BoundedPlainSequences; const rosidl_message_type_support_t * ts = rosidl_typesupport_cpp::get_message_type_support_handle(); @@ -261,7 +244,7 @@ TEST_F( EXPECT_EQ(input_message, output_message); } -TEST_F(CLASSNAME(TestSerializeDeserialize, RMW_IMPLEMENTATION), rmw_get_serialized_message_size) +TEST(TestSerializeDeserialize, rmw_get_serialized_message_size) { if (rmw_get_serialized_message_size(nullptr, nullptr, nullptr) != RMW_RET_UNSUPPORTED) { // TODO(anyone): Add tests here when the implementation it's supported diff --git a/test_rmw_implementation/test/test_service.cpp b/test_rmw_implementation/test/test_service.cpp index cbb763b3..f0e21bfe 100644 --- a/test_rmw_implementation/test/test_service.cpp +++ b/test_rmw_implementation/test/test_service.cpp @@ -29,14 +29,7 @@ #include "./config.hpp" #include "./testing_macros.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 (TestService, RMW_IMPLEMENTATION) : public ::testing::Test +class TestService : public ::testing::Test { protected: void SetUp() override @@ -73,7 +66,7 @@ class CLASSNAME (TestService, RMW_IMPLEMENTATION) : public ::testing::Test rmw_node_t * node{nullptr}; }; -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_and_destroy) { +TEST_F(TestService, create_and_destroy) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -84,7 +77,7 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_and_destroy) { EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_and_destroy_native) { +TEST_F(TestService, create_and_destroy_native) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -97,7 +90,7 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_and_destroy_native) { EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_with_bad_arguments) { +TEST_F(TestService, create_with_bad_arguments) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -161,7 +154,7 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_with_bad_arguments) { } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_with_internal_errors) { +TEST_F(TestService, create_with_internal_errors) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -180,7 +173,7 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_with_internal_errors) }); } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), destroy_with_internal_errors) { +TEST_F(TestService, destroy_with_internal_errors) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -198,15 +191,12 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), destroy_with_internal_errors) }); } -class CLASSNAME (TestServiceUse, RMW_IMPLEMENTATION) - : public CLASSNAME(TestService, RMW_IMPLEMENTATION) +class TestServiceUse : public TestService { protected: - using Base = CLASSNAME(TestService, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestService::SetUp(); constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -218,25 +208,25 @@ class CLASSNAME (TestServiceUse, RMW_IMPLEMENTATION) { rmw_ret_t ret = rmw_destroy_service(node, srv); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestService::TearDown(); } rmw_service_t * srv{nullptr}; }; -TEST_F(CLASSNAME(TestServiceUse, RMW_IMPLEMENTATION), destroy_with_null_node) { +TEST_F(TestServiceUse, destroy_with_null_node) { rmw_ret_t ret = rmw_destroy_service(nullptr, srv); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rmw_reset_error(); } -TEST_F(CLASSNAME(TestServiceUse, RMW_IMPLEMENTATION), destroy_null_service) { +TEST_F(TestServiceUse, destroy_null_service) { rmw_ret_t ret = rmw_destroy_service(node, nullptr); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rmw_reset_error(); } -TEST_F(CLASSNAME(TestServiceUse, RMW_IMPLEMENTATION), destroy_with_node_of_another_impl) { +TEST_F(TestServiceUse, destroy_with_node_of_another_impl) { const char * implementation_identifier = node->implementation_identifier; node->implementation_identifier = "not-an-rmw-implementation-identifier"; rmw_ret_t ret = rmw_destroy_service(node, srv); @@ -245,7 +235,7 @@ TEST_F(CLASSNAME(TestServiceUse, RMW_IMPLEMENTATION), destroy_with_node_of_anoth rmw_reset_error(); } -TEST_F(CLASSNAME(TestServiceUse, RMW_IMPLEMENTATION), destroy_service_of_another_impl) { +TEST_F(TestServiceUse, destroy_service_of_another_impl) { const char * implementation_identifier = srv->implementation_identifier; srv->implementation_identifier = "not-an-rmw-implementation-identifier"; rmw_ret_t ret = rmw_destroy_service(node, srv); @@ -254,7 +244,7 @@ TEST_F(CLASSNAME(TestServiceUse, RMW_IMPLEMENTATION), destroy_service_of_another rmw_reset_error(); } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), take_request_with_bad_arguments) { +TEST_F(TestService, take_request_with_bad_arguments) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -317,7 +307,7 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), take_request_with_bad_argumen rmw_reset_error(); } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), send_reponse_with_bad_arguments) { +TEST_F(TestService, send_reponse_with_bad_arguments) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -420,7 +410,7 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), send_reponse_with_bad_argumen srv->implementation_identifier = implementation_identifier; } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), send_reponse_with_client_gone) { +TEST_F(TestService, send_reponse_with_client_gone) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -516,7 +506,7 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), send_reponse_with_client_gone EXPECT_EQ(RMW_RET_OK, ret); } -TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), check_qos) { +TEST_F(TestService, check_qos) { constexpr char service_name[] = "/test"; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); diff --git a/test_rmw_implementation/test/test_subscription.cpp b/test_rmw_implementation/test/test_subscription.cpp index 38e54db3..033dfd8a 100644 --- a/test_rmw_implementation/test/test_subscription.cpp +++ b/test_rmw_implementation/test/test_subscription.cpp @@ -34,16 +34,9 @@ #include "rmw_dds_common/gid_utils.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 rmw_dds_common::operator==; -class CLASSNAME (TestSubscription, RMW_IMPLEMENTATION) : public ::testing::Test +class TestSubscription : public ::testing::Test { protected: void SetUp() override @@ -77,7 +70,7 @@ class CLASSNAME (TestSubscription, RMW_IMPLEMENTATION) : public ::testing::Test rmw_node_t * node{nullptr}; }; -TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_and_destroy) { +TEST_F(TestSubscription, create_and_destroy) { rmw_subscription_options_t options = rmw_get_default_subscription_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -89,7 +82,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_and_destroy) { EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_and_destroy_native) { +TEST_F(TestSubscription, create_and_destroy_native) { rmw_subscription_options_t options = rmw_get_default_subscription_options(); constexpr char topic_name[] = "test"; const rosidl_message_type_support_t * ts = @@ -103,7 +96,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_and_destroy_nativ EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_with_bad_arguments) { +TEST_F(TestSubscription, create_with_bad_arguments) { rmw_subscription_options_t options = rmw_get_default_subscription_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -173,7 +166,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_with_bad_argument EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_with_internal_errors) { +TEST_F(TestSubscription, create_with_internal_errors) { constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); @@ -195,7 +188,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), create_with_internal_err }); } -TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), destroy_with_bad_arguments) { +TEST_F(TestSubscription, destroy_with_bad_arguments) { rmw_subscription_options_t options = rmw_get_default_subscription_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -226,7 +219,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), destroy_with_bad_argumen rmw_reset_error(); } -TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), destroy_with_internal_errors) { +TEST_F(TestSubscription, destroy_with_internal_errors) { constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); @@ -246,7 +239,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), destroy_with_internal_er }); } -TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), get_actual_qos_from_system_defaults) { +TEST_F(TestSubscription, get_actual_qos_from_system_defaults) { rmw_subscription_options_t options = rmw_get_default_subscription_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -272,15 +265,12 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), get_actual_qos_from_syst EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -class CLASSNAME (TestSubscriptionUse, RMW_IMPLEMENTATION) - : public CLASSNAME(TestSubscription, RMW_IMPLEMENTATION) +class TestSubscriptionUse : public TestSubscription { protected: - using Base = CLASSNAME(TestSubscription, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestSubscription::SetUp(); // Tighten QoS policies to force mismatch. qos_profile.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; rmw_subscription_options_t options = rmw_get_default_subscription_options(); @@ -292,7 +282,7 @@ class CLASSNAME (TestSubscriptionUse, RMW_IMPLEMENTATION) { rmw_ret_t ret = rmw_destroy_subscription(node, sub); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestSubscription::TearDown(); } rmw_subscription_t * sub{nullptr}; @@ -302,7 +292,7 @@ class CLASSNAME (TestSubscriptionUse, RMW_IMPLEMENTATION) rmw_qos_profile_t qos_profile{rmw_qos_profile_default}; }; -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos_with_bad_arguments) { +TEST_F(TestSubscriptionUse, get_actual_qos_with_bad_arguments) { rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; rmw_ret_t ret = rmw_subscription_get_actual_qos(nullptr, &actual_qos_profile); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); @@ -320,7 +310,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos_with_b sub->implementation_identifier = implementation_identifier; } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos) { +TEST_F(TestSubscriptionUse, get_actual_qos) { rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; rmw_ret_t ret = rmw_subscription_get_actual_qos(sub, &actual_qos_profile); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; @@ -330,7 +320,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos) { EXPECT_EQ(qos_profile.durability, actual_qos_profile.durability); } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), count_matched_publishers_with_bad_args) { +TEST_F(TestSubscriptionUse, count_matched_publishers_with_bad_args) { size_t publisher_count = 0u; rmw_ret_t ret = rmw_subscription_count_matched_publishers(nullptr, &publisher_count); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); @@ -348,7 +338,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), count_matched_publish rmw_reset_error(); } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), count_matched_subscriptions) { +TEST_F(TestSubscriptionUse, count_matched_subscriptions) { osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_ret_t ret; @@ -398,7 +388,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), count_matched_subscri EXPECT_EQ(0u, publisher_count); } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), count_mismatched_subscriptions) { +TEST_F(TestSubscriptionUse, count_mismatched_subscriptions) { osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_ret_t ret; @@ -444,7 +434,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), count_mismatched_subs EXPECT_EQ(0u, publisher_count); } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_with_bad_args) { +TEST_F(TestSubscriptionUse, take_with_bad_args) { bool taken = false; test_msgs__msg__BasicTypes output_message{}; output_message.bool_value = true; @@ -479,7 +469,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_with_bad_args) { sub->implementation_identifier = implementation_identifier; } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_with_info_with_bad_args) { +TEST_F(TestSubscriptionUse, take_with_info_with_bad_args) { bool taken = false; test_msgs__msg__BasicTypes output_message{}; output_message.bool_value = true; @@ -528,7 +518,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_with_info_with_b sub->implementation_identifier = implementation_identifier; } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), ignore_local_publications) { +TEST_F(TestSubscriptionUse, ignore_local_publications) { rmw_ret_t ret; bool taken = false; @@ -629,7 +619,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), ignore_local_publicat } } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_sequence) { +TEST_F(TestSubscriptionUse, take_sequence) { size_t count = 1u; size_t taken = 10u; // Non-zero value to check variable update rcutils_allocator_t allocator = rcutils_get_default_allocator(); @@ -660,7 +650,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_sequence) { test_msgs__msg__Strings__Sequence__destroy(seq); } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_sequence_with_bad_args) { +TEST_F(TestSubscriptionUse, take_sequence_with_bad_args) { size_t count = 1u; size_t taken = 0u; rcutils_allocator_t allocator = rcutils_get_default_allocator(); @@ -770,7 +760,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_sequence_with_ba EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_serialized_with_bad_args) { +TEST_F(TestSubscriptionUse, take_serialized_with_bad_args) { rmw_subscription_allocation_t * null_allocation{nullptr}; // still valid allocation rcutils_allocator_t default_allocator = rcutils_get_default_allocator(); bool taken = false; @@ -825,9 +815,7 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), take_serialized_with_ RMW_RET_OK, rmw_serialized_message_fini(&original_message)) << rmw_get_error_string().str; } -TEST_F( - CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), - take_serialized_with_info_with_bad_args) { +TEST_F(TestSubscriptionUse, take_serialized_with_info_with_bad_args) { rmw_subscription_allocation_t * null_allocation{nullptr}; // still valid allocation rcutils_allocator_t default_allocator = rcutils_get_default_allocator(); bool taken = false; @@ -874,14 +862,14 @@ TEST_F( RMW_RET_OK, rmw_serialized_message_fini(&serialized_message)) << rmw_get_error_string().str; } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), no_content_filter_get) { +TEST_F(TestSubscriptionUse, no_content_filter_get) { rmw_subscription_content_filter_options_t options; auto allocator = rcutils_get_default_allocator(); rmw_ret_t ret = rmw_subscription_get_content_filter(sub, &allocator, &options); EXPECT_NE(RMW_RET_OK, ret); } -TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), no_content_filter_set) { +TEST_F(TestSubscriptionUse, no_content_filter_set) { rmw_ret_t ret; bool taken = false; @@ -1013,15 +1001,12 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), no_content_filter_set } } -class CLASSNAME (TestSubscriptionUseLoan, RMW_IMPLEMENTATION) - : public CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION) +class TestSubscriptionUseLoan : public TestSubscriptionUse { protected: - using Base = CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestSubscriptionUse::SetUp(); // Check if loaning is supported by the implementation if (!sub->can_loan_messages) { bool taken = false; @@ -1047,11 +1032,11 @@ class CLASSNAME (TestSubscriptionUseLoan, RMW_IMPLEMENTATION) void TearDown() override { - Base::TearDown(); + TestSubscriptionUse::TearDown(); } }; -TEST_F(CLASSNAME(TestSubscriptionUseLoan, RMW_IMPLEMENTATION), rmw_take_loaned_message) { +TEST_F(TestSubscriptionUseLoan, rmw_take_loaned_message) { bool taken = false; void * loaned_message = nullptr; rmw_subscription_allocation_t * null_allocation{nullptr}; // still valid allocation @@ -1087,7 +1072,7 @@ TEST_F(CLASSNAME(TestSubscriptionUseLoan, RMW_IMPLEMENTATION), rmw_take_loaned_m } TEST_F( - CLASSNAME(TestSubscriptionUseLoan, RMW_IMPLEMENTATION), rmw_take_loaned_message_with_info) { + TestSubscriptionUseLoan, rmw_take_loaned_message_with_info) { bool taken = false; void * loaned_message = nullptr; rmw_message_info_t message_info = rmw_get_zero_initialized_message_info(); @@ -1135,9 +1120,7 @@ TEST_F( sub->implementation_identifier = implementation_identifier; } -TEST_F( - CLASSNAME(TestSubscriptionUseLoan, RMW_IMPLEMENTATION), - rmw_return_loaned_message_from_subscription) { +TEST_F(TestSubscriptionUseLoan, rmw_return_loaned_message_from_subscription) { test_msgs__msg__BasicTypes msg{}; rmw_ret_t ret = rmw_return_loaned_message_from_subscription(nullptr, &msg); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret) << rmw_get_error_string().str; @@ -1185,15 +1168,12 @@ bool operator==(const rmw_message_info_t & m1, const rmw_message_info_t & m2) m1.from_intra_process == m2.from_intra_process; } -class CLASSNAME (TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION) - : public CLASSNAME(TestSubscription, RMW_IMPLEMENTATION) +class TestContentFilterSubscriptionUse : public TestSubscription { protected: - using Base = CLASSNAME(TestSubscription, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestSubscription::SetUp(); // Tighten QoS policies to force mismatch. qos_profile.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; rmw_subscription_options_t options = rmw_get_default_subscription_options(); @@ -1234,7 +1214,7 @@ class CLASSNAME (TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION) { rmw_ret_t ret = rmw_destroy_subscription(node, sub); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestSubscription::TearDown(); } rmw_subscription_t * sub{nullptr}; @@ -1252,7 +1232,7 @@ class CLASSNAME (TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION) }; }; -TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), get_content_filter) { +TEST_F(TestContentFilterSubscriptionUse, get_content_filter) { rmw_subscription_content_filter_options_t options; auto allocator = rcutils_get_default_allocator(); rmw_ret_t ret = rmw_subscription_get_content_filter(sub, &allocator, &options); @@ -1273,7 +1253,7 @@ TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), get_cont } } -TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), set_content_filter) { +TEST_F(TestContentFilterSubscriptionUse, set_content_filter) { rmw_subscription_content_filter_options_t options = rmw_get_zero_initialized_content_filter_options(); auto allocator = rcutils_get_default_allocator(); @@ -1300,7 +1280,7 @@ TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), set_cont } } -TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), content_filter_get_begin) { +TEST_F(TestContentFilterSubscriptionUse, content_filter_get_begin) { rmw_ret_t ret; bool taken = false; @@ -1436,7 +1416,7 @@ TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), content_ } } -TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), content_filter_get_later) { +TEST_F(TestContentFilterSubscriptionUse, content_filter_get_later) { rmw_ret_t ret; bool taken = false; @@ -1582,7 +1562,7 @@ TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), content_ } } -TEST_F(CLASSNAME(TestContentFilterSubscriptionUse, RMW_IMPLEMENTATION), content_filter_reset) { +TEST_F(TestContentFilterSubscriptionUse, content_filter_reset) { rmw_ret_t ret; bool taken = false; diff --git a/test_rmw_implementation/test/test_subscription_allocator.cpp b/test_rmw_implementation/test/test_subscription_allocator.cpp index 9ee0b34c..2e3f59d8 100644 --- a/test_rmw_implementation/test/test_subscription_allocator.cpp +++ b/test_rmw_implementation/test/test_subscription_allocator.cpp @@ -15,16 +15,7 @@ #include "rmw/rmw.h" -#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 (TestSubscriptionAllocator, RMW_IMPLEMENTATION) : public ::testing::Test {}; - -TEST_F(CLASSNAME(TestSubscriptionAllocator, RMW_IMPLEMENTATION), init_fini_subscription_allocation) +TEST(TestSubscriptionAllocator, init_fini_subscription_allocation) { if (rmw_init_subscription_allocation(nullptr, nullptr, nullptr) != RMW_RET_UNSUPPORTED) { // Add tests here when the implementation it's supported diff --git a/test_rmw_implementation/test/test_unique_identifiers.cpp b/test_rmw_implementation/test/test_unique_identifiers.cpp index 1a5dfe1e..14bbfc19 100644 --- a/test_rmw_implementation/test/test_unique_identifiers.cpp +++ b/test_rmw_implementation/test/test_unique_identifiers.cpp @@ -25,15 +25,7 @@ #include "test_msgs/msg/basic_types.h" #include "test_msgs/srv/basic_types.h" - -#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 (TestUniqueIdentifierAPI, RMW_IMPLEMENTATION) : public ::testing::Test +class TestUniqueIdentifierAPI : public ::testing::Test { protected: void SetUp() override @@ -89,7 +81,7 @@ class CLASSNAME (TestUniqueIdentifierAPI, RMW_IMPLEMENTATION) : public ::testing rmw_client_t * client{nullptr}; }; -TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), get_pub_gid_with_bad_args) { +TEST_F(TestUniqueIdentifierAPI, get_pub_gid_with_bad_args) { rmw_gid_t gid{}; rmw_ret_t ret = rmw_get_gid_for_publisher(pub, &gid); ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; @@ -124,7 +116,7 @@ TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), get_pub_gid_with_ } -TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), get_client_gid_with_bad_args) { +TEST_F(TestUniqueIdentifierAPI, get_client_gid_with_bad_args) { rmw_gid_t gid{}; rmw_ret_t ret = rmw_get_gid_for_client(client, &gid); ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; @@ -158,7 +150,7 @@ TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), get_client_gid_wi EXPECT_TRUE(gids_are_equal); } -TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), compare_gids_with_bad_args) { +TEST_F(TestUniqueIdentifierAPI, compare_gids_with_bad_args) { rmw_gid_t gid{}; rmw_ret_t ret = rmw_get_gid_for_publisher(pub, &gid); ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; @@ -192,7 +184,7 @@ TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), compare_gids_with rmw_reset_error(); } -TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), compare_gids) { +TEST_F(TestUniqueIdentifierAPI, compare_gids) { rmw_gid_t gid{}; rmw_ret_t ret = rmw_get_gid_for_publisher(pub, &gid); ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; @@ -209,14 +201,12 @@ TEST_F(CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION), compare_gids) { EXPECT_TRUE(are_equal); } -class CLASSNAME (TestUniqueIdentifiersForMultiplePublishers, RMW_IMPLEMENTATION) - : public CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION) +class TestUniqueIdentifiersForMultiplePublishers : public TestUniqueIdentifierAPI { protected: - using Base = CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION); void SetUp() override { - Base::SetUp(); + TestUniqueIdentifierAPI::SetUp(); rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic1_name[] = "/test0"; first_pub_for_topic1 = rmw_create_publisher( @@ -234,7 +224,7 @@ class CLASSNAME (TestUniqueIdentifiersForMultiplePublishers, RMW_IMPLEMENTATION) EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; ret = rmw_destroy_publisher(node, first_pub_for_topic1); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestUniqueIdentifierAPI::TearDown(); } rmw_publisher_t * first_pub_for_topic1{nullptr}; @@ -242,7 +232,7 @@ class CLASSNAME (TestUniqueIdentifiersForMultiplePublishers, RMW_IMPLEMENTATION) rmw_publisher_t * pub_for_topic0{nullptr}; }; -TEST_F(CLASSNAME(TestUniqueIdentifiersForMultiplePublishers, RMW_IMPLEMENTATION), different_pubs) { +TEST_F(TestUniqueIdentifiersForMultiplePublishers, different_pubs) { rmw_gid_t gid_of_pub_for_topic0{}; rmw_ret_t ret = rmw_get_gid_for_publisher(pub_for_topic0, &gid_of_pub_for_topic0); ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; @@ -268,14 +258,12 @@ TEST_F(CLASSNAME(TestUniqueIdentifiersForMultiplePublishers, RMW_IMPLEMENTATION) } -class CLASSNAME (TestUniqueIdentifiersForMultipleClients, RMW_IMPLEMENTATION) - : public CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION) +class TestUniqueIdentifiersForMultipleClients : public TestUniqueIdentifierAPI { protected: - using Base = CLASSNAME(TestUniqueIdentifierAPI, RMW_IMPLEMENTATION); void SetUp() override { - Base::SetUp(); + TestUniqueIdentifierAPI::SetUp(); constexpr char service_name[] = "/test_service1"; first_client_for_service1 = rmw_create_client( node, srv_ts, service_name, &qos_profile); @@ -292,7 +280,7 @@ class CLASSNAME (TestUniqueIdentifiersForMultipleClients, RMW_IMPLEMENTATION) EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; ret = rmw_destroy_client(node, second_client_for_service1); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestUniqueIdentifierAPI::TearDown(); } rmw_client_t * client_for_service0{nullptr}; @@ -301,7 +289,7 @@ class CLASSNAME (TestUniqueIdentifiersForMultipleClients, RMW_IMPLEMENTATION) }; -TEST_F(CLASSNAME(TestUniqueIdentifiersForMultipleClients, RMW_IMPLEMENTATION), different_clis) { +TEST_F(TestUniqueIdentifiersForMultipleClients, different_clis) { rmw_gid_t gid_of_client_for_service0{}; rmw_ret_t ret = rmw_get_gid_for_client(client_for_service0, &gid_of_client_for_service0); ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; diff --git a/test_rmw_implementation/test/test_wait_set.cpp b/test_rmw_implementation/test/test_wait_set.cpp index 5e9b01ee..3e656604 100644 --- a/test_rmw_implementation/test/test_wait_set.cpp +++ b/test_rmw_implementation/test/test_wait_set.cpp @@ -27,14 +27,7 @@ #include "test_msgs/msg/basic_types.h" #include "test_msgs/srv/basic_types.h" -#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 (TestWaitSet, RMW_IMPLEMENTATION) : public ::testing::Test +class TestWaitSet : public ::testing::Test { protected: void SetUp() override @@ -65,7 +58,7 @@ class CLASSNAME (TestWaitSet, RMW_IMPLEMENTATION) : public ::testing::Test rmw_context_t context; }; -TEST_F(CLASSNAME(TestWaitSet, RMW_IMPLEMENTATION), rmw_create_wait_set) +TEST_F(TestWaitSet, rmw_create_wait_set) { // Created a valid wait_set rmw_wait_set_t * wait_set = rmw_create_wait_set(&context, 0); @@ -98,15 +91,12 @@ TEST_F(CLASSNAME(TestWaitSet, RMW_IMPLEMENTATION), rmw_create_wait_set) }); } -class CLASSNAME (TestWaitSetUse, RMW_IMPLEMENTATION) - : public CLASSNAME(TestWaitSet, RMW_IMPLEMENTATION) +class TestWaitSetUse : public TestWaitSet { protected: - using Base = CLASSNAME(TestWaitSet, RMW_IMPLEMENTATION); - void SetUp() override { - Base::SetUp(); + TestWaitSet::SetUp(); constexpr char node_name[] = "my_node"; constexpr char node_namespace[] = "/my_ns"; node = rmw_create_node(&context, node_name, node_namespace); @@ -145,7 +135,7 @@ class CLASSNAME (TestWaitSetUse, RMW_IMPLEMENTATION) EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; ret = rmw_destroy_node(node); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; - Base::TearDown(); + TestWaitSet::TearDown(); } rmw_node_t * node{nullptr}; @@ -163,7 +153,7 @@ class CLASSNAME (TestWaitSetUse, RMW_IMPLEMENTATION) var_name.internal_var_name ## s = var_name ## _storage; \ var_name.internal_var_name ## _count = size; -TEST_F(CLASSNAME(TestWaitSetUse, RMW_IMPLEMENTATION), rmw_wait) +TEST_F(TestWaitSetUse, rmw_wait) { constexpr size_t number_of_subscriptions = 1u; constexpr size_t number_of_guard_conditions = 1u; @@ -390,7 +380,7 @@ TEST_F(CLASSNAME(TestWaitSetUse, RMW_IMPLEMENTATION), rmw_wait) }); } -TEST_F(CLASSNAME(TestWaitSet, RMW_IMPLEMENTATION), rmw_destroy_wait_set) +TEST_F(TestWaitSet, rmw_destroy_wait_set) { // Try to destroy a nullptr rmw_ret_t ret = rmw_destroy_wait_set(nullptr);