Improve subscription coverage (#681)
* Add bad argument tests for subscription.c * Add missing rcl_reset_error() * Add test failing cyclone * Disable test not working for rmw_cyclone_cpp * Add simple bad alloc test * Add tests enclave_name * Revert "Add tests enclave_name" * Move init/fini tests * Add auxiliar testing class * Reformat into smaller tests * Add checks ini/fini rmw messages * Add issue report for disabled test * Add assert for msg init * Add bad_allocator test Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
This commit is contained in:
parent
c52a938b9e
commit
91dad10c1e
2 changed files with 233 additions and 0 deletions
|
@ -23,6 +23,8 @@
|
|||
|
||||
#include "rcl/error_handling.h"
|
||||
|
||||
#include "./allocator_testing_utils.h"
|
||||
|
||||
using namespace std::string_literals;
|
||||
|
||||
TEST(test_expand_topic_name, normal) {
|
||||
|
@ -121,6 +123,16 @@ TEST(test_expand_topic_name, invalid_arguments) {
|
|||
rcl_reset_error();
|
||||
}
|
||||
|
||||
// pass failing allocator
|
||||
{
|
||||
rcl_allocator_t bad_allocator = get_failing_allocator();
|
||||
EXPECT_EQ(
|
||||
RCL_RET_BAD_ALLOC,
|
||||
rcl_expand_topic_name("/absolute", node, ns, &subs, bad_allocator, &expanded_topic));
|
||||
EXPECT_STREQ(NULL, expanded_topic);
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
ret = rcutils_string_map_fini(&subs);
|
||||
ASSERT_EQ(RCL_RET_OK, ret);
|
||||
}
|
||||
|
|
|
@ -29,6 +29,8 @@
|
|||
#include "rcl/error_handling.h"
|
||||
#include "wait_for_entity_helpers.hpp"
|
||||
|
||||
#include "./allocator_testing_utils.h"
|
||||
|
||||
#ifdef RMW_IMPLEMENTATION
|
||||
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
|
||||
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
|
||||
|
@ -78,6 +80,38 @@ public:
|
|||
}
|
||||
};
|
||||
|
||||
class CLASSNAME (TestSubscriptionFixtureInit, RMW_IMPLEMENTATION)
|
||||
: public CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION)
|
||||
{
|
||||
public:
|
||||
const rosidl_message_type_support_t * ts =
|
||||
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes);
|
||||
const char * topic = "/chatter";
|
||||
rcl_subscription_options_t subscription_options;
|
||||
rcl_subscription_t subscription;
|
||||
rcl_subscription_t subscription_zero_init;
|
||||
rcl_ret_t ret;
|
||||
rcutils_allocator_t allocator;
|
||||
|
||||
void SetUp() override
|
||||
{
|
||||
CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION) ::SetUp();
|
||||
allocator = rcutils_get_default_allocator();
|
||||
subscription_options = rcl_subscription_get_default_options();
|
||||
subscription = rcl_get_zero_initialized_subscription();
|
||||
subscription_zero_init = rcl_get_zero_initialized_subscription();
|
||||
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
}
|
||||
|
||||
void TearDown() override
|
||||
{
|
||||
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();
|
||||
}
|
||||
};
|
||||
|
||||
/* Test subscription init, fini and is_valid functions
|
||||
*/
|
||||
TEST_F(
|
||||
|
@ -109,6 +143,56 @@ TEST_F(
|
|||
rcl_reset_error();
|
||||
}
|
||||
|
||||
// Bad arguments for init and fini
|
||||
TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_bad_init) {
|
||||
const rosidl_message_type_support_t * ts =
|
||||
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes);
|
||||
const char * topic = "/chatter";
|
||||
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
||||
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
||||
rcl_node_t invalid_node = rcl_get_zero_initialized_node();
|
||||
|
||||
ASSERT_FALSE(rcl_node_is_valid_except_context(&invalid_node));
|
||||
EXPECT_EQ(nullptr, rcl_node_get_rmw_handle(&invalid_node));
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_NODE_INVALID,
|
||||
rcl_subscription_init(&subscription, nullptr, ts, topic, &subscription_options));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(
|
||||
RCL_RET_NODE_INVALID,
|
||||
rcl_subscription_init(&subscription, &invalid_node, ts, topic, &subscription_options));
|
||||
rcl_reset_error();
|
||||
|
||||
rcl_ret_t ret = rcl_subscription_init(
|
||||
&subscription, this->node_ptr, ts, "spaced name", &subscription_options);
|
||||
EXPECT_EQ(RCL_RET_TOPIC_NAME_INVALID, ret) << rcl_get_error_string().str;
|
||||
rcl_reset_error();
|
||||
ret = rcl_subscription_init(
|
||||
&subscription, this->node_ptr, ts, "sub{ros_not_match}", &subscription_options);
|
||||
EXPECT_EQ(RCL_RET_TOPIC_NAME_INVALID, ret) << rcl_get_error_string().str;
|
||||
rcl_reset_error();
|
||||
|
||||
rcl_subscription_options_t bad_subscription_options = rcl_subscription_get_default_options();
|
||||
bad_subscription_options.allocator = get_failing_allocator();
|
||||
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &bad_subscription_options);
|
||||
|
||||
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
ASSERT_TRUE(rcl_subscription_is_valid(&subscription));
|
||||
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
|
||||
EXPECT_EQ(RCL_RET_ALREADY_INIT, ret) << rcl_get_error_string().str;
|
||||
rcl_reset_error();
|
||||
|
||||
EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_subscription_fini(&subscription, nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_subscription_fini(&subscription, &invalid_node));
|
||||
rcl_reset_error();
|
||||
|
||||
ret = rcl_subscription_fini(&subscription, this->node_ptr);
|
||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
}
|
||||
|
||||
/* Basic nominal test of a subscription
|
||||
*/
|
||||
TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal) {
|
||||
|
@ -528,3 +612,140 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options)
|
|||
|
||||
ASSERT_EQ(NULL, rcl_subscription_get_options(nullptr));
|
||||
}
|
||||
|
||||
/* bad take()
|
||||
*/
|
||||
TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), 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));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
test_msgs__msg__BasicTypes__fini(&msg);
|
||||
});
|
||||
EXPECT_EQ(RCL_RET_SUBSCRIPTION_INVALID, rcl_take(nullptr, &msg, &message_info, nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_INVALID, rcl_take(&subscription_zero_init, &msg, &message_info, nullptr));
|
||||
rcl_reset_error();
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take(&subscription, &msg, &message_info, nullptr));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
/* bad take_serialized
|
||||
*/
|
||||
TEST_F(
|
||||
CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION),
|
||||
test_subscription_bad_take_serialized) {
|
||||
rcl_serialized_message_t serialized_msg = rmw_get_zero_initialized_serialized_message();
|
||||
size_t initial_capacity_ser = 0u;
|
||||
ASSERT_EQ(
|
||||
RCL_RET_OK, rmw_serialized_message_init(
|
||||
&serialized_msg, initial_capacity_ser, &allocator)) << rcl_get_error_string().str;
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_INVALID,
|
||||
rcl_take_serialized_message(nullptr, &serialized_msg, nullptr, nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_INVALID,
|
||||
rcl_take_serialized_message(&subscription_zero_init, &serialized_msg, nullptr, nullptr));
|
||||
rcl_reset_error();
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_TAKE_FAILED,
|
||||
rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
/* Bad arguments take_sequence
|
||||
*/
|
||||
TEST_F(
|
||||
CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_take_sequence)
|
||||
{
|
||||
size_t seq_size = 3u;
|
||||
rmw_message_sequence_t messages;
|
||||
ASSERT_EQ(RMW_RET_OK, rmw_message_sequence_init(&messages, seq_size, &allocator));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RMW_RET_OK, rmw_message_sequence_fini(&messages));
|
||||
});
|
||||
rmw_message_info_sequence_t message_infos_short;
|
||||
ASSERT_EQ(
|
||||
RMW_RET_OK, rmw_message_info_sequence_init(&message_infos_short, seq_size - 1u, &allocator));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RMW_RET_OK, rmw_message_info_sequence_fini(&message_infos_short));
|
||||
});
|
||||
rmw_message_info_sequence_t message_infos;
|
||||
ASSERT_EQ(
|
||||
RMW_RET_OK, rmw_message_info_sequence_init(&message_infos, seq_size, &allocator));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RMW_RET_OK, rmw_message_info_sequence_fini(&message_infos));
|
||||
});
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_INVALID,
|
||||
rcl_take_sequence(nullptr, seq_size, &messages, &message_infos, nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_INVALID,
|
||||
rcl_take_sequence(&subscription_zero_init, seq_size, &messages, &message_infos, nullptr));
|
||||
rcl_reset_error();
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_INVALID_ARGUMENT,
|
||||
rcl_take_sequence(&subscription, seq_size + 1, &messages, &message_infos, nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(
|
||||
RCL_RET_INVALID_ARGUMENT,
|
||||
rcl_take_sequence(&subscription, seq_size, &messages, &message_infos_short, nullptr));
|
||||
rcl_reset_error();
|
||||
|
||||
// This test fails for rmw_cyclonedds_cpp function rmw_take_sequence
|
||||
// Tracked here: https://github.com/ros2/rmw_cyclonedds/issues/193
|
||||
/*
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_TAKE_FAILED,
|
||||
rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr));
|
||||
rcl_reset_error();
|
||||
*/
|
||||
}
|
||||
|
||||
/* Using bad arguments subscription methods
|
||||
*/
|
||||
TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_argument) {
|
||||
size_t pub_count = 0;
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_INVALID, rcl_subscription_get_publisher_count(nullptr, &pub_count));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_actual_qos(nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_FALSE(rcl_subscription_can_loan_messages(nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_rmw_handle(nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_topic_name(nullptr));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_options(nullptr));
|
||||
rcl_reset_error();
|
||||
|
||||
EXPECT_EQ(
|
||||
RCL_RET_SUBSCRIPTION_INVALID,
|
||||
rcl_subscription_get_publisher_count(&subscription_zero_init, &pub_count));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_actual_qos(&subscription_zero_init));
|
||||
rcl_reset_error();
|
||||
EXPECT_FALSE(rcl_subscription_can_loan_messages(&subscription_zero_init));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_rmw_handle(&subscription_zero_init));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_topic_name(&subscription_zero_init));
|
||||
rcl_reset_error();
|
||||
EXPECT_EQ(NULL, rcl_subscription_get_options(&subscription_zero_init));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue