From adb2e7f9504595b1dafcfe76e33b7b6137b69f90 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Thu, 20 Aug 2020 12:22:21 -0300 Subject: [PATCH 1/2] Complete publisher/subscription QoS query API test coverage. Signed-off-by: Michel Hidalgo --- test_rmw_implementation/CMakeLists.txt | 4 ++-- .../test/test_publisher.cpp | 23 +++++++++++++++++-- .../test/test_subscription.cpp | 16 +++++++++++-- 3 files changed, 37 insertions(+), 6 deletions(-) diff --git a/test_rmw_implementation/CMakeLists.txt b/test_rmw_implementation/CMakeLists.txt index e08a439a..f2c6ba36 100644 --- a/test_rmw_implementation/CMakeLists.txt +++ b/test_rmw_implementation/CMakeLists.txt @@ -65,7 +65,7 @@ if(BUILD_TESTING) target_compile_definitions(test_publisher${target_suffix} PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") ament_target_dependencies(test_publisher${target_suffix} - rcutils rmw rmw_implementation test_msgs + osrf_testing_tools_cpp rcutils rmw rmw_implementation test_msgs ) ament_add_gtest(test_subscription${target_suffix} @@ -75,7 +75,7 @@ if(BUILD_TESTING) target_compile_definitions(test_subscription${target_suffix} PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") ament_target_dependencies(test_subscription${target_suffix} - rcutils rmw rmw_implementation test_msgs + osrf_testing_tools_cpp rcutils rmw rmw_implementation test_msgs ) ament_add_gtest(test_serialize_deserialize${target_suffix} diff --git a/test_rmw_implementation/test/test_publisher.cpp b/test_rmw_implementation/test/test_publisher.cpp index 5026b5b3..6d2f3081 100644 --- a/test_rmw_implementation/test/test_publisher.cpp +++ b/test_rmw_implementation/test/test_publisher.cpp @@ -14,6 +14,8 @@ #include +#include "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp" + #include "rcutils/allocator.h" #include "rcutils/strdup.h" @@ -177,6 +179,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_bad_arguments) } TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), get_actual_qos_from_system_defaults) { + osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -185,7 +188,11 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), get_actual_qos_from_system_ rmw_create_publisher(node, ts, topic_name, &rmw_qos_profile_system_default, &options); ASSERT_NE(nullptr, pub) << rmw_get_error_string().str; rmw_qos_profile_t qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret = rmw_publisher_get_actual_qos(pub, &qos_profile); + rmw_ret_t ret; + EXPECT_NO_MEMORY_OPERATIONS( + { + ret = rmw_publisher_get_actual_qos(pub, &qos_profile); + }); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; // Check that a valid QoS policy has been put in place for each system default one. EXPECT_NE(rmw_qos_profile_system_default.history, qos_profile.history); @@ -239,11 +246,23 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos_with_bad_ ret = rmw_publisher_get_actual_qos(pub, nullptr); EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret); rmw_reset_error(); + + const char * implementation_identifier = pub->implementation_identifier; + pub->implementation_identifier = "not-an-rmw-implementation-identifier"; + ret = rmw_publisher_get_actual_qos(pub, &actual_qos_profile); + pub->implementation_identifier = implementation_identifier; + EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret); + rmw_reset_error(); } TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos) { + osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret = rmw_publisher_get_actual_qos(pub, &actual_qos_profile); + rmw_ret_t ret; + EXPECT_NO_MEMORY_OPERATIONS( + { + ret = rmw_publisher_get_actual_qos(pub, &actual_qos_profile); + }); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; EXPECT_EQ(rmw_qos_profile_default.history, actual_qos_profile.history); EXPECT_EQ(rmw_qos_profile_default.depth, actual_qos_profile.depth); diff --git a/test_rmw_implementation/test/test_subscription.cpp b/test_rmw_implementation/test/test_subscription.cpp index 11963643..c03bf2e0 100644 --- a/test_rmw_implementation/test/test_subscription.cpp +++ b/test_rmw_implementation/test/test_subscription.cpp @@ -14,6 +14,8 @@ #include +#include "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp" + #include "rcutils/allocator.h" #include "rcutils/strdup.h" @@ -176,6 +178,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), destroy_with_bad_argumen } TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), get_actual_qos_from_system_defaults) { + osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_subscription_options_t options = rmw_get_default_subscription_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -184,7 +187,11 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), get_actual_qos_from_syst rmw_create_subscription(node, ts, topic_name, &rmw_qos_profile_system_default, &options); ASSERT_NE(nullptr, sub) << rmw_get_error_string().str; rmw_qos_profile_t qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret = rmw_subscription_get_actual_qos(sub, &qos_profile); + rmw_ret_t ret; + EXPECT_NO_MEMORY_OPERATIONS( + { + ret = rmw_subscription_get_actual_qos(sub, &qos_profile); + }); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; // Check that a valid QoS policy has been put in place for each system default one. EXPECT_NE(rmw_qos_profile_system_default.history, qos_profile.history); @@ -248,8 +255,13 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos_with_b } TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos) { + osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret = rmw_subscription_get_actual_qos(sub, &actual_qos_profile); + rmw_ret_t ret; + EXPECT_NO_MEMORY_OPERATIONS( + { + ret = rmw_subscription_get_actual_qos(sub, &actual_qos_profile); + }); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; EXPECT_EQ(rmw_qos_profile_default.history, actual_qos_profile.history); EXPECT_EQ(rmw_qos_profile_default.depth, actual_qos_profile.depth); From 3b32d7100106f4a1f48737e249ca21e9950c0ca5 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Mon, 24 Aug 2020 11:56:25 -0300 Subject: [PATCH 2/2] Drop no allocation requirement from QoS query API tests. Signed-off-by: Michel Hidalgo --- test_rmw_implementation/CMakeLists.txt | 4 ++-- test_rmw_implementation/test/test_publisher.cpp | 16 ++-------------- .../test/test_subscription.cpp | 16 ++-------------- 3 files changed, 6 insertions(+), 30 deletions(-) diff --git a/test_rmw_implementation/CMakeLists.txt b/test_rmw_implementation/CMakeLists.txt index f2c6ba36..e08a439a 100644 --- a/test_rmw_implementation/CMakeLists.txt +++ b/test_rmw_implementation/CMakeLists.txt @@ -65,7 +65,7 @@ if(BUILD_TESTING) target_compile_definitions(test_publisher${target_suffix} PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") ament_target_dependencies(test_publisher${target_suffix} - osrf_testing_tools_cpp rcutils rmw rmw_implementation test_msgs + rcutils rmw rmw_implementation test_msgs ) ament_add_gtest(test_subscription${target_suffix} @@ -75,7 +75,7 @@ if(BUILD_TESTING) target_compile_definitions(test_subscription${target_suffix} PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") ament_target_dependencies(test_subscription${target_suffix} - osrf_testing_tools_cpp rcutils rmw rmw_implementation test_msgs + rcutils rmw rmw_implementation test_msgs ) ament_add_gtest(test_serialize_deserialize${target_suffix} diff --git a/test_rmw_implementation/test/test_publisher.cpp b/test_rmw_implementation/test/test_publisher.cpp index 6d2f3081..45706c91 100644 --- a/test_rmw_implementation/test/test_publisher.cpp +++ b/test_rmw_implementation/test/test_publisher.cpp @@ -14,8 +14,6 @@ #include -#include "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp" - #include "rcutils/allocator.h" #include "rcutils/strdup.h" @@ -179,7 +177,6 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_bad_arguments) } TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), get_actual_qos_from_system_defaults) { - osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_publisher_options_t options = rmw_get_default_publisher_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -188,11 +185,7 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), get_actual_qos_from_system_ rmw_create_publisher(node, ts, topic_name, &rmw_qos_profile_system_default, &options); ASSERT_NE(nullptr, pub) << rmw_get_error_string().str; rmw_qos_profile_t qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret; - EXPECT_NO_MEMORY_OPERATIONS( - { - ret = rmw_publisher_get_actual_qos(pub, &qos_profile); - }); + rmw_ret_t ret = rmw_publisher_get_actual_qos(pub, &qos_profile); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; // Check that a valid QoS policy has been put in place for each system default one. EXPECT_NE(rmw_qos_profile_system_default.history, qos_profile.history); @@ -256,13 +249,8 @@ TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos_with_bad_ } TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), get_actual_qos) { - osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret; - EXPECT_NO_MEMORY_OPERATIONS( - { - ret = rmw_publisher_get_actual_qos(pub, &actual_qos_profile); - }); + rmw_ret_t ret = rmw_publisher_get_actual_qos(pub, &actual_qos_profile); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; EXPECT_EQ(rmw_qos_profile_default.history, actual_qos_profile.history); EXPECT_EQ(rmw_qos_profile_default.depth, actual_qos_profile.depth); diff --git a/test_rmw_implementation/test/test_subscription.cpp b/test_rmw_implementation/test/test_subscription.cpp index c03bf2e0..11963643 100644 --- a/test_rmw_implementation/test/test_subscription.cpp +++ b/test_rmw_implementation/test/test_subscription.cpp @@ -14,8 +14,6 @@ #include -#include "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp" - #include "rcutils/allocator.h" #include "rcutils/strdup.h" @@ -178,7 +176,6 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), destroy_with_bad_argumen } TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), get_actual_qos_from_system_defaults) { - osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_subscription_options_t options = rmw_get_default_subscription_options(); constexpr char topic_name[] = "/test"; const rosidl_message_type_support_t * ts = @@ -187,11 +184,7 @@ TEST_F(CLASSNAME(TestSubscription, RMW_IMPLEMENTATION), get_actual_qos_from_syst rmw_create_subscription(node, ts, topic_name, &rmw_qos_profile_system_default, &options); ASSERT_NE(nullptr, sub) << rmw_get_error_string().str; rmw_qos_profile_t qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret; - EXPECT_NO_MEMORY_OPERATIONS( - { - ret = rmw_subscription_get_actual_qos(sub, &qos_profile); - }); + rmw_ret_t ret = rmw_subscription_get_actual_qos(sub, &qos_profile); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; // Check that a valid QoS policy has been put in place for each system default one. EXPECT_NE(rmw_qos_profile_system_default.history, qos_profile.history); @@ -255,13 +248,8 @@ TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos_with_b } TEST_F(CLASSNAME(TestSubscriptionUse, RMW_IMPLEMENTATION), get_actual_qos) { - osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest sqg; rmw_qos_profile_t actual_qos_profile = rmw_qos_profile_unknown; - rmw_ret_t ret; - EXPECT_NO_MEMORY_OPERATIONS( - { - ret = rmw_subscription_get_actual_qos(sub, &actual_qos_profile); - }); + rmw_ret_t ret = rmw_subscription_get_actual_qos(sub, &actual_qos_profile); EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str; EXPECT_EQ(rmw_qos_profile_default.history, actual_qos_profile.history); EXPECT_EQ(rmw_qos_profile_default.depth, actual_qos_profile.depth);