From e9f82da4bce2a3294e99d37f317116334bd62ca1 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 11 Jun 2020 19:26:09 -0300 Subject: [PATCH 01/14] Add bad argument tests for subscription.c Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 137 +++++++++++++++++++++++++++++ 1 file changed, 137 insertions(+) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 910775a1c..6d4953808 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -528,3 +528,140 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) ASSERT_EQ(NULL, rcl_subscription_get_options(nullptr)); } + +/* Using bad arguments subscription methods + */ +TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_bad_argument) { + rcl_ret_t ret = RCL_RET_OK; + 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(); + + size_t pub_count = 0; + test_msgs__msg__BasicTypes msg; + test_msgs__msg__BasicTypes__init(&msg); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + test_msgs__msg__BasicTypes__fini(&msg); + }); + rmw_message_info_t message_info = rmw_get_zero_initialized_message_info(); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + size_t seq_size = 3u; + rmw_message_sequence_t messages; + rmw_message_sequence_init(&messages, seq_size, &allocator); + rmw_message_info_sequence_t message_infos_short; + rmw_message_info_sequence_init(&message_infos_short, seq_size - 1u, &allocator); + rmw_message_info_sequence_t message_infos; + rmw_message_info_sequence_init(&message_infos, seq_size, &allocator); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rmw_message_info_sequence_fini(&message_infos); + rmw_message_info_sequence_fini(&message_infos_short); + rmw_message_sequence_fini(&messages); + }); + + 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_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_take(nullptr, &msg, &message_info, nullptr)); + rcl_reset_error(); + 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_serialized_message(nullptr, &serialized_msg, nullptr, nullptr)); + rcl_reset_error(); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, rcl_subscription_get_publisher_count(&subscription, &pub_count)); + rcl_reset_error(); + EXPECT_EQ(NULL, rcl_subscription_get_actual_qos(&subscription)); + rcl_reset_error(); + EXPECT_FALSE(rcl_subscription_can_loan_messages(&subscription)); + rcl_reset_error(); + EXPECT_EQ(NULL, rcl_subscription_get_rmw_handle(&subscription)); + rcl_reset_error(); + EXPECT_EQ(NULL, rcl_subscription_get_topic_name(&subscription)); + rcl_reset_error(); + EXPECT_EQ(NULL, rcl_subscription_get_options(&subscription)); + rcl_reset_error(); + EXPECT_EQ(RCL_RET_SUBSCRIPTION_INVALID, rcl_take(&subscription, &msg, &message_info, nullptr)); + rcl_reset_error(); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_reset_error(); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, + rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + rcl_reset_error(); + + 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(); + + 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; + 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; + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + 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_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(); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_TAKE_FAILED, + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_reset_error(); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take(&subscription, &msg, &message_info, nullptr)); + rcl_reset_error(); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_TAKE_FAILED, + rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + 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; +} From 8b00583fbc803718a81b969d6cc1f364af40e851 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 12 Jun 2020 13:03:41 -0300 Subject: [PATCH 02/14] Add missing rcl_reset_error() Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 6d4953808..e9ff087a0 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -628,9 +628,11 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription 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(); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); From 621d3a3cd99aa0db6a04a509b5dbaf216d900308 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 12 Jun 2020 13:12:20 -0300 Subject: [PATCH 03/14] Add test failing cyclone Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index e9ff087a0..3ae62b318 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -659,10 +659,16 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); + ASSERT_TRUE(rcl_subscription_is_valid(&subscription)); + 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_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; From 525d4605c09a7e797e59f187d697d055216ca141 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 12 Jun 2020 17:18:03 -0300 Subject: [PATCH 04/14] Disable test not working for rmw_cyclone_cpp Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 3ae62b318..650897718 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -638,7 +638,6 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_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_INVALID_ARGUMENT, rcl_take_sequence(&subscription, seq_size + 1, &messages, &message_infos, nullptr)); @@ -647,10 +646,15 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription 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 + /* EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); rcl_reset_error(); + */ + EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take(&subscription, &msg, &message_info, nullptr)); rcl_reset_error(); @@ -663,12 +667,10 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription 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_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; From 86b4547ebf835f4e4a4d1204ca9837503004cde9 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 12 Jun 2020 19:08:35 -0300 Subject: [PATCH 05/14] Add simple bad alloc test Signed-off-by: Jorge Perez --- rcl/test/rcl/test_expand_topic_name.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/rcl/test/rcl/test_expand_topic_name.cpp b/rcl/test/rcl/test_expand_topic_name.cpp index 3f51b8c2d..fedd54041 100644 --- a/rcl/test/rcl/test_expand_topic_name.cpp +++ b/rcl/test/rcl/test_expand_topic_name.cpp @@ -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); } From 31d66847580b34c9e40b932bc6b54fb93d302e1d Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 12 Jun 2020 19:49:26 -0300 Subject: [PATCH 06/14] Add tests enclave_name Signed-off-by: Jorge Perez --- rcl/test/rcl/test_validate_enclave_name.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/rcl/test/rcl/test_validate_enclave_name.cpp b/rcl/test/rcl/test_validate_enclave_name.cpp index 689d216ab..b382b1b55 100644 --- a/rcl/test/rcl/test_validate_enclave_name.cpp +++ b/rcl/test/rcl/test_validate_enclave_name.cpp @@ -42,6 +42,7 @@ TEST(TestValidateEnclaveName, test_validate) { RCL_RET_OK, rcl_validate_enclave_name("/foo", &validation_result, &invalid_index)); EXPECT_EQ(RCL_ENCLAVE_NAME_VALID, validation_result); + EXPECT_EQ(NULL, rcl_enclave_name_validation_result_string(validation_result)); EXPECT_EQ( RCL_RET_OK, @@ -56,15 +57,20 @@ TEST(TestValidateEnclaveName, test_validation_string) { int expected_validation_result; size_t expected_invalid_index; }; + std::string longString = "/looooooooooooooooooooooooooooooooooooooooooooooooo" + "oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo" + "oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo" + "oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo" + "ooooooooooooooooooooooooooooongString"; std::vector enclave_cases_that_should_fail = { - // TODO(blast_545): Look for naming conventions doc for enclave_names {"", RCL_ENCLAVE_NAME_INVALID_IS_EMPTY_STRING, 0}, {"~/foo", RCL_ENCLAVE_NAME_INVALID_NOT_ABSOLUTE, 0}, {"/foo/", RCL_ENCLAVE_NAME_INVALID_ENDS_WITH_FORWARD_SLASH, 4}, {"/foo/$", RCL_ENCLAVE_NAME_INVALID_CONTAINS_UNALLOWED_CHARACTERS, 5}, {"/bar#", RCL_ENCLAVE_NAME_INVALID_CONTAINS_UNALLOWED_CHARACTERS, 4}, {"/foo//bar", RCL_ENCLAVE_NAME_INVALID_CONTAINS_REPEATED_FORWARD_SLASH, 5}, - {"/1bar", RCL_ENCLAVE_NAME_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER, 1} + {"/1bar", RCL_ENCLAVE_NAME_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER, 1}, + {longString, RCL_ENCLAVE_NAME_INVALID_TOO_LONG, RCL_ENCLAVE_NAME_MAX_LENGTH - 1} }; for (const auto & case_tuple : enclave_cases_that_should_fail) { std::string enclave = case_tuple.enclave; From 2e0f073e79dac3d68a0789cf6bfe26f6d0e9b223 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Tue, 16 Jun 2020 10:45:24 -0300 Subject: [PATCH 07/14] Revert "Add tests enclave_name" Being tested in another branch This reverts commit 31d66847580b34c9e40b932bc6b54fb93d302e1d. Signed-off-by: Jorge Perez --- rcl/test/rcl/test_validate_enclave_name.cpp | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/rcl/test/rcl/test_validate_enclave_name.cpp b/rcl/test/rcl/test_validate_enclave_name.cpp index b382b1b55..689d216ab 100644 --- a/rcl/test/rcl/test_validate_enclave_name.cpp +++ b/rcl/test/rcl/test_validate_enclave_name.cpp @@ -42,7 +42,6 @@ TEST(TestValidateEnclaveName, test_validate) { RCL_RET_OK, rcl_validate_enclave_name("/foo", &validation_result, &invalid_index)); EXPECT_EQ(RCL_ENCLAVE_NAME_VALID, validation_result); - EXPECT_EQ(NULL, rcl_enclave_name_validation_result_string(validation_result)); EXPECT_EQ( RCL_RET_OK, @@ -57,20 +56,15 @@ TEST(TestValidateEnclaveName, test_validation_string) { int expected_validation_result; size_t expected_invalid_index; }; - std::string longString = "/looooooooooooooooooooooooooooooooooooooooooooooooo" - "oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo" - "oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo" - "oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo" - "ooooooooooooooooooooooooooooongString"; std::vector enclave_cases_that_should_fail = { + // TODO(blast_545): Look for naming conventions doc for enclave_names {"", RCL_ENCLAVE_NAME_INVALID_IS_EMPTY_STRING, 0}, {"~/foo", RCL_ENCLAVE_NAME_INVALID_NOT_ABSOLUTE, 0}, {"/foo/", RCL_ENCLAVE_NAME_INVALID_ENDS_WITH_FORWARD_SLASH, 4}, {"/foo/$", RCL_ENCLAVE_NAME_INVALID_CONTAINS_UNALLOWED_CHARACTERS, 5}, {"/bar#", RCL_ENCLAVE_NAME_INVALID_CONTAINS_UNALLOWED_CHARACTERS, 4}, {"/foo//bar", RCL_ENCLAVE_NAME_INVALID_CONTAINS_REPEATED_FORWARD_SLASH, 5}, - {"/1bar", RCL_ENCLAVE_NAME_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER, 1}, - {longString, RCL_ENCLAVE_NAME_INVALID_TOO_LONG, RCL_ENCLAVE_NAME_MAX_LENGTH - 1} + {"/1bar", RCL_ENCLAVE_NAME_INVALID_NAME_TOKEN_STARTS_WITH_NUMBER, 1} }; for (const auto & case_tuple : enclave_cases_that_should_fail) { std::string enclave = case_tuple.enclave; From e145923ac96cd30efa3ce6d42e76e57862cfbd6e Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 17 Jun 2020 10:16:13 -0300 Subject: [PATCH 08/14] Move init/fini tests Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 77 ++++++++++++++++++------------ 1 file changed, 47 insertions(+), 30 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 650897718..77315cb33 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -109,6 +109,52 @@ 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(); + + 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) { @@ -538,7 +584,6 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription 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(); size_t pub_count = 0; test_msgs__msg__BasicTypes msg; @@ -616,28 +661,9 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); - 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(); - - 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(); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - 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_INVALID_ARGUMENT, rcl_take_sequence(&subscription, seq_size + 1, &messages, &message_infos, nullptr)); @@ -663,15 +689,6 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); - ASSERT_TRUE(rcl_subscription_is_valid(&subscription)); - 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_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; } From 375dbf22bb346dde5dcc9b75607d250ff2caacef Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 17 Jun 2020 11:51:57 -0300 Subject: [PATCH 09/14] Add auxiliar testing class Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 65 +++++++++++++++++++----------- 1 file changed, 42 insertions(+), 23 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 77315cb33..afa5d3644 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -78,6 +78,36 @@ class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing } }; +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 = RCL_RET_OK; + + void SetUp() override + { + CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION) ::SetUp(); + 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( @@ -577,14 +607,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) /* Using bad arguments subscription methods */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_bad_argument) { - rcl_ret_t ret = RCL_RET_OK; - 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(); - +TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_argument) { size_t pub_count = 0; test_msgs__msg__BasicTypes msg; test_msgs__msg__BasicTypes__init(&msg); @@ -638,32 +661,31 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_take_serialized_message(nullptr, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); EXPECT_EQ( - RCL_RET_SUBSCRIPTION_INVALID, rcl_subscription_get_publisher_count(&subscription, &pub_count)); + 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)); + EXPECT_EQ(NULL, rcl_subscription_get_actual_qos(&subscription_zero_init)); rcl_reset_error(); - EXPECT_FALSE(rcl_subscription_can_loan_messages(&subscription)); + EXPECT_FALSE(rcl_subscription_can_loan_messages(&subscription_zero_init)); rcl_reset_error(); - EXPECT_EQ(NULL, rcl_subscription_get_rmw_handle(&subscription)); + EXPECT_EQ(NULL, rcl_subscription_get_rmw_handle(&subscription_zero_init)); rcl_reset_error(); - EXPECT_EQ(NULL, rcl_subscription_get_topic_name(&subscription)); + EXPECT_EQ(NULL, rcl_subscription_get_topic_name(&subscription_zero_init)); rcl_reset_error(); - EXPECT_EQ(NULL, rcl_subscription_get_options(&subscription)); + EXPECT_EQ(NULL, rcl_subscription_get_options(&subscription_zero_init)); rcl_reset_error(); - EXPECT_EQ(RCL_RET_SUBSCRIPTION_INVALID, rcl_take(&subscription, &msg, &message_info, nullptr)); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, rcl_take(&subscription_zero_init, &msg, &message_info, nullptr)); rcl_reset_error(); EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_take_sequence(&subscription_zero_init, seq_size, &messages, &message_infos, nullptr)); rcl_reset_error(); EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + rcl_take_serialized_message(&subscription_zero_init, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); - ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, rcl_take_sequence(&subscription, seq_size + 1, &messages, &message_infos, nullptr)); @@ -688,7 +710,4 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); - - ret = rcl_subscription_fini(&subscription, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } From 0446918cd8e01bc163c92568025bfefd991b2698 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 17 Jun 2020 13:22:38 -0300 Subject: [PATCH 10/14] Reformat into smaller tests Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 135 +++++++++++++++++------------ 1 file changed, 79 insertions(+), 56 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index afa5d3644..662bb7b12 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -88,11 +88,13 @@ class CLASSNAME (TestSubscriptionFixtureInit, RMW_IMPLEMENTATION) rcl_subscription_options_t subscription_options; rcl_subscription_t subscription; rcl_subscription_t subscription_zero_init; - rcl_ret_t ret = RCL_RET_OK; + 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(); @@ -605,85 +607,79 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) ASSERT_EQ(NULL, rcl_subscription_get_options(nullptr)); } -/* Using bad arguments subscription methods - */ -TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_argument) { - size_t pub_count = 0; +/* 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(); test_msgs__msg__BasicTypes__init(&msg); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( { test_msgs__msg__BasicTypes__fini(&msg); }); - rmw_message_info_t message_info = rmw_get_zero_initialized_message_info(); - rcutils_allocator_t allocator = rcutils_get_default_allocator(); - size_t seq_size = 3u; - rmw_message_sequence_t messages; - rmw_message_sequence_init(&messages, seq_size, &allocator); - rmw_message_info_sequence_t message_infos_short; - rmw_message_info_sequence_init(&message_infos_short, seq_size - 1u, &allocator); - rmw_message_info_sequence_t message_infos; - rmw_message_info_sequence_init(&message_infos, seq_size, &allocator); - OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( - { - rmw_message_info_sequence_fini(&message_infos); - rmw_message_info_sequence_fini(&message_infos_short); - rmw_message_sequence_fini(&messages); - }); + 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_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_take(nullptr, &msg, &message_info, nullptr)); - rcl_reset_error(); - 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_serialized_message(nullptr, &serialized_msg, nullptr, 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_take_serialized_message(&subscription_zero_init, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); + EXPECT_EQ( - RCL_RET_SUBSCRIPTION_INVALID, rcl_take(&subscription_zero_init, &msg, &message_info, nullptr)); + 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; + rmw_message_sequence_init(&messages, seq_size, &allocator); + rmw_message_info_sequence_t message_infos_short; + rmw_message_info_sequence_init(&message_infos_short, seq_size - 1u, &allocator); + rmw_message_info_sequence_t message_infos; + rmw_message_info_sequence_init(&message_infos, seq_size, &allocator); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rmw_message_info_sequence_fini(&message_infos); + rmw_message_info_sequence_fini(&message_infos_short); + rmw_message_sequence_fini(&messages); + }); + EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_sequence(&subscription_zero_init, seq_size, &messages, &message_infos, nullptr)); + rcl_take_sequence(nullptr, seq_size, &messages, &message_infos, nullptr)); rcl_reset_error(); EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_serialized_message(&subscription_zero_init, &serialized_msg, nullptr, nullptr)); + rcl_take_sequence(&subscription_zero_init, seq_size, &messages, &message_infos, nullptr)); rcl_reset_error(); EXPECT_EQ( @@ -702,12 +698,39 @@ TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscrip 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_TAKE_FAILED, rcl_take(&subscription, &msg, &message_info, nullptr)); + 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_TAKE_FAILED, - rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + 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(); } From 1a99fb0651985450477240759abc88b20d5368cb Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 17 Jun 2020 13:45:44 -0300 Subject: [PATCH 11/14] Add checks ini/fini rmw messages Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 20 ++++++++++++++------ 1 file changed, 14 insertions(+), 6 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 662bb7b12..c0c79bd96 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -661,16 +661,24 @@ TEST_F( { size_t seq_size = 3u; rmw_message_sequence_t messages; - rmw_message_sequence_init(&messages, seq_size, &allocator); + 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; - rmw_message_info_sequence_init(&message_infos_short, seq_size - 1u, &allocator); + 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; - rmw_message_info_sequence_init(&message_infos, seq_size, &allocator); + ASSERT_EQ( + RMW_RET_OK, rmw_message_info_sequence_init(&message_infos, seq_size, &allocator)); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( { - rmw_message_info_sequence_fini(&message_infos); - rmw_message_info_sequence_fini(&message_infos_short); - rmw_message_sequence_fini(&messages); + EXPECT_EQ(RMW_RET_OK, rmw_message_info_sequence_fini(&message_infos)); }); EXPECT_EQ( From 62e6111225ca1a92b750f599d1b866f87fdfaf4a Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 17 Jun 2020 14:07:27 -0300 Subject: [PATCH 12/14] Add issue report for disabled test Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index c0c79bd96..6e9680acc 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -700,6 +700,7 @@ TEST_F( 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, From fa888460ae68fe030544bf715189ce1a63764833 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 17 Jun 2020 15:31:12 -0300 Subject: [PATCH 13/14] Add assert for msg init Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 6e9680acc..75a30a4ab 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -612,7 +612,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) 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(); - test_msgs__msg__BasicTypes__init(&msg); + ASSERT_TRUE(test_msgs__msg__BasicTypes__init(&msg)); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( { test_msgs__msg__BasicTypes__fini(&msg); From 3eb7cb7d1f3d76e1c98b25fff808e504775ee3b4 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 18 Jun 2020 18:57:41 -0300 Subject: [PATCH 14/14] Add bad_allocator test Signed-off-by: Jorge Perez --- rcl/test/rcl/test_subscription.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 75a30a4ab..2dcbd4490 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -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) @@ -171,6 +173,10 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription 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));