Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Complete publisher/subscription QoS query API test coverage. #120

Merged
merged 2 commits into from
Sep 7, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions test_rmw_implementation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}
Expand All @@ -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}
Expand Down
23 changes: 21 additions & 2 deletions test_rmw_implementation/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include <gtest/gtest.h>

#include "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp"

#include "rcutils/allocator.h"
#include "rcutils/strdup.h"

Expand Down Expand Up @@ -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 =
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand Down
16 changes: 14 additions & 2 deletions test_rmw_implementation/test/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include <gtest/gtest.h>

#include "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp"

#include "rcutils/allocator.h"
#include "rcutils/strdup.h"

Expand Down Expand Up @@ -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 =
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand Down