diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 7a8fdc531..261f8bd82 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -316,6 +316,12 @@ target_link_libraries(test_rmw_impl_id_check_exe ${PROJECT_NAME}) call_for_each_rmw_implementation(test_target) +rcl_add_custom_gtest(test_validate_enclave_name + SRCS rcl/test_validate_enclave_name.cpp + APPEND_LIBRARY_DIRS ${extra_lib_dirs} + LIBRARIES ${PROJECT_NAME} +) + rcl_add_custom_gtest(test_validate_topic_name SRCS rcl/test_validate_topic_name.cpp APPEND_LIBRARY_DIRS ${extra_lib_dirs} diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index f13efb6d6..2b92e7047 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -430,3 +430,161 @@ TEST_F( std::string(seq->data[0].string_value.data, seq->data[0].string_value.size)); } } + +/* Basic nominal test of a subscription with take_serialize msg + */ +TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_serialized) { + rcl_ret_t ret; + rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); + rcutils_allocator_t allocator = rcl_get_default_allocator(); + const rosidl_message_type_support_t * ts = + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); + const char * topic = "/chatterSer"; + rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); + ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + + rcl_serialized_message_t serialized_msg = rmw_get_zero_initialized_serialized_message(); + auto initial_capacity_ser = 0u; + ASSERT_EQ( + RCL_RET_OK, rmw_serialized_message_init( + &serialized_msg, initial_capacity_ser, &allocator)) << rcl_get_error_string().str; + const char * test_string = "testing"; + test_msgs__msg__Strings msg; + test_msgs__msg__Strings__init(&msg); + ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string)); + ASSERT_STREQ(msg.string_value.data, test_string); + ret = rmw_serialize(&msg, ts, &serialized_msg); + ASSERT_EQ(RMW_RET_OK, ret); + + rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); + rcl_subscription_t subscription = 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; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + ret = rcl_subscription_fini(&subscription, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + rcl_reset_error(); + + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + { + ret = rcl_publish_serialized_message(&publisher, &serialized_msg, nullptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } + bool success; + wait_for_subscription_to_be_ready(&subscription, context_ptr, 10, 100, success); + ASSERT_TRUE(success); + { + rcl_serialized_message_t serialized_msg_rcv = rmw_get_zero_initialized_serialized_message(); + initial_capacity_ser = 0u; + ASSERT_EQ( + RCL_RET_OK, rmw_serialized_message_init( + &serialized_msg_rcv, initial_capacity_ser, &allocator)) << rcl_get_error_string().str; + ret = rcl_take_serialized_message(&subscription, &serialized_msg_rcv, nullptr, nullptr); + ASSERT_EQ(RMW_RET_OK, ret); + + test_msgs__msg__Strings msg_rcv; + test_msgs__msg__Strings__init(&msg_rcv); + ret = rmw_deserialize(&serialized_msg_rcv, ts, &msg_rcv); + ASSERT_EQ(RMW_RET_OK, ret); + ASSERT_EQ( + std::string(test_string), std::string(msg_rcv.string_value.data, msg_rcv.string_value.size)); + } +} + +/* Basic test for subscription loan functions + */ +TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_loaned) { + rcl_ret_t ret; + 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); + const char * topic = "rcl_loan"; + rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); + ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + // TODO(wjwwood): add logic to wait for the connection to be established + // probably using the count_subscriptions busy wait mechanism + // until then we will sleep for a short period of time + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + const char * test_string = "testing"; + { + test_msgs__msg__Strings msg; + test_msgs__msg__Strings__init(&msg); + ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string)); + ret = rcl_publish(&publisher, &msg, nullptr); + test_msgs__msg__Strings__fini(&msg); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } + bool success; + wait_for_subscription_to_be_ready(&subscription, context_ptr, 10, 100, success); + ASSERT_TRUE(success); + { + test_msgs__msg__Strings msg; + test_msgs__msg__Strings * msg_loaned; + test_msgs__msg__Strings__init(&msg); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + test_msgs__msg__Strings__fini(&msg); + }); + + // Only if rmw supports the functionality + if (rcl_subscription_can_loan_messages(&subscription)) { + ret = rcl_take_loaned_message( + &subscription, reinterpret_cast(&msg_loaned), nullptr, nullptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ASSERT_EQ( + std::string(test_string), + std::string(*msg_loaned->string_value.data, msg_loaned->string_value.size)); + } else { + ret = rcl_take(&subscription, &msg, nullptr, nullptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ASSERT_EQ( + std::string(test_string), std::string(msg.string_value.data, msg.string_value.size)); + } + } +} + +TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) { + rcl_ret_t ret; + const rosidl_message_type_support_t * ts = + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); + const char * topic = "test_get_options"; + rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + + const rcl_subscription_options_t * get_sub_options = rcl_subscription_get_options(&subscription); + ASSERT_EQ(subscription_options.qos.history, get_sub_options->qos.history); + ASSERT_EQ(subscription_options.qos.depth, get_sub_options->qos.depth); + ASSERT_EQ(subscription_options.qos.durability, get_sub_options->qos.durability); + + ASSERT_EQ(NULL, rcl_subscription_get_options(nullptr)); +} diff --git a/rcl/test/rcl/test_validate_enclave_name.cpp b/rcl/test/rcl/test_validate_enclave_name.cpp new file mode 100644 index 000000000..689d216ab --- /dev/null +++ b/rcl/test/rcl/test_validate_enclave_name.cpp @@ -0,0 +1,85 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include + +#include "rcl/rcl.h" +#include "rcl/validate_enclave_name.h" + +#include "rcl/error_handling.h" + +TEST(TestValidateEnclaveName, test_validate) { + int validation_result; + size_t invalid_index; + + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + rcl_validate_enclave_name(nullptr, &validation_result, &invalid_index)); + + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + rcl_validate_enclave_name_with_size(nullptr, 20, &validation_result, &invalid_index)); + + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + rcl_validate_enclave_name_with_size("/foo", 20, nullptr, &invalid_index)); + + EXPECT_EQ( + RCL_RET_OK, + rcl_validate_enclave_name("/foo", &validation_result, &invalid_index)); + EXPECT_EQ(RCL_ENCLAVE_NAME_VALID, validation_result); + + EXPECT_EQ( + RCL_RET_OK, + rcl_validate_enclave_name("/foo/bar", &validation_result, &invalid_index)); + EXPECT_EQ(RCL_ENCLAVE_NAME_VALID, validation_result); +} + +TEST(TestValidateEnclaveName, test_validation_string) { + struct enclave_case + { + std::string enclave; + int expected_validation_result; + size_t expected_invalid_index; + }; + 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} + }; + for (const auto & case_tuple : enclave_cases_that_should_fail) { + std::string enclave = case_tuple.enclave; + int expected_validation_result = case_tuple.expected_validation_result; + size_t expected_invalid_index = case_tuple.expected_invalid_index; + int validation_result; + size_t invalid_index = 0; + rcl_ret_t ret = rcl_validate_enclave_name(enclave.c_str(), &validation_result, &invalid_index); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + EXPECT_EQ(expected_validation_result, validation_result) << + "'" << enclave << "' should have failed with '" << + expected_validation_result << "' but got '" << validation_result << "'.\n" << + " " << std::string(invalid_index, ' ') << "^"; + EXPECT_EQ(expected_invalid_index, invalid_index) << + "Enclave '" << enclave << "' failed with '" << validation_result << "'."; + EXPECT_NE(nullptr, rcl_enclave_name_validation_result_string(validation_result)) << enclave; + } +}