diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 1d928ce57..1babe7c96 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -42,88 +42,190 @@ endif() # prevents finding it repeatedly in each local scope ament_find_gtest() -macro(test_target) - find_package(${rmw_implementation} REQUIRED) - test_target_function() -endmacro() +ament_add_gtest_executable(test_client + rcl/test_client.cpp +) +target_link_libraries(test_client ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_timer + rcl/test_timer.cpp +) +target_link_libraries(test_timer ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_context + rcl/test_context.cpp +) +target_link_libraries(test_context ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_get_node_names + rcl/test_get_node_names.cpp +) +target_link_libraries(test_get_node_names ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_graph + rcl/test_graph.cpp +) +target_link_libraries(test_graph ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) -function(test_target_function) +ament_add_gtest_executable(test_info_by_topic + rcl/test_info_by_topic.cpp +) +target_link_libraries(test_info_by_topic ${PROJECT_NAME} wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_count_matched + rcl/test_count_matched.cpp +) +target_link_libraries(test_count_matched ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_get_actual_qos + rcl/test_get_actual_qos.cpp +) +target_link_libraries(test_get_actual_qos ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + + +ament_add_gtest_executable(test_init + rcl/test_init.cpp +) +target_link_libraries(test_init ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_node + rcl/test_node.cpp +) +target_link_libraries(test_node ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_remap + rcl/test_remap.cpp +) +target_include_directories(test_remap PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/) +target_link_libraries(test_remap ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_remap_integration + rcl/test_remap_integration.cpp +) +target_link_libraries(test_remap_integration ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_guard_condition + rcl/test_guard_condition.cpp +) +target_link_libraries(test_guard_condition ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_publisher + rcl/test_publisher.cpp +) +target_include_directories(test_publisher PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/) +target_link_libraries(test_publisher ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_publisher_wait_all_ack + rcl/test_publisher_wait_all_ack.cpp +) +target_link_libraries(test_publisher_wait_all_ack ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools + rcutils::rcutils rosidl_runtime_c::rosidl_runtime_c ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_events + rcl/test_events.cpp +) +target_include_directories(test_events PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/) +target_link_libraries(test_events ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_wait + rcl/test_wait.cpp +) +target_link_libraries(test_wait ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools) + +ament_add_gtest_executable(test_logging_rosout + rcl/test_logging_rosout.cpp +) +target_link_libraries(test_logging_rosout ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${rcl_interfaces_TARGETS}) + +ament_add_gtest_executable(test_namespace + rcl/test_namespace.cpp +) +target_link_libraries(test_namespace ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_rmw_impl_id_check_func + rcl/test_rmw_impl_id_check_func.cpp +) +target_link_libraries(test_rmw_impl_id_check_func ${PROJECT_NAME} mimick) + +ament_add_gtest_executable(test_network_flow_endpoints + rcl/test_network_flow_endpoints.cpp +) +target_link_libraries(test_network_flow_endpoints ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_service_event_publisher + rcl/test_service_event_publisher.cpp +) +target_include_directories(test_service_event_publisher PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/) +target_link_libraries(test_service_event_publisher + ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_type_description_conversions + rcl/test_type_description_conversions.cpp +) +target_link_libraries(test_type_description_conversions + ${PROJECT_NAME} rosidl_runtime_c::rosidl_runtime_c ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_node_type_cache + rcl/test_node_type_cache.cpp +) +target_link_libraries(test_node_type_cache ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS}) + +ament_add_gtest_executable(test_get_type_description_service + rcl/test_get_type_description_service.cpp +) +target_include_directories(test_get_type_description_service PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/) +target_link_libraries(test_get_type_description_service + ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${type_description_interfaces_TARGETS}) + +function(test_target) message(STATUS "Creating tests for '${rmw_implementation}'") set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) # Gtests - - rcl_add_custom_gtest(test_client${target_suffix} - SRCS rcl/test_client.cpp + ament_add_gtest_test(test_client + TEST_NAME test_client${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_timer${target_suffix} - SRCS rcl/test_timer.cpp + ament_add_gtest_test(test_timer + TEST_NAME test_timer${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_context${target_suffix} - SRCS rcl/test_context.cpp + ament_add_gtest_test(test_context + TEST_NAME test_context${target_suffix} ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_get_node_names${target_suffix} - SRCS rcl/test_get_node_names.cpp + ament_add_gtest_test(test_get_node_names + TEST_NAME test_get_node_names${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_graph${target_suffix} - SRCS rcl/test_graph.cpp + ament_add_gtest_test(test_graph + TEST_NAME test_graph${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} TIMEOUT 120 ) - rcl_add_custom_gtest(test_info_by_topic${target_suffix} - SRCS rcl/test_info_by_topic.cpp + ament_add_gtest_test(test_info_by_topic + TEST_NAME test_info_by_topic${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_count_matched${target_suffix} - SRCS rcl/test_count_matched.cpp + ament_add_gtest_test(test_count_matched + TEST_NAME test_count_matched${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_get_actual_qos${target_suffix} - SRCS rcl/test_get_actual_qos.cpp + ament_add_gtest_test(test_get_actual_qos + TEST_NAME test_get_actual_qos${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_init${target_suffix} - SRCS rcl/test_init.cpp + ament_add_gtest_test(test_init + TEST_NAME test_init${target_suffix} ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES ${rmw_implementation} ) # RHEL does not support mimick's inject_on_return functionality, which @@ -136,56 +238,36 @@ function(test_target_function) else() set(gtest_filter_env_var "") endif() - rcl_add_custom_gtest(test_node${target_suffix} - SRCS rcl/test_node.cpp + ament_add_gtest_test(test_node + TEST_NAME test_node${target_suffix} ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} ${gtest_filter_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES ${rmw_implementation} TIMEOUT 240 # Large timeout to wait for fault injection tests ) - rcl_add_custom_gtest(test_remap${target_suffix} - SRCS rcl/test_remap.cpp + ament_add_gtest_test(test_remap + TEST_NAME test_remap${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ) - rcl_add_custom_gtest(test_remap_integration${target_suffix} - SRCS rcl/test_remap_integration.cpp - TIMEOUT 200 + ament_add_gtest_test(test_remap_integration + TEST_NAME test_remap_integration${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} + TIMEOUT 200 ) - rcl_add_custom_gtest(test_guard_condition${target_suffix} - SRCS rcl/test_guard_condition.cpp + ament_add_gtest_test(test_guard_condition + TEST_NAME test_guard_condition${target_suffix} ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_publisher${target_suffix} - SRCS rcl/test_publisher.cpp + ament_add_gtest_test(test_publisher + TEST_NAME test_publisher${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_publisher_wait_all_ack${target_suffix} - SRCS rcl/test_publisher_wait_all_ack.cpp + ament_add_gtest_test(test_publisher_wait_all_ack + TEST_NAME test_publisher_wait_all_ack${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools rcutils::rcutils - rosidl_runtime_c::rosidl_runtime_c ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_service${target_suffix} @@ -193,7 +275,6 @@ function(test_target_function) ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_subscription${target_suffix} @@ -202,7 +283,6 @@ function(test_target_function) APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools rosidl_runtime_cpp::rosidl_runtime_cpp ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} TIMEOUT 120 ) # TODO(asorbini) Enable message timestamp tests for rmw_connextdds on Windows @@ -227,102 +307,58 @@ function(test_target_function) endif() endif() - rcl_add_custom_gtest(test_events${target_suffix} - SRCS rcl/test_events.cpp + ament_add_gtest_test(test_events + TEST_NAME test_events${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_wait${target_suffix} - SRCS rcl/test_wait.cpp + ament_add_gtest_test(test_wait + TEST_NAME test_wait${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_logging_rosout${target_suffix} - SRCS rcl/test_logging_rosout.cpp + ament_add_gtest_test(test_logging_rosout + TEST_NAME test_logging_rosout${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${rcl_interfaces_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_namespace${target_suffix} - SRCS rcl/test_namespace.cpp + ament_add_gtest_test(test_namespace + TEST_NAME test_namespace${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_rmw_impl_id_check_func${target_suffix} - SRCS rcl/test_rmw_impl_id_check_func.cpp + ament_add_gtest_test(test_rmw_impl_id_check_func + TEST_NAME test_rmw_impl_id_check_func${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} mimick - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_network_flow_endpoints${target_suffix} - SRCS rcl/test_network_flow_endpoints.cpp + ament_add_gtest_test(test_network_flow_endpoints + TEST_NAME test_network_flow_endpoints${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_service_event_publisher${target_suffix} - SRCS rcl/test_service_event_publisher.cpp + ament_add_gtest_test(test_service_event_publisher + TEST_NAME test_service_event_publisher${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_type_description_conversions${target_suffix} - SRCS rcl/test_type_description_conversions.cpp - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} ${test_msgs_TARGETS} + ament_add_gtest_test(test_type_description_conversions + TEST_NAME test_type_description_conversions${target_suffix} + ENV ${rmw_implementation_env_var} ) - rcl_add_custom_gtest(test_node_type_cache${target_suffix} - SRCS rcl/test_node_type_cache.cpp + ament_add_gtest_test(test_node_type_cache + TEST_NAME test_node_type_cache${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) - rcl_add_custom_gtest(test_get_type_description_service${target_suffix} - SRCS rcl/test_get_type_description_service.cpp + ament_add_gtest_test(test_get_type_description_service + TEST_NAME test_get_type_description_service${target_suffix} ENV ${rmw_implementation_env_var} - APPEND_LIBRARY_DIRS ${extra_lib_dirs} - INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ - LIBRARIES ${PROJECT_NAME} mimick wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${type_description_interfaces_TARGETS} - AMENT_DEPENDENCIES ${rmw_implementation} ) # Launch tests - rcl_add_custom_executable(service_fixture${target_suffix} - SRCS rcl/service_fixture.cpp - LIBRARIES ${PROJECT_NAME} wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} rcutils::rcutils - ) - - rcl_add_custom_executable(client_fixture${target_suffix} - SRCS rcl/client_fixture.cpp - LIBRARIES ${PROJECT_NAME} wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} - ) - rcl_add_custom_launch_test(test_services service_fixture client_fixture @@ -369,12 +405,23 @@ target_link_libraries(test_rmw_impl_id_check_exe ${PROJECT_NAME}) # This file is used by many tests, so build it just once add_library(wait_for_entity_helpers STATIC rcl/wait_for_entity_helpers.cpp) -target_include_directories(wait_for_entity_helpers PRIVATE - ${osrf_testing_tools_cpp_INCLUDE_DIRS}) target_link_libraries(wait_for_entity_helpers PUBLIC ${PROJECT_NAME}) target_link_libraries(wait_for_entity_helpers PRIVATE + osrf_testing_tools_cpp::memory_tools rcutils::rcutils) +# Launch test executables + +rcl_add_custom_executable(service_fixture + SRCS rcl/service_fixture.cpp + LIBRARIES ${PROJECT_NAME} wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} rcutils::rcutils +) + +rcl_add_custom_executable(client_fixture + SRCS rcl/client_fixture.cpp + LIBRARIES ${PROJECT_NAME} wait_for_entity_helpers osrf_testing_tools_cpp::memory_tools ${test_msgs_TARGETS} +) + call_for_each_rmw_implementation(test_target) rcl_add_custom_gtest(test_arguments diff --git a/rcl/test/cmake/rcl_add_custom_launch_test.cmake b/rcl/test/cmake/rcl_add_custom_launch_test.cmake index d4d2e224d..8be69800e 100644 --- a/rcl/test/cmake/rcl_add_custom_launch_test.cmake +++ b/rcl/test/cmake/rcl_add_custom_launch_test.cmake @@ -21,9 +21,9 @@ set(rcl_add_custom_launch_test_INCLUDED TRUE) macro(rcl_add_custom_launch_test test_name executable1 executable2) set(TEST_NAME "${test_name}") - set(TEST_EXECUTABLE1 "$") + set(TEST_EXECUTABLE1 "$") set(TEST_EXECUTABLE1_NAME "${executable1}") - set(TEST_EXECUTABLE2 "$") + set(TEST_EXECUTABLE2 "$") set(TEST_EXECUTABLE2_NAME "${executable2}") configure_file( rcl/test_two_executables.py.in @@ -40,6 +40,6 @@ macro(rcl_add_custom_launch_test test_name executable1 executable2) ${ARGN} ) if(TEST ${test_name}${target_suffix}) - set_tests_properties(${test_name}${target_suffix} PROPERTIES DEPENDS "${executable1}${target_suffix} ${executable2}${target_suffix}") + set_tests_properties(${test_name}${target_suffix} PROPERTIES DEPENDS "${executable1} ${executable2}") endif() endmacro() diff --git a/rcl/test/rcl/test_context.cpp b/rcl/test/rcl/test_context.cpp index 31e4100b3..55aa485dc 100644 --- a/rcl/test/rcl/test_context.cpp +++ b/rcl/test/rcl/test_context.cpp @@ -24,18 +24,9 @@ #include "../mocking_utils/patch.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 (TestContextFixture, RMW_IMPLEMENTATION) : public ::testing::Test {}; - // Test the rcl_context_t's normal function. // Note: that init/fini are tested in test_init.cpp. -TEST_F(CLASSNAME(TestContextFixture, RMW_IMPLEMENTATION), nominal) { +TEST(TestContext, nominal) { osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest scoped_quickstart_gtest; // This prevents memory allocations when setting error states in the future. @@ -151,7 +142,7 @@ TEST_F(CLASSNAME(TestContextFixture, RMW_IMPLEMENTATION), nominal) { EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } -TEST_F(CLASSNAME(TestContextFixture, RMW_IMPLEMENTATION), bad_fini) { +TEST(TestContext, bad_fini) { EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_context_fini(nullptr)); rcl_reset_error(); diff --git a/rcl/test/rcl/test_count_matched.cpp b/rcl/test/rcl/test_count_matched.cpp index b0baaa8ba..296741900 100644 --- a/rcl/test/rcl/test_count_matched.cpp +++ b/rcl/test/rcl/test_count_matched.cpp @@ -28,13 +28,6 @@ #include "rcl/error_handling.h" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - void check_state( rcl_wait_set_t * wait_set_ptr, rcl_publisher_t * publisher, @@ -96,7 +89,7 @@ void check_state( EXPECT_EQ(expected_subscriber_count, subscriber_count); } -class CLASSNAME (TestCountFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestCountFixture : public ::testing::Test { public: rcl_node_t * node_ptr; @@ -150,7 +143,7 @@ class CLASSNAME (TestCountFixture, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(TestCountFixture, RMW_IMPLEMENTATION), test_count_matched_functions) { +TEST_F(TestCountFixture, test_count_matched_functions) { std::string topic_name("/test_count_matched_functions__"); rcl_ret_t ret; @@ -199,9 +192,7 @@ TEST_F(CLASSNAME(TestCountFixture, RMW_IMPLEMENTATION), test_count_matched_funct rcl_reset_error(); } -TEST_F( - CLASSNAME(TestCountFixture, RMW_IMPLEMENTATION), - test_count_matched_functions_mismatched_qos) { +TEST_F(TestCountFixture, test_count_matched_functions_mismatched_qos) { std::string topic_name("/test_count_matched_functions_mismatched_qos__"); rcl_ret_t ret; diff --git a/rcl/test/rcl/test_events.cpp b/rcl/test/rcl/test_events.cpp index 34f1a0a11..33ccc914e 100644 --- a/rcl/test/rcl/test_events.cpp +++ b/rcl/test/rcl/test_events.cpp @@ -43,13 +43,6 @@ constexpr seconds LIVELINESS_LEASE_DURATION_IN_S = 1s; constexpr seconds DEADLINE_PERIOD_IN_S = 2s; constexpr seconds MAX_WAIT_PER_TESTCASE = 10s; -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - #define EXPECT_OK(varname) EXPECT_EQ(varname, RCL_RET_OK) << rcl_get_error_string().str struct TestIncompatibleQosEventParams @@ -61,8 +54,7 @@ struct TestIncompatibleQosEventParams std::string error_msg; }; -class CLASSNAME (TestEventFixture, RMW_IMPLEMENTATION) - : public ::testing::TestWithParam +class TestEventFixture : public ::testing::TestWithParam { public: void SetUp() @@ -240,8 +232,6 @@ class CLASSNAME (TestEventFixture, RMW_IMPLEMENTATION) const rosidl_message_type_support_t * ts; }; -using TestEventFixture = CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION); - const rmw_qos_profile_t TestEventFixture::default_qos_profile = { RMW_QOS_POLICY_HISTORY_KEEP_LAST, // history 0, // depth diff --git a/rcl/test/rcl/test_get_actual_qos.cpp b/rcl/test/rcl/test_get_actual_qos.cpp index f590867d4..2f4555d36 100644 --- a/rcl/test/rcl/test_get_actual_qos.cpp +++ b/rcl/test/rcl/test_get_actual_qos.cpp @@ -28,28 +28,6 @@ #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) -# define RMW_IMPLEMENTATION_STR RCUTILS_STRINGIFY(RMW_IMPLEMENTATION) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -#define EXPAND(x) x -#define TEST_FIXTURE_P_RMW(test_fixture_name) CLASSNAME( \ - test_fixture_name, RMW_IMPLEMENTATION) -#define APPLY(macro, ...) EXPAND(macro(__VA_ARGS__)) -#define TEST_P_RMW(test_case_name, test_name) \ - APPLY( \ - TEST_P, \ - CLASSNAME(test_case_name, RMW_IMPLEMENTATION), test_name) -#define INSTANTIATE_TEST_SUITE_P_RMW(instance_name, test_case_name, ...) \ - EXPAND( \ - APPLY( \ - INSTANTIATE_TEST_SUITE_P, instance_name, \ - CLASSNAME(test_case_name, RMW_IMPLEMENTATION), __VA_ARGS__)) - /** * Parameterized test. * The first param are the NodeOptions used to create the nodes. @@ -98,8 +76,7 @@ std::ostream & operator<<( return out; } -class TEST_FIXTURE_P_RMW (TestGetActualQoS) - : public ::testing::TestWithParam +class TestGetActualQoS : public ::testing::TestWithParam { public: void SetUp() override @@ -147,10 +124,9 @@ class TEST_FIXTURE_P_RMW (TestGetActualQoS) }; -class TEST_FIXTURE_P_RMW (TestPublisherGetActualQoS) - : public TEST_FIXTURE_P_RMW(TestGetActualQoS) {}; +class TestPublisherGetActualQoS : public TestGetActualQoS {}; -TEST_P_RMW(TestPublisherGetActualQoS, test_publisher_get_qos_settings) +TEST_P(TestPublisherGetActualQoS, test_publisher_get_qos_settings) { TestParameters parameters = GetParam(); std::string topic_name("/test_publisher_get_actual_qos__"); @@ -202,10 +178,9 @@ TEST_P_RMW(TestPublisherGetActualQoS, test_publisher_get_qos_settings) } -class TEST_FIXTURE_P_RMW (TestSubscriptionGetActualQoS) - : public TEST_FIXTURE_P_RMW(TestGetActualQoS) {}; +class TestSubscriptionGetActualQoS : public TestGetActualQoS {}; -TEST_P_RMW(TestSubscriptionGetActualQoS, test_subscription_get_qos_settings) +TEST_P(TestSubscriptionGetActualQoS, test_subscription_get_qos_settings) { TestParameters parameters = GetParam(); std::string topic_name("/test_subscription_get_qos_settings"); @@ -396,8 +371,7 @@ get_parameters(bool for_publisher) "default_qos" }); -#ifdef RMW_IMPLEMENTATION_STR - std::string rmw_implementation_str = RMW_IMPLEMENTATION_STR; + std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier()); if (rmw_implementation_str == "rmw_fastrtps_cpp" || rmw_implementation_str == "rmw_fastrtps_dynamic_cpp") { @@ -464,18 +438,17 @@ get_parameters(bool for_publisher) } } } -#endif return parameters; } -INSTANTIATE_TEST_SUITE_P_RMW( +INSTANTIATE_TEST_SUITE_P( TestPublisherWithDifferentQoSSettings, TestPublisherGetActualQoS, ::testing::ValuesIn(get_parameters(true)), ::testing::PrintToStringParamName()); -INSTANTIATE_TEST_SUITE_P_RMW( +INSTANTIATE_TEST_SUITE_P( TestSubscriptionWithDifferentQoSSettings, TestSubscriptionGetActualQoS, ::testing::ValuesIn(get_parameters(false)), diff --git a/rcl/test/rcl/test_get_node_names.cpp b/rcl/test/rcl/test_get_node_names.cpp index 80a0da47c..3dc7bf4aa 100644 --- a/rcl/test/rcl/test_get_node_names.cpp +++ b/rcl/test/rcl/test_get_node_names.cpp @@ -32,16 +32,9 @@ #include "rcl/error_handling.h" -#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 (TestGetNodeNames, RMW_IMPLEMENTATION) : public ::testing::Test +class TestGetNodeNames : public ::testing::Test { public: void SetUp() @@ -51,7 +44,7 @@ class CLASSNAME (TestGetNodeNames, RMW_IMPLEMENTATION) : public ::testing::Test {} }; -TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) { +TEST_F(TestGetNodeNames, test_rcl_get_node_names) { rcl_ret_t ret; rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); @@ -164,8 +157,7 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } -TEST_F( - CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names_with_enclave) +TEST_F(TestGetNodeNames, test_rcl_get_node_names_with_enclave) { rcl_ret_t ret; rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); diff --git a/rcl/test/rcl/test_get_type_description_service.cpp b/rcl/test/rcl/test_get_type_description_service.cpp index 235e7937a..1055b1cf6 100644 --- a/rcl/test/rcl/test_get_type_description_service.cpp +++ b/rcl/test/rcl/test_get_type_description_service.cpp @@ -31,13 +31,6 @@ #include "node_impl.h" // NOLINT #include "wait_for_entity_helpers.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - constexpr char GET_TYPE_DESCRIPTION_SRV_TYPE_NAME[] = "type_description_interfaces/srv/GetTypeDescription"; @@ -140,7 +133,7 @@ static bool service_not_exists( return false; } -class CLASSNAME (TestGetTypeDescSrvFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestGetTypeDescSrvFixture : public ::testing::Test { public: void SetUp() @@ -190,9 +183,7 @@ class CLASSNAME (TestGetTypeDescSrvFixture, RMW_IMPLEMENTATION) : public ::testi /* Test init and fini functions. */ -TEST_F( - CLASSNAME(TestGetTypeDescSrvFixture, RMW_IMPLEMENTATION), - test_service_init_and_fini_functions) { +TEST_F(TestGetTypeDescSrvFixture, test_service_init_and_fini_functions) { rcl_service_t service = rcl_get_zero_initialized_service(); // Service does not initially exist @@ -220,7 +211,7 @@ TEST_F( } /* Basic nominal test of the ~/get_type_description service. */ -TEST_F(CLASSNAME(TestGetTypeDescSrvFixture, RMW_IMPLEMENTATION), test_service_nominal) { +TEST_F(TestGetTypeDescSrvFixture, test_service_nominal) { rcl_ret_t ret; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( type_description_interfaces, srv, GetTypeDescription); @@ -317,10 +308,7 @@ TEST_F(CLASSNAME(TestGetTypeDescSrvFixture, RMW_IMPLEMENTATION), test_service_no } /* Test calling ~/get_type_description service with invalid hash. */ -TEST_F( - CLASSNAME( - TestGetTypeDescSrvFixture, - RMW_IMPLEMENTATION), test_service_invalid_hash) { +TEST_F(TestGetTypeDescSrvFixture, test_service_invalid_hash) { rcl_ret_t ret; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( type_description_interfaces, srv, GetTypeDescription); diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index 1d42c7acc..2eb0d7612 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -42,17 +42,10 @@ #include "osrf_testing_tools_cpp/scope_exit.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - bool is_connext = std::string(rmw_get_implementation_identifier()).find("rmw_connext") == 0; -class CLASSNAME (TestGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestGraphFixture : public ::testing::Test { public: rcl_context_t * old_context_ptr; @@ -148,10 +141,7 @@ class CLASSNAME (TestGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test * * This does not test content of the rcl_names_and_types_t structure. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_get_and_destroy_topic_names_and_types -) { +TEST_F(TestGraphFixture, test_rcl_get_and_destroy_topic_names_and_types) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t zero_allocator = static_cast( @@ -199,10 +189,7 @@ TEST_F( * * This does not test content of the rcl_names_and_types_t structure. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_get_service_names_and_types -) { +TEST_F(TestGraphFixture, test_rcl_get_service_names_and_types) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t zero_allocator = static_cast( @@ -248,10 +235,7 @@ TEST_F( /* Test the rcl_names_and_types_init function. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_names_and_types_init -) { +TEST_F(TestGraphFixture, test_rcl_names_and_types_init) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t zero_allocator = static_cast( @@ -290,10 +274,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_get_publisher_names_and_types_by_node -) { +TEST_F(TestGraphFixture, test_rcl_get_publisher_names_and_types_by_node) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t zero_allocator = static_cast( @@ -381,10 +362,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_get_subscriber_names_and_types_by_node -) { +TEST_F(TestGraphFixture, test_rcl_get_subscriber_names_and_types_by_node) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t zero_allocator = static_cast( @@ -469,10 +447,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_get_service_names_and_types_by_node -) { +TEST_F(TestGraphFixture, test_rcl_get_service_names_and_types_by_node) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t zero_allocator = static_cast( @@ -557,10 +532,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_get_client_names_and_types_by_node -) { +TEST_F(TestGraphFixture, test_rcl_get_client_names_and_types_by_node) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t zero_allocator = static_cast( @@ -646,10 +618,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_count_publishers -) { +TEST_F(TestGraphFixture, test_rcl_count_publishers) { rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); const char * topic_name = "/topic_test_rcl_count_publishers"; @@ -683,10 +652,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_count_subscribers -) { +TEST_F(TestGraphFixture, test_rcl_count_subscribers) { rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); const char * topic_name = "/topic_test_rcl_count_subscribers"; @@ -720,10 +686,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_count_clients -) { +TEST_F(TestGraphFixture, test_rcl_count_clients) { rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); const char * service_name = "/topic_test_rcl_count_clients"; @@ -757,10 +720,7 @@ TEST_F( * * This does not test content of the response. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_count_services -) { +TEST_F(TestGraphFixture, test_rcl_count_services) { rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); const char * service_name = "/topic_test_rcl_count_services"; @@ -792,10 +752,7 @@ TEST_F( /* Test the rcl_wait_for_publishers function. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_wait_for_publishers -) { +TEST_F(TestGraphFixture, test_rcl_wait_for_publishers) { rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); rcl_allocator_t zero_allocator = static_cast( @@ -837,10 +794,7 @@ TEST_F( /* Test the rcl_wait_for_subscribers function. */ -TEST_F( - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), - test_rcl_wait_for_subscribers -) { +TEST_F(TestGraphFixture, test_rcl_wait_for_subscribers) { rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); rcl_allocator_t zero_allocator = static_cast( @@ -996,7 +950,7 @@ struct expected_node_state /** * Extend the TestGraphFixture with a multi node fixture for node discovery and node-graph perspective. */ -class NodeGraphMultiNodeFixture : public CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION) +class NodeGraphMultiNodeFixture : public TestGraphFixture { public: const char * remote_node_name = "remote_graph_node"; @@ -1008,7 +962,7 @@ class NodeGraphMultiNodeFixture : public CLASSNAME(TestGraphFixture, RMW_IMPLEME void SetUp() override { - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION) ::SetUp(); + TestGraphFixture::SetUp(); rcl_ret_t ret; rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); @@ -1074,7 +1028,7 @@ class NodeGraphMultiNodeFixture : public CLASSNAME(TestGraphFixture, RMW_IMPLEME void TearDown() override { rcl_ret_t ret; - CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION) ::TearDown(); + TestGraphFixture::TearDown(); const rcl_node_options_t * node_ops = rcl_node_get_options(this->remote_node_ptr); if (rcl_logging_rosout_enabled() && node_ops->enable_rosout) { ret = rcl_logging_rosout_fini_publisher_for_node(this->remote_node_ptr); @@ -1290,7 +1244,7 @@ TEST_F(NodeGraphMultiNodeFixture, test_node_info_clients) /* * Test graph queries with a hand crafted graph. */ -TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functions) +TEST_F(TestGraphFixture, test_graph_query_functions) { std::string topic_name("/test_graph_query_functions__"); std::chrono::nanoseconds now = std::chrono::system_clock::now().time_since_epoch(); @@ -1367,7 +1321,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio * * Note: this test could be impacted by other communications on the same ROS Domain. */ -TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_condition_trigger_check) { +TEST_F(TestGraphFixture, test_graph_guard_condition_trigger_check) { #define CHECK_GUARD_CONDITION_CHANGE(EXPECTED_RESULT, TIMEOUT) do { \ ret = rcl_wait_set_clear(&wait_set); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \ @@ -1534,7 +1488,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi /* Test the rcl_service_server_is_available function. */ -TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_is_available) { +TEST_F(TestGraphFixture, test_rcl_service_server_is_available) { rcl_ret_t ret; // First create a client which will be used to call the function. rcl_client_t client = rcl_get_zero_initialized_client(); @@ -1628,7 +1582,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_ /* Test passing invalid params to server_is_available */ -TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_server_available) { +TEST_F(TestGraphFixture, test_bad_server_available) { // Create a client which will be used to call the function. rcl_client_t client = rcl_get_zero_initialized_client(); auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); @@ -1658,7 +1612,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_server_availabl /* Test passing invalid params to get_node_names functions */ -TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) { +TEST_F(TestGraphFixture, test_bad_get_node_names) { rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array(); rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array(); diff --git a/rcl/test/rcl/test_guard_condition.cpp b/rcl/test/rcl/test_guard_condition.cpp index 48d4ede4d..027fa9aed 100644 --- a/rcl/test/rcl/test_guard_condition.cpp +++ b/rcl/test/rcl/test_guard_condition.cpp @@ -28,19 +28,12 @@ #include "../mocking_utils/patch.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 osrf_testing_tools_cpp::memory_tools::on_unexpected_malloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_free; -class CLASSNAME (TestGuardConditionFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestGuardConditionFixture : public ::testing::Test { public: void SetUp() @@ -60,8 +53,7 @@ class CLASSNAME (TestGuardConditionFixture, RMW_IMPLEMENTATION) : public ::testi /* Tests the guard condition accessors, i.e. rcl_guard_condition_get_* functions. */ -TEST_F( - CLASSNAME(TestGuardConditionFixture, RMW_IMPLEMENTATION), test_rcl_guard_condition_accessors) { +TEST_F(TestGuardConditionFixture, test_rcl_guard_condition_accessors) { osrf_testing_tools_cpp::memory_tools::enable_monitoring_in_all_threads(); rcl_ret_t ret; @@ -135,8 +127,7 @@ TEST_F( /* Tests the guard condition life cycle, including rcl_guard_condition_init/fini(). */ -TEST_F( - CLASSNAME(TestGuardConditionFixture, RMW_IMPLEMENTATION), test_rcl_guard_condition_life_cycle) { +TEST_F(TestGuardConditionFixture, test_rcl_guard_condition_life_cycle) { rcl_ret_t ret; rcl_context_t context = rcl_get_zero_initialized_context(); rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); @@ -243,8 +234,7 @@ TEST_F( /* Tests trigger_guard_condition with bad arguments */ -TEST_F( - CLASSNAME(TestGuardConditionFixture, RMW_IMPLEMENTATION), test_rcl_guard_condition_bad_arg) { +TEST_F(TestGuardConditionFixture, test_rcl_guard_condition_bad_arg) { rcl_guard_condition_t zero_guard_condition = rcl_get_zero_initialized_guard_condition(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_trigger_guard_condition(nullptr)); rcl_reset_error(); diff --git a/rcl/test/rcl/test_info_by_topic.cpp b/rcl/test/rcl/test_info_by_topic.cpp index 09d6e0858..de8849b31 100644 --- a/rcl/test/rcl/test_info_by_topic.cpp +++ b/rcl/test/rcl/test_info_by_topic.cpp @@ -34,14 +34,7 @@ #include "osrf_testing_tools_cpp/scope_exit.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 (TestInfoByTopicFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestInfoByTopicFixture : public ::testing::Test { public: rcl_context_t old_context; @@ -132,9 +125,7 @@ class CLASSNAME (TestInfoByTopicFixture, RMW_IMPLEMENTATION) : public ::testing: * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_publishers_info_by_topic_null_node) +TEST_F(TestInfoByTopicFixture, test_rcl_get_publishers_info_by_topic_null_node) { rcl_allocator_t allocator = rcl_get_default_allocator(); const auto ret = rcl_get_publishers_info_by_topic( @@ -148,9 +139,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_subscriptions_info_by_topic_null_node) +TEST_F(TestInfoByTopicFixture, test_rcl_get_subscriptions_info_by_topic_null_node) { rcl_allocator_t allocator = rcl_get_default_allocator(); const auto ret = rcl_get_subscriptions_info_by_topic( @@ -164,9 +153,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_publishers_info_by_topic_invalid_node) +TEST_F(TestInfoByTopicFixture, test_rcl_get_publishers_info_by_topic_invalid_node) { // this->old_node is an invalid node. rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -181,9 +168,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_subscriptions_info_by_topic_invalid_node) +TEST_F(TestInfoByTopicFixture, test_rcl_get_subscriptions_info_by_topic_invalid_node) { // this->old_node is an invalid node. rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -198,9 +183,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_publishers_info_by_topic_null_allocator) +TEST_F(TestInfoByTopicFixture, test_rcl_get_publishers_info_by_topic_null_allocator) { const auto ret = rcl_get_publishers_info_by_topic( &this->node, nullptr, this->topic_name, false, @@ -213,9 +196,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_subscriptions_info_by_topic_null_allocator) +TEST_F(TestInfoByTopicFixture, test_rcl_get_subscriptions_info_by_topic_null_allocator) { const auto ret = rcl_get_subscriptions_info_by_topic( &this->node, nullptr, this->topic_name, false, @@ -228,9 +209,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_publishers_info_by_topic_null_topic) +TEST_F(TestInfoByTopicFixture, test_rcl_get_publishers_info_by_topic_null_topic) { rcl_allocator_t allocator = rcl_get_default_allocator(); const auto ret = rcl_get_publishers_info_by_topic( @@ -243,9 +222,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_subscriptions_info_by_topic_null_topic) +TEST_F(TestInfoByTopicFixture, test_rcl_get_subscriptions_info_by_topic_null_topic) { rcl_allocator_t allocator = rcl_get_default_allocator(); const auto ret = rcl_get_subscriptions_info_by_topic( @@ -258,9 +235,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_publishers_info_by_topic_null_participants) +TEST_F(TestInfoByTopicFixture, test_rcl_get_publishers_info_by_topic_null_participants) { rcl_allocator_t allocator = rcl_get_default_allocator(); const auto ret = rcl_get_publishers_info_by_topic( @@ -273,9 +248,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_subscriptions_info_by_topic_null_participants) +TEST_F(TestInfoByTopicFixture, test_rcl_get_subscriptions_info_by_topic_null_participants) { rcl_allocator_t allocator = rcl_get_default_allocator(); const auto ret = rcl_get_subscriptions_info_by_topic( @@ -288,9 +261,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_publishers_info_by_topic_invalid_participants) +TEST_F(TestInfoByTopicFixture, test_rcl_get_publishers_info_by_topic_invalid_participants) { // topic_endpoint_info_array is invalid because it is expected to be zero initialized // and the info_array variable inside it is expected to be null. @@ -311,9 +282,7 @@ TEST_F( * This does not test content of the response. * It only tests if the return code is the one expected. */ -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_subscriptions_info_by_topic_invalid_participants) +TEST_F(TestInfoByTopicFixture, test_rcl_get_subscriptions_info_by_topic_invalid_participants) { // topic_endpoint_info_array is invalid because it is expected to be zero initialized // and the info_array variable inside it is expected to be null. @@ -330,9 +299,7 @@ TEST_F( rcl_reset_error(); } -TEST_F( - CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION), - test_rcl_get_publishers_subscription_info_by_topic) +TEST_F(TestInfoByTopicFixture, test_rcl_get_publishers_subscription_info_by_topic) { rmw_qos_profile_t default_qos_profile = rmw_qos_profile_system_default; default_qos_profile.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST; diff --git a/rcl/test/rcl/test_init.cpp b/rcl/test/rcl/test_init.cpp index f40e015e2..6ac629eb7 100644 --- a/rcl/test/rcl/test_init.cpp +++ b/rcl/test/rcl/test_init.cpp @@ -31,19 +31,12 @@ #include "../mocking_utils/patch.hpp" #include "../src/rcl/init_options_impl.h" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - using osrf_testing_tools_cpp::memory_tools::on_unexpected_malloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_free; -class CLASSNAME (TestRCLFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestRCLFixture : public ::testing::Test { public: void SetUp() @@ -106,7 +99,7 @@ struct FakeTestArgv /* Tests rcl_init_options_init() and rcl_init_options_fini() functions. */ -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_options_init) { +TEST_F(TestRCLFixture, test_rcl_init_options_init) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); // fini a not empty options @@ -140,7 +133,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_options_init /* Tests calling rcl_init() with invalid arguments fails. */ -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_invalid_arguments) { +TEST_F(TestRCLFixture, test_rcl_init_invalid_arguments) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -250,7 +243,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_invalid_argu /* Tests the rcl_init() and rcl_shutdown() functions. */ -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_and_shutdown) { +TEST_F(TestRCLFixture, test_rcl_init_and_shutdown) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -321,7 +314,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_and_shutdown /* Tests rcl_init() deals with internal errors correctly. */ -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_internal_error) { +TEST_F(TestRCLFixture, test_rcl_init_internal_error) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -364,7 +357,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_internal_err /* Tests rcl_shutdown() deals with internal errors correctly. */ -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_shutdown_internal_error) { +TEST_F(TestRCLFixture, test_rcl_shutdown_internal_error) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -391,7 +384,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_shutdown_internal /* Tests the rcl_get_instance_id() function. */ -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_get_instance_id) { +TEST_F(TestRCLFixture, test_rcl_get_instance_id) { rcl_ret_t ret; rcl_context_t context = rcl_get_zero_initialized_context(); // Instance id should be 0 before rcl_init(). @@ -454,7 +447,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_get_instance_id) EXPECT_EQ(ret, RCL_RET_OK); } -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_options_access) { +TEST_F(TestRCLFixture, test_rcl_init_options_access) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_init_options_t not_ini_init_options = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); @@ -535,7 +528,7 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, >) MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, !=) // Tests rcl_init_options_init() mocked to fail -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_mocked_rcl_init_options_ini) { +TEST_F(TestRCLFixture, test_mocked_rcl_init_options_ini) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); auto mock = mocking_utils::patch_and_return("lib:rcl", rmw_init_options_init, RMW_RET_ERROR); EXPECT_EQ(RCL_RET_ERROR, rcl_init_options_init(&init_options, rcl_get_default_allocator())); @@ -543,7 +536,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_mocked_rcl_init_optio } // Tests rcl_init_options_fini() mocked to fail -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_mocked_rcl_init_options_fini) { +TEST_F(TestRCLFixture, test_mocked_rcl_init_options_fini) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -555,7 +548,7 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_mocked_rcl_init_optio } // Mock rcl_init_options_copy to fail -TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_options_copy_fail_rmw_copy) { +TEST_F(TestRCLFixture, test_rcl_init_options_copy_fail_rmw_copy) { rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; diff --git a/rcl/test/rcl/test_logging_rosout.cpp b/rcl/test/rcl/test_logging_rosout.cpp index bd89dc4f6..6bfcac97e 100644 --- a/rcl/test/rcl/test_logging_rosout.cpp +++ b/rcl/test/rcl/test_logging_rosout.cpp @@ -27,26 +27,6 @@ #include "rcl/logging_rosout.h" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -#define EXPAND(x) x -#define TEST_FIXTURE_P_RMW(test_fixture_name) CLASSNAME( \ - test_fixture_name, RMW_IMPLEMENTATION) -#define APPLY(macro, ...) EXPAND(macro(__VA_ARGS__)) -#define TEST_P_RMW(test_case_name, test_name) \ - APPLY( \ - TEST_P, CLASSNAME(test_case_name, RMW_IMPLEMENTATION), test_name) -#define INSTANTIATE_TEST_SUITE_P_RMW(instance_name, test_case_name, ...) \ - EXPAND( \ - APPLY( \ - INSTANTIATE_TEST_SUITE_P, instance_name, \ - CLASSNAME(test_case_name, RMW_IMPLEMENTATION), __VA_ARGS__)) - struct TestParameters { int argc; @@ -65,7 +45,7 @@ std::ostream & operator<<( return out; } -class CLASSNAME (TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION) : public ::testing::Test {}; +class TestLogRosoutFixtureNotParam : public ::testing::Test {}; class TestLoggingRosout : public ::testing::Test { @@ -153,7 +133,7 @@ class TestLoggingRosout : public ::testing::Test rcl_subscription_t * subscription_ptr; }; -class TEST_FIXTURE_P_RMW (TestLoggingRosoutFixture) +class TestLoggingRosoutFixture : public TestLoggingRosout, public ::testing::WithParamInterface { protected: @@ -179,7 +159,7 @@ class TEST_FIXTURE_P_RMW (TestLoggingRosoutFixture) TestParameters param_; }; -class CLASSNAME (TestLogRosoutFixtureGeneral, RMW_IMPLEMENTATION) : public TestLoggingRosout {}; +class TestLogRosoutFixtureGeneral : public TestLoggingRosout {}; static void check_if_rosout_subscription_gets_a_message( @@ -233,7 +213,7 @@ check_if_rosout_subscription_gets_a_message( /* Testing the subscriber of topic 'rosout' whether to get event from logging or not. */ -TEST_P_RMW(TestLoggingRosoutFixture, test_logging_rosout) { +TEST_P(TestLoggingRosoutFixture, test_logging_rosout) { bool success = false; check_if_rosout_subscription_gets_a_message( rcl_node_get_logger_name(this->node_ptr), this->subscription_ptr, @@ -322,7 +302,7 @@ get_parameters() return parameters; } -INSTANTIATE_TEST_SUITE_P_RMW( +INSTANTIATE_TEST_SUITE_P( TestLoggingRosoutWithDifferentSettings, TestLoggingRosoutFixture, ::testing::ValuesIn(get_parameters()), @@ -330,8 +310,7 @@ INSTANTIATE_TEST_SUITE_P_RMW( /* Testing twice init logging_rosout */ -TEST_F( - CLASSNAME(TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION), test_twice_init_logging_rosout) +TEST_F(TestLogRosoutFixtureNotParam, test_twice_init_logging_rosout) { rcl_allocator_t allocator = rcl_get_default_allocator(); EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_init(&allocator)); @@ -344,10 +323,7 @@ TEST_F( /* Bad params */ -TEST_F( - CLASSNAME( - TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION), - test_bad_params_init_fini_node_publisher) +TEST_F(TestLogRosoutFixtureNotParam, test_bad_params_init_fini_node_publisher) { rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_node_t not_init_node = rcl_get_zero_initialized_node(); @@ -368,8 +344,7 @@ TEST_F( /* Testing basic of adding and removing sublogger */ -TEST_F( - CLASSNAME(TestLogRosoutFixtureGeneral, RMW_IMPLEMENTATION), test_add_remove_sublogger_basic) +TEST_F(TestLogRosoutFixtureGeneral, test_add_remove_sublogger_basic) { const char * logger_name = rcl_node_get_logger_name(this->node_ptr); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_logging_rosout_add_sublogger(nullptr, nullptr)); @@ -413,8 +388,7 @@ TEST_F( /* Testing rosout message while adding and removing sublogger */ -TEST_F( - CLASSNAME(TestLogRosoutFixtureGeneral, RMW_IMPLEMENTATION), test_add_remove_sublogger_message) +TEST_F(TestLogRosoutFixtureGeneral, test_add_remove_sublogger_message) { const char * logger_name = rcl_node_get_logger_name(this->node_ptr); const char * sublogger_name = "child"; @@ -447,9 +421,7 @@ TEST_F( /* Testing rosout message while adding and removing sublogger multiple times */ -TEST_F( - CLASSNAME(TestLogRosoutFixtureGeneral, RMW_IMPLEMENTATION), - test_multi_add_remove_sublogger_message) +TEST_F(TestLogRosoutFixtureGeneral, test_multi_add_remove_sublogger_message) { const char * logger_name = rcl_node_get_logger_name(this->node_ptr); const char * sublogger_name = "child"; diff --git a/rcl/test/rcl/test_network_flow_endpoints.cpp b/rcl/test/rcl/test_network_flow_endpoints.cpp index 12b1b87f3..857a4516c 100644 --- a/rcl/test/rcl/test_network_flow_endpoints.cpp +++ b/rcl/test/rcl/test_network_flow_endpoints.cpp @@ -26,14 +26,7 @@ #include "./allocator_testing_utils.h" #include "../mocking_utils/patch.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 (TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) : public ::testing::Test +class TestNetworkFlowEndpointsNode : public ::testing::Test { public: rcl_context_t * context_ptr; @@ -75,8 +68,7 @@ class CLASSNAME (TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) : public ::te } }; -class CLASSNAME (TestPublisherNetworkFlowEndpoints, RMW_IMPLEMENTATION) - : public CLASSNAME(TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) +class TestPublisherNetworkFlowEndpoints : public TestNetworkFlowEndpointsNode { public: const rosidl_message_type_support_t * ts = @@ -95,7 +87,7 @@ class CLASSNAME (TestPublisherNetworkFlowEndpoints, RMW_IMPLEMENTATION) void SetUp() override { - CLASSNAME(TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) ::SetUp(); + TestNetworkFlowEndpointsNode::SetUp(); publisher_1 = rcl_get_zero_initialized_publisher(); publisher_1_options = rcl_publisher_get_default_options(); @@ -136,12 +128,11 @@ class CLASSNAME (TestPublisherNetworkFlowEndpoints, RMW_IMPLEMENTATION) ret = rcl_publisher_fini(&publisher_3, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - CLASSNAME(TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) ::TearDown(); + TestNetworkFlowEndpointsNode::TearDown(); } }; -class CLASSNAME (TestSubscriptionNetworkFlowEndpoints, RMW_IMPLEMENTATION) - : public CLASSNAME(TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) +class TestSubscriptionNetworkFlowEndpoints : public TestNetworkFlowEndpointsNode { public: const rosidl_message_type_support_t * ts = @@ -160,7 +151,7 @@ class CLASSNAME (TestSubscriptionNetworkFlowEndpoints, RMW_IMPLEMENTATION) void SetUp() override { - CLASSNAME(TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) ::SetUp(); + TestNetworkFlowEndpointsNode::SetUp(); subscription_1 = rcl_get_zero_initialized_subscription(); subscription_1_options = rcl_subscription_get_default_options(); @@ -201,14 +192,11 @@ class CLASSNAME (TestSubscriptionNetworkFlowEndpoints, RMW_IMPLEMENTATION) ret = rcl_subscription_fini(&subscription_3, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - CLASSNAME(TestNetworkFlowEndpointsNode, RMW_IMPLEMENTATION) ::TearDown(); + TestNetworkFlowEndpointsNode::TearDown(); } }; -TEST_F( - CLASSNAME( - TestPublisherNetworkFlowEndpoints, - RMW_IMPLEMENTATION), test_publisher_get_network_flow_endpoints_errors) { +TEST_F(TestPublisherNetworkFlowEndpoints, test_publisher_get_network_flow_endpoints_errors) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t failing_allocator = get_failing_allocator(); @@ -248,10 +236,7 @@ TEST_F( rcl_reset_error(); } -TEST_F( - CLASSNAME( - TestPublisherNetworkFlowEndpoints, - RMW_IMPLEMENTATION), test_publisher_get_network_flow_endpoints) { +TEST_F(TestPublisherNetworkFlowEndpoints, test_publisher_get_network_flow_endpoints) { rcl_ret_t ret_1; rcl_ret_t ret_2; rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -312,10 +297,7 @@ TEST_F( rcl_reset_error(); } -TEST_F( - CLASSNAME( - TestSubscriptionNetworkFlowEndpoints, - RMW_IMPLEMENTATION), test_subscription_get_network_flow_endpoints_errors) { +TEST_F(TestSubscriptionNetworkFlowEndpoints, test_subscription_get_network_flow_endpoints_errors) { rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t failing_allocator = get_failing_allocator(); @@ -355,10 +337,7 @@ TEST_F( rcl_reset_error(); } -TEST_F( - CLASSNAME( - TestSubscriptionNetworkFlowEndpoints, - RMW_IMPLEMENTATION), test_subscription_get_network_flow_endpoints) { +TEST_F(TestSubscriptionNetworkFlowEndpoints, test_subscription_get_network_flow_endpoints) { rcl_ret_t ret_1; rcl_ret_t ret_2; rcl_allocator_t allocator = rcl_get_default_allocator(); diff --git a/rcl/test/rcl/test_node.cpp b/rcl/test/rcl/test_node.cpp index 8ab234721..314023287 100644 --- a/rcl/test/rcl/test_node.cpp +++ b/rcl/test/rcl/test_node.cpp @@ -37,13 +37,6 @@ #include "../mocking_utils/patch.hpp" #include "./arg_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 - using osrf_testing_tools_cpp::memory_tools::on_unexpected_malloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc; using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc; @@ -71,7 +64,7 @@ bool operator==( lhs.avoid_ros_namespace_conventions == rhs.avoid_ros_namespace_conventions; } -class CLASSNAME (TestNodeFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestNodeFixture : public ::testing::Test { public: void SetUp() @@ -107,7 +100,7 @@ class CLASSNAME (TestNodeFixture, RMW_IMPLEMENTATION) : public ::testing::Test /* Tests the node accessors, i.e. rcl_node_get_* functions. */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) { +TEST_F(TestNodeFixture, test_rcl_node_accessors) { osrf_testing_tools_cpp::memory_tools::enable_monitoring_in_all_threads(); rcl_ret_t ret; // Initialize rcl with rcl_init(). @@ -354,7 +347,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) /* Tests the node life cycle, including rcl_node_init() and rcl_node_fini(). */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) { +TEST_F(TestNodeFixture, test_rcl_node_life_cycle) { rcl_ret_t ret; rcl_context_t context = rcl_get_zero_initialized_context(); rcl_node_t node = rcl_get_zero_initialized_node(); @@ -428,7 +421,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) EXPECT_EQ(RCL_RET_OK, ret); } -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_init_with_internal_errors) { +TEST_F(TestNodeFixture, test_rcl_node_init_with_internal_errors) { // We always call rcutils_logging_shutdown(), even if we didn't explicitly // initialize it. That's because some internals of rcl may implicitly // initialize it, so we have to do this not to leak memory. It doesn't @@ -555,7 +548,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_init_with_i /* Tests the node name restrictions enforcement. */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restrictions) { +TEST_F(TestNodeFixture, test_rcl_node_name_restrictions) { rcl_ret_t ret; // Initialize rcl with rcl_init(). @@ -623,7 +616,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri /* Tests the node namespace restrictions enforcement. */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_restrictions) { +TEST_F(TestNodeFixture, test_rcl_node_namespace_restrictions) { rcl_ret_t ret; // Initialize rcl with rcl_init(). @@ -729,7 +722,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r /* Tests the logger name as well as fully qualified name associated with the node. */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names) { +TEST_F(TestNodeFixture, test_rcl_node_names) { rcl_ret_t ret; // Initialize rcl with rcl_init(). @@ -859,7 +852,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names) { /* Tests the node_options functionality */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options) { +TEST_F(TestNodeFixture, test_rcl_node_options) { rcl_node_options_t default_options = rcl_node_get_default_options(); rcl_node_options_t not_ini_options = rcl_node_get_default_options(); memset(¬_ini_options.rosout_qos, 0, sizeof(rmw_qos_profile_t)); @@ -904,7 +897,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options) { /* Tests special case node_options */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options_fail) { +TEST_F(TestNodeFixture, test_rcl_node_options_fail) { rcl_node_options_t prev_ini_options = rcl_node_get_default_options(); const char * argv[] = {"--ros-args"}; int argc = sizeof(argv) / sizeof(const char *); @@ -921,7 +914,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options_fai /* Tests special case node_options */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_resolve_name) { +TEST_F(TestNodeFixture, test_rcl_node_resolve_name) { rcl_allocator_t default_allocator = rcl_get_default_allocator(); char * final_name = NULL; rcl_node_t node = rcl_get_zero_initialized_node(); @@ -1021,7 +1014,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_resolve_nam /* Tests special case node_options */ -TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_get_disable_loaned_message) { +TEST_F(TestNodeFixture, test_rcl_get_disable_loaned_message) { { EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_get_disable_loaned_message(nullptr)); rcl_reset_error(); diff --git a/rcl/test/rcl/test_node_type_cache.cpp b/rcl/test/rcl/test_node_type_cache.cpp index 378f4c4d5..cf691529e 100644 --- a/rcl/test/rcl/test_node_type_cache.cpp +++ b/rcl/test/rcl/test_node_type_cache.cpp @@ -25,15 +25,7 @@ #include "rcl/node.h" #include "rcutils/env.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 (TestNodeTypeCacheFixture, RMW_IMPLEMENTATION) - : public ::testing::Test +class TestNodeTypeCacheFixture : public ::testing::Test { public: rcl_context_t * context_ptr; @@ -78,9 +70,7 @@ class CLASSNAME (TestNodeTypeCacheFixture, RMW_IMPLEMENTATION) } }; -TEST_F( - CLASSNAME(TestNodeTypeCacheFixture, RMW_IMPLEMENTATION), - test_type_cache_invalid_args) { +TEST_F(TestNodeTypeCacheFixture, test_type_cache_invalid_args) { const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_type_info_t type_info; @@ -129,9 +119,7 @@ TEST_F( rcl_reset_error(); } -TEST_F( - CLASSNAME(TestNodeTypeCacheFixture, RMW_IMPLEMENTATION), - test_type_registration_count) { +TEST_F(TestNodeTypeCacheFixture, test_type_registration_count) { const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); rcl_type_info_t type_info; @@ -174,9 +162,7 @@ TEST_F( this->node_ptr, ts->get_type_hash_func(ts), &type_info)); } -TEST_F( - CLASSNAME(TestNodeTypeCacheFixture, RMW_IMPLEMENTATION), - test_invalid_unregistration) { +TEST_F(TestNodeTypeCacheFixture, test_invalid_unregistration) { const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); EXPECT_EQ( diff --git a/rcl/test/rcl/test_publisher.cpp b/rcl/test/rcl/test_publisher.cpp index 0a4249218..a303241e8 100644 --- a/rcl/test/rcl/test_publisher.cpp +++ b/rcl/test/rcl/test_publisher.cpp @@ -33,14 +33,7 @@ #include "./publisher_impl.h" #include "../mocking_utils/patch.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 (TestPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestPublisherFixture : public ::testing::Test { public: rcl_context_t * context_ptr; @@ -82,8 +75,7 @@ class CLASSNAME (TestPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::T } }; -class CLASSNAME (TestPublisherFixtureInit, RMW_IMPLEMENTATION) - : public CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION) +class TestPublisherFixtureInit : public TestPublisherFixture { public: const rosidl_message_type_support_t * ts = @@ -94,7 +86,7 @@ class CLASSNAME (TestPublisherFixtureInit, RMW_IMPLEMENTATION) void SetUp() override { - CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION) ::SetUp(); + TestPublisherFixture::SetUp(); publisher = rcl_get_zero_initialized_publisher(); publisher_options = rcl_publisher_get_default_options(); rcl_ret_t ret = rcl_publisher_init( @@ -106,13 +98,13 @@ class CLASSNAME (TestPublisherFixtureInit, RMW_IMPLEMENTATION) { rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION) ::TearDown(); + TestPublisherFixture::TearDown(); } }; /* Basic nominal test of a publisher. */ -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal) { +TEST_F(TestPublisherFixture, test_publisher_nominal) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -138,7 +130,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin /* Basic nominal test of a publisher with a string. */ -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal_string) { +TEST_F(TestPublisherFixture, test_publisher_nominal_string) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -166,7 +158,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin * not support publishers on topics with the same basename (but different namespaces) using * different message types, because at the time partitions were used for implementing namespaces. */ -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_different_types) { +TEST_F(TestPublisherFixture, test_publishers_different_types) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts_int = @@ -215,7 +207,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff /* Testing the publisher init and fini functions. */ -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_fini) { +TEST_F(TestPublisherFixture, test_publisher_init_fini) { rcl_ret_t ret; // Setup valid inputs. rcl_publisher_t publisher; @@ -340,7 +332,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_ rcl_reset_error(); } -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_loan) { +TEST_F(TestPublisherFixture, test_publisher_loan) { rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); @@ -372,7 +364,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_loan) } } -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_option) { +TEST_F(TestPublisherFixture, test_publisher_option) { { rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); EXPECT_FALSE(publisher_options.disable_loaned_message); @@ -399,7 +391,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_optio } } -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_loan_disable) { +TEST_F(TestPublisherFixture, test_publisher_loan_disable) { bool is_fastdds = (std::string(rmw_get_implementation_identifier()).find("rmw_fastrtps") == 0); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); @@ -442,7 +434,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_loan_ } } -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_invalid_publisher) { +TEST_F(TestPublisherFixture, test_invalid_publisher) { rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); @@ -623,9 +615,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_invalid_publish // Mocking rmw_publisher_count_matched_subscriptions to make // rcl_publisher_get_subscription_count fail -TEST_F( - CLASSNAME(TestPublisherFixtureInit, RMW_IMPLEMENTATION), - test_mock_publisher_get_subscription_count) +TEST_F(TestPublisherFixtureInit, test_mock_publisher_get_subscription_count) { auto mock = mocking_utils::patch_and_return( "lib:rcl", rmw_publisher_count_matched_subscriptions, RMW_RET_BAD_ALLOC); @@ -641,7 +631,7 @@ TEST_F( // Mocking rmw_publisher_assert_liveliness to make // rcl_publisher_assert_liveliness fail -TEST_F(CLASSNAME(TestPublisherFixtureInit, RMW_IMPLEMENTATION), test_mock_assert_liveliness) { +TEST_F(TestPublisherFixtureInit, test_mock_assert_liveliness) { auto mock = mocking_utils::patch_and_return( "lib:rcl", rmw_publisher_assert_liveliness, RMW_RET_ERROR); @@ -660,9 +650,7 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rmw_time_t, !=) MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rmw_time_t, <) MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rmw_time_t, >) -TEST_F( - CLASSNAME(TestPublisherFixtureInit, RMW_IMPLEMENTATION), - test_mock_assert_wait_for_all_acked) +TEST_F(TestPublisherFixtureInit, test_mock_assert_wait_for_all_acked) { #define CHECK_PUBLISHER_WAIT_FOR_ALL_ACKED_RETURN(RMW_RET_RESULT, EXPECT_RET) do { \ rmw_publisher_wait_for_all_acked_return = RMW_RET_RESULT; \ @@ -713,7 +701,7 @@ TEST_F( } // Mocking rmw_publish to make rcl_publish fail -TEST_F(CLASSNAME(TestPublisherFixtureInit, RMW_IMPLEMENTATION), test_mock_publish) { +TEST_F(TestPublisherFixtureInit, test_mock_publish) { auto mock = mocking_utils::patch_and_return("lib:rcl", rmw_publish, RMW_RET_ERROR); // Test normal usage of the function rcl_publish returning unexpected RMW_RET_ERROR @@ -728,8 +716,7 @@ TEST_F(CLASSNAME(TestPublisherFixtureInit, RMW_IMPLEMENTATION), test_mock_publis } // Mocking rmw_publish_serialized_message to make rcl_publish_serialized_message fail -TEST_F( - CLASSNAME(TestPublisherFixtureInit, RMW_IMPLEMENTATION), test_mock_publish_serialized_message) +TEST_F(TestPublisherFixtureInit, test_mock_publish_serialized_message) { rcl_serialized_message_t serialized_msg = rmw_get_zero_initialized_serialized_message(); size_t initial_size_serialized = 0u; @@ -780,7 +767,7 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, <) MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, >) MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, !=) -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mock_publisher_init) { +TEST_F(TestPublisherFixture, test_mock_publisher_init) { rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); @@ -795,8 +782,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mock_publisher_ rcl_reset_error(); } -TEST_F( - CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mock_publisher_init_fail_qos) +TEST_F(TestPublisherFixture, test_mock_publisher_init_fail_qos) { auto mock = mocking_utils::patch_and_return( "lib:rcl", rmw_publisher_get_actual_qos, RMW_RET_ERROR); @@ -814,7 +800,7 @@ TEST_F( } // Tests for loaned msgs functions. Mocked as the rmw tier1 vendors don't support it -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mock_loaned_functions) { +TEST_F(TestPublisherFixture, test_mock_loaned_functions) { rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_publisher_t not_init_publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -906,7 +892,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mock_loaned_fun } // Tests mocking ini/fini functions for specific failures -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mocks_fail_publisher_init) { +TEST_F(TestPublisherFixture, test_mocks_fail_publisher_init) { rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); @@ -959,7 +945,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mocks_fail_publ } // Test mocked fail fini publisher -TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_mock_publisher_fini_fail) { +TEST_F(TestPublisherFixture, test_mock_publisher_fini_fail) { rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); diff --git a/rcl/test/rcl/test_publisher_wait_all_ack.cpp b/rcl/test/rcl/test_publisher_wait_all_ack.cpp index 6371eb4d0..7aa00ad6a 100644 --- a/rcl/test/rcl/test_publisher_wait_all_ack.cpp +++ b/rcl/test/rcl/test_publisher_wait_all_ack.cpp @@ -34,17 +34,9 @@ #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - - /* This class is used for test_wait_for_all_acked */ -class CLASSNAME (TestPublisherFixtureSpecial, RMW_IMPLEMENTATION) : public ::testing::Test +class TestPublisherFixtureSpecial : public ::testing::Test { public: rcl_context_t * context_ptr; @@ -118,7 +110,7 @@ class CLASSNAME (TestPublisherFixtureSpecial, RMW_IMPLEMENTATION) : public ::tes #define ONE_MEGABYTE (1024 * 1024) -TEST_F(CLASSNAME(TestPublisherFixtureSpecial, RMW_IMPLEMENTATION), test_wait_for_all_acked) { +TEST_F(TestPublisherFixtureSpecial, test_wait_for_all_acked) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -183,9 +175,7 @@ TEST_F(CLASSNAME(TestPublisherFixtureSpecial, RMW_IMPLEMENTATION), test_wait_for EXPECT_EQ(RCL_RET_OK, ret); } -TEST_F( - CLASSNAME(TestPublisherFixtureSpecial, RMW_IMPLEMENTATION), - test_wait_for_all_acked_with_best_effort) +TEST_F(TestPublisherFixtureSpecial, test_wait_for_all_acked_with_best_effort) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); diff --git a/rcl/test/rcl/test_remap.cpp b/rcl/test/rcl/test_remap.cpp index ed25fb0be..90b701544 100644 --- a/rcl/test/rcl/test_remap.cpp +++ b/rcl/test/rcl/test_remap.cpp @@ -23,14 +23,7 @@ #include "./arg_macros.hpp" #include "./arguments_impl.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 (TestRemapFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestRemapFixture : public ::testing::Test { public: void SetUp() @@ -42,7 +35,7 @@ class CLASSNAME (TestRemapFixture, RMW_IMPLEMENTATION) : public ::testing::Test } }; -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_namespace_replacement) { +TEST_F(TestRemapFixture, global_namespace_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "__ns:=/foo/bar"); @@ -55,7 +48,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_namespace_replace rcl_get_default_allocator().deallocate(output, rcl_get_default_allocator().state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_namespace_remap) { +TEST_F(TestRemapFixture, nodename_prefix_namespace_remap) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -92,7 +85,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_namespac } } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_namespace_replacement) { +TEST_F(TestRemapFixture, no_namespace_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name"); @@ -104,7 +97,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_namespace_replacement EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_namespace_replacement_before_global) { +TEST_F(TestRemapFixture, local_namespace_replacement_before_global) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "__ns:=/global_args"); @@ -119,7 +112,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_namespace_replacem rcl_get_default_allocator().deallocate(output, rcl_get_default_allocator().state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_namespace_replacement) { +TEST_F(TestRemapFixture, no_use_global_namespace_replacement) { rcl_ret_t ret; rcl_arguments_t local_arguments; SCOPE_ARGS(local_arguments, "process_name"); @@ -131,7 +124,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_namespace_ EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_namespace_rule) { +TEST_F(TestRemapFixture, other_rules_before_namespace_rule) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -150,7 +143,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_names allocator.deallocate(output, allocator.state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_topic_name_replacement) { +TEST_F(TestRemapFixture, global_topic_name_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "/bar/foo:=/foo/bar"); @@ -172,7 +165,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_topic_name_replac } } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), topic_and_service_name_not_null) { +TEST_F(TestRemapFixture, topic_and_service_name_not_null) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "/bar/foo:=/foo/bar"); @@ -195,7 +188,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), topic_and_service_name_n } } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_topic_name_remap) { +TEST_F(TestRemapFixture, relative_topic_name_remap) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "foo:=bar"); @@ -208,7 +201,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_topic_name_rema rcl_get_default_allocator().deallocate(output, rcl_get_default_allocator().state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_topic_remap) { +TEST_F(TestRemapFixture, nodename_prefix_topic_remap) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -245,7 +238,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_topic_re } } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_topic_name_replacement) { +TEST_F(TestRemapFixture, no_use_global_topic_name_replacement) { rcl_ret_t ret; rcl_arguments_t local_arguments; SCOPE_ARGS(local_arguments, "process_name"); @@ -257,7 +250,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_topic_name EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_topic_name_replacement) { +TEST_F(TestRemapFixture, no_topic_name_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name"); @@ -269,7 +262,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_topic_name_replacemen EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_topic_replacement_before_global) { +TEST_F(TestRemapFixture, local_topic_replacement_before_global) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "/bar/foo:=/foo/global_args"); @@ -285,7 +278,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_topic_replacement_ rcl_get_default_allocator().deallocate(output, rcl_get_default_allocator().state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_topic_rule) { +TEST_F(TestRemapFixture, other_rules_before_topic_rule) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -305,7 +298,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_topic allocator.deallocate(output, allocator.state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_service_name_replacement) { +TEST_F(TestRemapFixture, global_service_name_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "/bar/foo:=/foo/bar"); @@ -327,7 +320,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_service_name_repl } } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_service_name_remap) { +TEST_F(TestRemapFixture, relative_service_name_remap) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "foo:=bar"); @@ -340,7 +333,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_service_name_re rcl_get_default_allocator().deallocate(output, rcl_get_default_allocator().state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_service_remap) { +TEST_F(TestRemapFixture, nodename_prefix_service_remap) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -377,7 +370,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_service_ } } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_service_name_replacement) { +TEST_F(TestRemapFixture, no_use_global_service_name_replacement) { rcl_ret_t ret; rcl_arguments_t local_arguments; SCOPE_ARGS(local_arguments, "process_name"); @@ -390,7 +383,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_service_na EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_service_name_replacement) { +TEST_F(TestRemapFixture, no_service_name_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name"); @@ -402,7 +395,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_service_name_replacem EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_service_replacement_before_global) { +TEST_F(TestRemapFixture, local_service_replacement_before_global) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "/bar/foo:=/foo/global_args"); @@ -418,7 +411,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_service_replacemen rcl_get_default_allocator().deallocate(output, rcl_get_default_allocator().state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_service_rule) { +TEST_F(TestRemapFixture, other_rules_before_service_rule) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -438,7 +431,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_servi allocator.deallocate(output, allocator.state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_nodename_replacement) { +TEST_F(TestRemapFixture, global_nodename_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "__node:=globalname"); @@ -451,7 +444,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_nodename_replacem allocator.deallocate(output, allocator.state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_nodename_replacement) { +TEST_F(TestRemapFixture, no_nodename_replacement) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name"); @@ -463,7 +456,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_nodename_replacement) EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_nodename_replacement_before_global) { +TEST_F(TestRemapFixture, local_nodename_replacement_before_global) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "__node:=global_name"); @@ -478,7 +471,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_nodename_replaceme rcl_get_default_allocator().deallocate(output, rcl_get_default_allocator().state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_nodename_replacement) { +TEST_F(TestRemapFixture, no_use_global_nodename_replacement) { rcl_ret_t ret; rcl_arguments_t local_arguments; SCOPE_ARGS(local_arguments, "process_name"); @@ -490,7 +483,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_nodename_r EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), use_first_nodename_rule) { +TEST_F(TestRemapFixture, use_first_nodename_rule) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -508,7 +501,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), use_first_nodename_rule) allocator.deallocate(output, allocator.state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_nodename_rule) { +TEST_F(TestRemapFixture, other_rules_before_nodename_rule) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS( @@ -527,7 +520,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_noden allocator.deallocate(output, allocator.state); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rosservice) { +TEST_F(TestRemapFixture, url_scheme_rosservice) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "rosservice://foo:=bar"); @@ -545,7 +538,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rosservice) { EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rostopic) { +TEST_F(TestRemapFixture, url_scheme_rostopic) { rcl_ret_t ret; rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "rostopic://foo:=bar"); @@ -563,7 +556,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rostopic) { EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), _rcl_remap_name_bad_arg) { +TEST_F(TestRemapFixture, _rcl_remap_name_bad_arg) { rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "__node:=global_name"); rcl_arguments_t local_arguments; @@ -597,7 +590,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), _rcl_remap_name_bad_arg) rcl_reset_error(); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), internal_remap_use) { +TEST_F(TestRemapFixture, internal_remap_use) { // Easiest way to init a rcl_remap is through the arguments API const char * argv[] = { "process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg" diff --git a/rcl/test/rcl/test_remap_integration.cpp b/rcl/test/rcl/test_remap_integration.cpp index 60ff51909..68abf4a5a 100644 --- a/rcl/test/rcl/test_remap_integration.cpp +++ b/rcl/test/rcl/test_remap_integration.cpp @@ -23,14 +23,7 @@ #include "./arg_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 (TestRemapIntegrationFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestRemapIntegrationFixture : public ::testing::Test { public: void SetUp() @@ -42,7 +35,7 @@ class CLASSNAME (TestRemapIntegrationFixture, RMW_IMPLEMENTATION) : public ::tes } }; -TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_global_rule) { +TEST_F(TestRemapIntegrationFixture, remap_using_global_rule) { int argc; char ** argv; SCOPE_GLOBAL_ARGS( @@ -113,7 +106,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g EXPECT_EQ(RCL_RET_OK, rcl_node_fini(&node)); } -TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global_rules) { +TEST_F(TestRemapIntegrationFixture, ignore_global_rules) { int argc; char ** argv; SCOPE_GLOBAL_ARGS( @@ -186,7 +179,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global EXPECT_EQ(RCL_RET_OK, rcl_node_fini(&node)); } -TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_before_global) { +TEST_F(TestRemapIntegrationFixture, local_rules_before_global) { int argc; char ** argv; SCOPE_GLOBAL_ARGS( @@ -264,7 +257,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b EXPECT_EQ(RCL_RET_OK, rcl_node_fini(&node)); } -TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relative_topic) { +TEST_F(TestRemapIntegrationFixture, remap_relative_topic) { int argc; char ** argv; SCOPE_GLOBAL_ARGS(argc, argv, "process_name", "--ros-args", "-r", "/foo/bar:=remap/global"); @@ -318,7 +311,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ EXPECT_EQ(RCL_RET_OK, rcl_node_fini(&node)); } -TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_node_rules) { +TEST_F(TestRemapIntegrationFixture, remap_using_node_rules) { int argc; char ** argv; SCOPE_GLOBAL_ARGS( diff --git a/rcl/test/rcl/test_service.cpp b/rcl/test/rcl/test_service.cpp index 60440a716..1a20f5013 100644 --- a/rcl/test/rcl/test_service.cpp +++ b/rcl/test/rcl/test_service.cpp @@ -27,14 +27,7 @@ #include "./allocator_testing_utils.h" #include "../mocking_utils/patch.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 (TestServiceFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestServiceFixture : public ::testing::Test { public: rcl_context_t * context_ptr; @@ -78,7 +71,7 @@ class CLASSNAME (TestServiceFixture, RMW_IMPLEMENTATION) : public ::testing::Tes /* Basic nominal test of a service. */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) { +TEST_F(TestServiceFixture, test_service_nominal) { rcl_ret_t ret; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); @@ -240,7 +233,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) /* Basic nominal test of a service with rcl_take_response */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_without_info) { +TEST_F(TestServiceFixture, test_service_without_info) { rcl_ret_t ret; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); @@ -338,7 +331,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_without_i /* Passing bad/invalid arguments to service functions */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_bad_arguments) { +TEST_F(TestServiceFixture, test_bad_arguments) { const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); const char * topic = "primitives"; @@ -453,7 +446,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_bad_arguments) { /* Name failed tests */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_fail_name) { +TEST_F(TestServiceFixture, test_service_fail_name) { const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); const char * topic = "white space"; @@ -477,7 +470,7 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, !=) /* Test failed service initialization using mocks */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_fail_ini_mocked) { +TEST_F(TestServiceFixture, test_fail_ini_mocked) { const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); constexpr char topic[] = "topic"; @@ -541,7 +534,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_fail_ini_mocked) /* Test failed service finalization using mocks */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_fail_fini_mocked) { +TEST_F(TestServiceFixture, test_fail_fini_mocked) { const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); constexpr char topic[] = "primitives"; @@ -565,7 +558,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_fail_fini_mocked) /* Test failed service take_request_with_info using mocks and nullptrs */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_fail_take_request_with_info) { +TEST_F(TestServiceFixture, test_fail_take_request_with_info) { const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); constexpr char topic[] = "primitives"; @@ -633,7 +626,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_fail_take_request /* Test failed service send_response using mocks and nullptrs */ -TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_fail_send_response) { +TEST_F(TestServiceFixture, test_fail_send_response) { const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( test_msgs, srv, BasicTypes); constexpr char topic[] = "primitives"; diff --git a/rcl/test/rcl/test_service_event_publisher.cpp b/rcl/test/rcl/test_service_event_publisher.cpp index f6ee979c4..e39a6c67a 100644 --- a/rcl/test/rcl/test_service_event_publisher.cpp +++ b/rcl/test/rcl/test_service_event_publisher.cpp @@ -37,14 +37,7 @@ #include "test_msgs/srv/basic_types.h" #include "wait_for_entity_helpers.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 (TestServiceEventPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestServiceEventPublisherFixture : public ::testing::Test { public: void SetUp() override @@ -108,9 +101,7 @@ class CLASSNAME (TestServiceEventPublisherFixture, RMW_IMPLEMENTATION) : public /* Basic nominal test of service introspection features covering init, fini, and sending a message */ -TEST_F( - CLASSNAME(TestServiceEventPublisherFixture, RMW_IMPLEMENTATION), - test_service_event_publisher_nominal) +TEST_F(TestServiceEventPublisherFixture, test_service_event_publisher_nominal) { rcl_service_event_publisher_t service_event_publisher = rcl_get_zero_initialized_service_event_publisher(); @@ -143,9 +134,7 @@ TEST_F( EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } -TEST_F( - CLASSNAME(TestServiceEventPublisherFixture, RMW_IMPLEMENTATION), - test_service_event_publisher_init_and_fini) +TEST_F(TestServiceEventPublisherFixture, test_service_event_publisher_init_and_fini) { rcl_service_event_publisher_t service_event_publisher = rcl_get_zero_initialized_service_event_publisher(); @@ -207,9 +196,7 @@ TEST_F( /* Test sending service introspection message via service_event_publisher.h */ -TEST_F( - CLASSNAME(TestServiceEventPublisherFixture, RMW_IMPLEMENTATION), - test_service_event_publisher_send_message_nominal) +TEST_F(TestServiceEventPublisherFixture, test_service_event_publisher_send_message_nominal) { uint8_t guid[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; auto sub_opts = rcl_subscription_get_default_options(); @@ -276,9 +263,7 @@ TEST_F( ASSERT_EQ(test_req.uint32_value, event_msg.request.data[0].uint32_value); } -TEST_F( - CLASSNAME(TestServiceEventPublisherFixture, RMW_IMPLEMENTATION), - test_service_event_publisher_send_message_return_codes) +TEST_F(TestServiceEventPublisherFixture, test_service_event_publisher_send_message_return_codes) { rcl_ret_t ret; @@ -327,9 +312,7 @@ TEST_F( EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } -TEST_F( - CLASSNAME(TestServiceEventPublisherFixture, RMW_IMPLEMENTATION), - test_service_event_publisher_utils) +TEST_F(TestServiceEventPublisherFixture, test_service_event_publisher_utils) { rcl_ret_t ret; @@ -368,7 +351,7 @@ TEST_F( } TEST_F( - CLASSNAME(TestServiceEventPublisherFixture, RMW_IMPLEMENTATION), + TestServiceEventPublisherFixture, test_service_event_publisher_enable_and_disable_return_codes) { rcl_ret_t ret; @@ -404,8 +387,7 @@ TEST_F( EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } -class CLASSNAME (TestServiceEventPublisherWithServicesAndClientsFixture, RMW_IMPLEMENTATION) - : public ::testing::Test +class TestServiceEventPublisherWithServicesAndClientsFixture : public ::testing::Test { public: void SetUp() @@ -522,7 +504,7 @@ class CLASSNAME (TestServiceEventPublisherWithServicesAndClientsFixture, RMW_IMP /* Whole test of service event publisher with service, client, and subscription */ TEST_F( - CLASSNAME(TestServiceEventPublisherWithServicesAndClientsFixture, RMW_IMPLEMENTATION), + TestServiceEventPublisherWithServicesAndClientsFixture, test_service_event_publisher_with_subscriber) { rcl_ret_t ret; @@ -614,7 +596,7 @@ TEST_F( /* Integration level test with disabling service events */ TEST_F( - CLASSNAME(TestServiceEventPublisherWithServicesAndClientsFixture, RMW_IMPLEMENTATION), + TestServiceEventPublisherWithServicesAndClientsFixture, test_service_event_publisher_with_subscriber_disable_service_events) { rcl_ret_t ret; diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index fe58e20c1..dbb7435d1 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -41,27 +41,7 @@ #include "./allocator_testing_utils.h" #include "../mocking_utils/patch.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - -#define EXPAND(x) x -#define TEST_FIXTURE_P_RMW(test_fixture_name) CLASSNAME( \ - test_fixture_name, RMW_IMPLEMENTATION) -#define APPLY(macro, ...) EXPAND(macro(__VA_ARGS__)) -#define TEST_P_RMW(test_case_name, test_name) \ - APPLY( \ - TEST_P, CLASSNAME(test_case_name, RMW_IMPLEMENTATION), test_name) -#define INSTANTIATE_TEST_SUITE_P_RMW(instance_name, test_case_name, ...) \ - EXPAND( \ - APPLY( \ - INSTANTIATE_TEST_SUITE_P, instance_name, \ - CLASSNAME(test_case_name, RMW_IMPLEMENTATION), __VA_ARGS__)) - -class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class TestSubscriptionFixture : public ::testing::Test { public: rcl_context_t * context_ptr; @@ -103,8 +83,7 @@ class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing } }; -class CLASSNAME (TestSubscriptionFixtureInit, RMW_IMPLEMENTATION) - : public CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION) +class TestSubscriptionFixtureInit : public TestSubscriptionFixture { public: const rosidl_message_type_support_t * ts = @@ -118,7 +97,7 @@ class CLASSNAME (TestSubscriptionFixtureInit, RMW_IMPLEMENTATION) void SetUp() override { - CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION) ::SetUp(); + TestSubscriptionFixture::SetUp(); allocator = rcutils_get_default_allocator(); subscription_options = rcl_subscription_get_default_options(); subscription = rcl_get_zero_initialized_subscription(); @@ -131,15 +110,13 @@ class CLASSNAME (TestSubscriptionFixtureInit, RMW_IMPLEMENTATION) { rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION) ::TearDown(); + TestSubscriptionFixture::TearDown(); } }; /* Test subscription init, fini and is_valid functions */ -TEST_F( - CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), - test_subscription_init_fini_and_is_valid) +TEST_F(TestSubscriptionFixture, test_subscription_init_fini_and_is_valid) { rcl_ret_t ret; @@ -174,7 +151,7 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, <) MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, >) // Bad arguments for init and fini -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_bad_init) { +TEST_F(TestSubscriptionFixture, test_subscription_bad_init) { const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); constexpr char topic[] = "/chatter"; @@ -284,7 +261,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription /* Basic nominal test of a subscription */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal) { +TEST_F(TestSubscriptionFixture, test_subscription_nominal) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -357,7 +334,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription /* Basic nominal test of a publisher with a string. */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal_string) { +TEST_F(TestSubscriptionFixture, test_subscription_nominal_string) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -406,10 +383,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription /* Basic nominal test of a subscription taking a sequence. */ -TEST_F( - CLASSNAME( - TestSubscriptionFixture, - RMW_IMPLEMENTATION), test_subscription_nominal_string_sequence) { +TEST_F(TestSubscriptionFixture, test_subscription_nominal_string_sequence) { using namespace std::chrono_literals; rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); @@ -578,7 +552,7 @@ TEST_F( /* Basic nominal test of a subscription with take_serialize msg */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_serialized) { +TEST_F(TestSubscriptionFixture, test_subscription_serialized) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcutils_allocator_t allocator = rcl_get_default_allocator(); @@ -654,7 +628,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription /* Basic test for subscription loan functions */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_loaned) { +TEST_F(TestSubscriptionFixture, test_subscription_loaned) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -733,7 +707,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription } } -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_option) { +TEST_F(TestSubscriptionFixture, test_subscription_option) { { rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); EXPECT_TRUE(subscription_options.disable_loaned_message); @@ -760,7 +734,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription } } -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_loan_disable) { +TEST_F(TestSubscriptionFixture, test_subscription_loan_disable) { bool is_fastdds = (std::string(rmw_get_implementation_identifier()).find("rmw_fastrtps") == 0); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); @@ -805,7 +779,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription /* Test for all failure modes in subscription take with loaned messages function. */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loaned_message) { +TEST_F(TestSubscriptionFixture, test_bad_take_loaned_message) { constexpr char topic[] = "rcl_loan"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); @@ -878,7 +852,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loa /* Test for all failure modes in subscription return loaned messages function. */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_return_loaned_message) { +TEST_F(TestSubscriptionFixture, test_bad_return_loaned_message) { constexpr char topic[] = "rcl_loan"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); @@ -940,10 +914,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_return_l /* A subscription with a content filtered topic setting. */ -TEST_F( - CLASSNAME( - TestSubscriptionFixture, - RMW_IMPLEMENTATION), test_subscription_content_filtered) { +TEST_F(TestSubscriptionFixture, test_subscription_content_filtered) { const char * filter_expression1 = "string_value = 'FilteredData'"; rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); @@ -1213,10 +1184,7 @@ TEST_F( /* A subscription without a content filtered topic setting at beginning. */ -TEST_F( - CLASSNAME( - TestSubscriptionFixture, - RMW_IMPLEMENTATION), test_subscription_not_initialized_with_content_filtering) { +TEST_F(TestSubscriptionFixture, test_subscription_not_initialized_with_content_filtering) { rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = @@ -1369,7 +1337,7 @@ TEST_F( } } -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) { +TEST_F(TestSubscriptionFixture, test_get_options) { rcl_ret_t ret; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); @@ -1395,7 +1363,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) /* bad take() */ -TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_take) { +TEST_F(TestSubscriptionFixtureInit, test_subscription_bad_take) { test_msgs__msg__BasicTypes msg; rmw_message_info_t message_info = rmw_get_zero_initialized_message_info(); ASSERT_TRUE(test_msgs__msg__BasicTypes__init(&msg)); @@ -1434,9 +1402,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscrip /* bad take_serialized */ -TEST_F( - CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), - test_subscription_bad_take_serialized) { +TEST_F(TestSubscriptionFixtureInit, test_subscription_bad_take_serialized) { rcl_serialized_message_t serialized_msg = rmw_get_zero_initialized_serialized_message(); size_t initial_serialization_capacity = 0u; ASSERT_EQ( @@ -1490,8 +1456,7 @@ TEST_F( /* Bad arguments take_sequence */ -TEST_F( - CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_take_sequence) +TEST_F(TestSubscriptionFixtureInit, test_subscription_bad_take_sequence) { size_t seq_size = 3u; rmw_message_sequence_t messages; @@ -1572,7 +1537,7 @@ TEST_F( /* Test for all failure modes in subscription get_publisher_count function. */ -TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_bad_get_publisher_count) { +TEST_F(TestSubscriptionFixtureInit, test_bad_get_publisher_count) { size_t publisher_count = 0; EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, @@ -1599,7 +1564,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_bad_get_ /* Using bad arguments subscription methods */ -TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_argument) { +TEST_F(TestSubscriptionFixtureInit, test_subscription_bad_argument) { EXPECT_EQ(NULL, rcl_subscription_get_actual_qos(nullptr)); rcl_reset_error(); EXPECT_FALSE(rcl_subscription_can_loan_messages(nullptr)); @@ -1629,10 +1594,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscrip /* Test for all failure modes in rcl_subscription_set_content_filter function. */ -TEST_F( - CLASSNAME( - TestSubscriptionFixtureInit, - RMW_IMPLEMENTATION), test_bad_rcl_subscription_set_content_filter) { +TEST_F(TestSubscriptionFixtureInit, test_bad_rcl_subscription_set_content_filter) { EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, rcl_subscription_set_content_filter(nullptr, nullptr)); @@ -1692,10 +1654,7 @@ TEST_F( /* Test for all failure modes in rcl_subscription_get_content_filter function. */ -TEST_F( - CLASSNAME( - TestSubscriptionFixtureInit, - RMW_IMPLEMENTATION), test_bad_rcl_subscription_get_content_filter) { +TEST_F(TestSubscriptionFixtureInit, test_bad_rcl_subscription_get_content_filter) { EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, rcl_subscription_get_content_filter(nullptr, nullptr)); @@ -1735,7 +1694,7 @@ TEST_F( } } -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_init_fini_maybe_fail) +TEST_F(TestSubscriptionFixture, test_init_fini_maybe_fail) { const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); @@ -1776,15 +1735,14 @@ struct TestParameters TYPESUPPORT sub_ts_; }; -class TEST_FIXTURE_P_RMW (TestSubscriptionFixtureParam) - : public TEST_FIXTURE_P_RMW(TestSubscriptionFixture), +class TestSubscriptionFixtureParam : public TestSubscriptionFixture, public ::testing::WithParamInterface { protected: void SetUp() { param_ = GetParam(); - TEST_FIXTURE_P_RMW(TestSubscriptionFixture) ::SetUp(); + TestSubscriptionFixture::SetUp(); } TestParameters param_; @@ -1793,7 +1751,7 @@ class TEST_FIXTURE_P_RMW (TestSubscriptionFixtureParam) /* Test subscription to receive complex message from a publisher with typesupport settings. */ -TEST_P_RMW(TestSubscriptionFixtureParam, test_subscription_complex_message) { +TEST_P(TestSubscriptionFixtureParam, test_subscription_complex_message) { rcl_ret_t ret; const rosidl_message_type_support_t * ts_pub; const rosidl_message_type_support_t * ts_sub; @@ -1870,7 +1828,7 @@ TEST_P_RMW(TestSubscriptionFixtureParam, test_subscription_complex_message) { } } -INSTANTIATE_TEST_SUITE_P_RMW( +INSTANTIATE_TEST_SUITE_P( TestSubscriptionFixtureParamWithDifferentSettings, TestSubscriptionFixtureParam, ::testing::Values( diff --git a/rcl/test/rcl/test_wait.cpp b/rcl/test/rcl/test_wait.cpp index daadfbf66..626d047dc 100644 --- a/rcl/test/rcl/test_wait.cpp +++ b/rcl/test/rcl/test_wait.cpp @@ -32,20 +32,13 @@ #include "./allocator_testing_utils.h" #include "../mocking_utils/patch.hpp" -#ifdef RMW_IMPLEMENTATION -# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX -# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) -#else -# define CLASSNAME(NAME, SUFFIX) NAME -#endif - #ifndef _WIN32 #define TOLERANCE RCL_MS_TO_NS(6) #else #define TOLERANCE RCL_MS_TO_NS(25) #endif -class CLASSNAME (WaitSetTestFixture, RMW_IMPLEMENTATION) : public ::testing::Test +class WaitSetTestFixture : public ::testing::Test { public: rcl_context_t * context_ptr; @@ -73,7 +66,7 @@ class CLASSNAME (WaitSetTestFixture, RMW_IMPLEMENTATION) : public ::testing::Tes } }; -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_is_valid) { +TEST_F(WaitSetTestFixture, wait_set_is_valid) { // null pointers are invalid EXPECT_FALSE(rcl_wait_set_is_valid(nullptr)); @@ -93,7 +86,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_is_valid) { EXPECT_FALSE(rcl_wait_set_is_valid(&wait_set)); } -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), test_failed_resize) { +TEST_F(WaitSetTestFixture, test_failed_resize) { // Initialize a wait set with a subscription and then resize it to zero. rcl_allocator_t allocator = get_failing_allocator(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); @@ -112,7 +105,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), test_failed_resize) { ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), test_resize_to_zero) { +TEST_F(WaitSetTestFixture, test_resize_to_zero) { // Initialize a wait set with a subscription and then resize it to zero. rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = @@ -133,7 +126,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), test_resize_to_zero) { } // Test rcl_wait with a positive finite timeout value (1ms) -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), finite_timeout) { +TEST_F(WaitSetTestFixture, finite_timeout) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -153,7 +146,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), finite_timeout) { } // Check that a timer overrides a negative timeout value (blocking forever) -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) { +TEST_F(WaitSetTestFixture, negative_timeout) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -212,7 +205,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) { } // Test rcl_wait with a timeout value of 0 (non-blocking) -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) { +TEST_F(WaitSetTestFixture, zero_timeout) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -248,7 +241,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) { } // Test rcl_wait with a timeout value of 0 (non-blocking) and an already triggered guard condition -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered_guard_condition) { +TEST_F(WaitSetTestFixture, zero_timeout_triggered_guard_condition) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 0, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -285,7 +278,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered } // Test rcl_wait with a timeout value and an overrun timer -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_overrun_timer) { +TEST_F(WaitSetTestFixture, zero_timeout_overrun_timer) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -329,7 +322,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_overrun_t } // Check that a canceled timer doesn't wake up rcl_wait -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) { +TEST_F(WaitSetTestFixture, canceled_timer) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -390,7 +383,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) { } // Test rcl_wait_set_t with excess capacity works. -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), excess_capacity) { +TEST_F(WaitSetTestFixture, excess_capacity) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 42, 42, 42, 42, 42, 0, context_ptr, rcl_get_default_allocator()); @@ -407,7 +400,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), excess_capacity) { } // Check rcl_wait can be called in many threads, each with unique wait sets and resources. -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threaded) { +TEST_F(WaitSetTestFixture, multi_wait_set_threaded) { rcl_ret_t ret; const size_t number_of_threads = 20; // concurrent waits const size_t count_target = 10; // number of times each wait should wake up before being "done" @@ -541,7 +534,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade // Check the interaction of a guard condition and a negative timeout by // triggering a guard condition in a separate thread -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) { +TEST_F(WaitSetTestFixture, guard_condition) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 0, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -591,7 +584,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) { } // Check that index arguments are properly set when adding entities -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), add_with_index) { +TEST_F(WaitSetTestFixture, add_with_index) { const size_t kNumEntities = 3u; rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init( @@ -626,7 +619,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), add_with_index) { } // Extra invalid arguments not tested -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_valid_arguments) { +TEST_F(WaitSetTestFixture, wait_set_valid_arguments) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 0, 0, context_ptr, rcl_get_default_allocator()); @@ -683,7 +676,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_valid_argumen } // Test get allocator function -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_get_allocator) { +TEST_F(WaitSetTestFixture, wait_set_get_allocator) { rcl_allocator_t allocator_returned; rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); @@ -711,7 +704,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_get_allocator } // Test wait set init failure cases using mocks -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_failed_init) { +TEST_F(WaitSetTestFixture, wait_set_failed_init) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); // Mock rmw implementation to fail init auto mock = mocking_utils::patch_and_return( @@ -724,7 +717,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_failed_init) } // Test wait set fini failure cases using mocks -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_failed_fini) { +TEST_F(WaitSetTestFixture, wait_set_failed_fini) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 1, 1, 1, 1, 0, context_ptr, rcl_get_default_allocator()); @@ -740,7 +733,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_failed_fini) } // Test proper error handling with a fault injection test -TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), wait_set_test_maybe_init_fail) { +TEST_F(WaitSetTestFixture, wait_set_test_maybe_init_fail) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = RCL_RET_OK; rcl_allocator_t alloc = rcl_get_default_allocator();