diff --git a/rclcpp/test/CMakeLists.txt b/rclcpp/test/CMakeLists.txt index d500f3e58a..569f1e2be8 100644 --- a/rclcpp/test/CMakeLists.txt +++ b/rclcpp/test/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(ament_cmake_gtest REQUIRED) find_package(rmw_implementation_cmake REQUIRED) find_package(rosidl_default_generators REQUIRED) +find_package(osrf_testing_tools_cpp REQUIRED) find_package(test_msgs REQUIRED) include(cmake/rclcpp_add_build_failure_test.cmake) @@ -17,6 +18,25 @@ rosidl_generate_interfaces(${PROJECT_NAME}_test_msgs SKIP_INSTALL ) +ament_add_gtest(test_allocator_memory_strategy rclcpp/strategies/test_allocator_memory_strategy.cpp) +if(TARGET test_allocator_memory_strategy) + ament_target_dependencies(test_allocator_memory_strategy + "osrf_testing_tools_cpp" + "rcl" + "test_msgs" + ) + target_link_libraries(test_allocator_memory_strategy ${PROJECT_NAME}) +endif() + +ament_add_gtest(test_message_pool_memory_strategy rclcpp/strategies/test_message_pool_memory_strategy.cpp) +if(TARGET test_message_pool_memory_strategy) + ament_target_dependencies(test_message_pool_memory_strategy + "rcl" + "test_msgs" + ) + target_link_libraries(test_message_pool_memory_strategy ${PROJECT_NAME}) +endif() + ament_add_gtest(test_client rclcpp/test_client.cpp) if(TARGET test_client) ament_target_dependencies(test_client @@ -97,6 +117,18 @@ ament_target_dependencies(test_loaned_message ) target_link_libraries(test_loaned_message ${PROJECT_NAME}) +ament_add_gtest(test_memory_strategy rclcpp/test_memory_strategy.cpp) +ament_target_dependencies(test_memory_strategy + "test_msgs" +) +target_link_libraries(test_memory_strategy ${PROJECT_NAME}) + +ament_add_gtest(test_message_memory_strategy rclcpp/test_message_memory_strategy.cpp) +ament_target_dependencies(test_message_memory_strategy + "test_msgs" +) +target_link_libraries(test_message_memory_strategy ${PROJECT_NAME}) + ament_add_gtest(test_node rclcpp/test_node.cpp TIMEOUT 240) if(TARGET test_node) ament_target_dependencies(test_node diff --git a/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp b/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp new file mode 100644 index 0000000000..a58ad94c2c --- /dev/null +++ b/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp @@ -0,0 +1,732 @@ +// 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 +#include + +#include "gtest/gtest.h" + +#include "osrf_testing_tools_cpp/scope_exit.hpp" +#include "rclcpp/strategies/allocator_memory_strategy.hpp" +#include "test_msgs/msg/empty.hpp" +#include "test_msgs/srv/empty.hpp" + +using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy; +using WeakNodeList = std::list; + +static bool test_waitable_result = false; + +/** + * Mock Waitable class, with a globally setable boolean result. + */ +class TestWaitable : public rclcpp::Waitable +{ +public: + bool add_to_wait_set(rcl_wait_set_t *) override + { + return test_waitable_result; + } + + bool is_ready(rcl_wait_set_t *) override + { + return test_waitable_result; + } + + void execute() override {} +}; + +struct RclWaitSetSizes +{ + size_t size_of_subscriptions = 0; + size_t size_of_guard_conditions = 0; + size_t size_of_timers = 0; + size_t size_of_clients = 0; + size_t size_of_services = 0; + size_t size_of_events = 0; + size_t size_of_waitables = 0; +}; + +// For a standard rclcpp node, this should be more than enough capacity for each type. +RclWaitSetSizes SufficientWaitSetCapacities() +{ + return {100, 100, 100, 100, 100, 100, 100}; +} + +class TestAllocatorMemoryStrategy : public ::testing::Test +{ +public: + TestAllocatorMemoryStrategy() + : allocator_memory_strategy_(nullptr), + num_ready_subscriptions_of_basic_node_(0), + num_ready_services_of_basic_node_(0), + num_ready_events_of_basic_node_(0), + num_ready_clients_of_basic_node_(0), + num_guard_conditions_of_basic_node_(0), + num_ready_timers_of_basic_node_(0), + num_waitables_of_basic_node_(0) {} + + void SetUp() override + { + rclcpp::init(0, nullptr); + allocator_memory_strategy_ = std::make_shared>(); + + auto basic_node = std::make_shared("basic_node", "ns"); + auto dummy_memory_strategy = std::make_shared>(); + WeakNodeList nodes; + nodes.push_back(basic_node->get_node_base_interface()); + dummy_memory_strategy->collect_entities(nodes); + + num_ready_subscriptions_of_basic_node_ = + dummy_memory_strategy->number_of_ready_subscriptions(); + num_ready_services_of_basic_node_ = dummy_memory_strategy->number_of_ready_services(); + num_ready_events_of_basic_node_ = dummy_memory_strategy->number_of_ready_events(); + num_ready_clients_of_basic_node_ = dummy_memory_strategy->number_of_ready_clients(); + num_guard_conditions_of_basic_node_ = dummy_memory_strategy->number_of_guard_conditions(); + num_ready_timers_of_basic_node_ = dummy_memory_strategy->number_of_ready_timers(); + num_waitables_of_basic_node_ = dummy_memory_strategy->number_of_waitables(); + } + + void TearDown() override + { + rclcpp::shutdown(); + } + +protected: + std::shared_ptr> allocator_memory_strategy() + { + return allocator_memory_strategy_; + } + + // + // Convience methods, but it adds entities to vectors so the weak pointers kept by the node + // interfaces remain alive and valid + // + + std::shared_ptr create_node_with_subscription( + const std::string & name, bool with_exclusive_callback_group = false) + { + auto subscription_callback = [](const test_msgs::msg::Empty::SharedPtr) {}; + const rclcpp::QoS qos(10); + auto node_with_subscription = std::make_shared(name, "ns"); + + rclcpp::SubscriptionOptions subscription_options; + + if (with_exclusive_callback_group) { + auto callback_group = + node_with_subscription->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive); + + subscription_options.callback_group = callback_group; + callback_groups_.push_back(callback_group); + } + + auto subscription = node_with_subscription->create_subscription< + test_msgs::msg::Empty, decltype(subscription_callback)>( + "topic", qos, std::move(subscription_callback), subscription_options); + subscriptions_.push_back(subscription); + + return node_with_subscription; + } + + std::shared_ptr create_node_with_service( + const std::string & name, bool with_exclusive_callback_group = false) + { + auto service_callback = + [](const test_msgs::srv::Empty::Request::SharedPtr, + test_msgs::srv::Empty::Response::SharedPtr) {}; + auto node_with_service = std::make_shared(name, "ns"); + + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr; + + if (with_exclusive_callback_group) { + callback_group = + node_with_service->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive); + + callback_groups_.push_back(callback_group); + } + + services_.push_back( + node_with_service->create_service( + "service", std::move(service_callback), rmw_qos_profile_services_default, callback_group)); + return node_with_service; + } + + std::shared_ptr create_node_with_client( + const std::string & name, bool with_exclusive_callback_group = false) + { + auto node_with_client = std::make_shared(name, "ns"); + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr; + if (with_exclusive_callback_group) { + callback_group = + node_with_client->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive); + + callback_groups_.push_back(callback_group); + } + + clients_.push_back( + node_with_client->create_client( + "service", rmw_qos_profile_services_default, callback_group)); + return node_with_client; + } + + std::shared_ptr create_node_with_timer( + const std::string & name, bool with_exclusive_callback_group = false) + { + auto timer_callback = []() {}; + auto node_with_timer = std::make_shared(name, "ns"); + + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr; + if (with_exclusive_callback_group) { + callback_group = + node_with_timer->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive); + callback_groups_.push_back(callback_group); + } + + timers_.push_back( + node_with_timer->create_wall_timer( + std::chrono::milliseconds(1), timer_callback, callback_group)); + return node_with_timer; + } + + std::shared_ptr create_node_with_waitable( + const std::string & name, bool with_exclusive_callback_group = false) + { + auto node = std::make_shared(name, "ns"); + rclcpp::Waitable::SharedPtr waitable = std::make_shared(); + + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr; + + if (with_exclusive_callback_group) { + callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + + callback_groups_.push_back(callback_group); + } + + waitables_.push_back(waitable); + node->get_node_waitables_interface()->add_waitable(waitable, callback_group); + return node; + } + + size_t number_of_ready_subscriptions_in_addition_to_basic_node() const + { + return + allocator_memory_strategy_->number_of_ready_subscriptions() - + num_ready_subscriptions_of_basic_node_; + } + + size_t number_of_ready_services_in_addition_to_basic_node() const + { + return + allocator_memory_strategy_->number_of_ready_services() - + num_ready_services_of_basic_node_; + } + + size_t number_of_ready_events_in_addition_to_basic_node() const + { + return + allocator_memory_strategy_->number_of_ready_events() - + num_ready_events_of_basic_node_; + } + + size_t number_of_ready_clients_in_addition_to_basic_node() const + { + return + allocator_memory_strategy_->number_of_ready_clients() - + num_ready_clients_of_basic_node_; + } + + size_t number_of_guard_conditions_in_addition_to_basic_node() const + { + return + allocator_memory_strategy_->number_of_guard_conditions() - + num_guard_conditions_of_basic_node_; + } + + size_t number_of_ready_timers_in_addition_to_basic_node() const + { + return + allocator_memory_strategy_->number_of_ready_timers() - + num_ready_timers_of_basic_node_; + } + + size_t number_of_waitables_in_addition_to_basic_node() const + { + return + allocator_memory_strategy_->number_of_waitables() - + num_waitables_of_basic_node_; + } + + ::testing::AssertionResult TestNumberOfEntitiesAfterCollection( + std::shared_ptr node, + const RclWaitSetSizes & expected) + { + WeakNodeList nodes; + nodes.push_back(node->get_node_base_interface()); + + allocator_memory_strategy()->collect_entities(nodes); + EXPECT_EQ( + expected.size_of_subscriptions, number_of_ready_subscriptions_in_addition_to_basic_node()); + EXPECT_EQ( + expected.size_of_guard_conditions, number_of_guard_conditions_in_addition_to_basic_node()); + EXPECT_EQ(expected.size_of_timers, number_of_ready_timers_in_addition_to_basic_node()); + EXPECT_EQ(expected.size_of_clients, number_of_ready_clients_in_addition_to_basic_node()); + EXPECT_EQ(expected.size_of_services, number_of_ready_services_in_addition_to_basic_node()); + EXPECT_EQ(expected.size_of_events, number_of_ready_events_in_addition_to_basic_node()); + EXPECT_EQ(expected.size_of_waitables, number_of_waitables_in_addition_to_basic_node()); + if (::testing::Test::HasFailure()) { + return ::testing::AssertionFailure() << + "Expected number of entities did not match actual counts"; + } + return ::testing::AssertionSuccess(); + } + + ::testing::AssertionResult TestAddHandlesToWaitSet( + std::shared_ptr node, + const RclWaitSetSizes & insufficient_capacities) + { + WeakNodeList nodes; + nodes.push_back(node->get_node_base_interface()); + allocator_memory_strategy()->collect_entities(nodes); + + auto context = node->get_node_base_interface()->get_context(); + rcl_context_t * rcl_context = context->get_rcl_context().get(); + rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); + rcl_allocator_t allocator = rcl_get_default_allocator(); + RclWaitSetSizes sufficient_capacities = SufficientWaitSetCapacities(); + + rcl_ret_t ret = rcl_wait_set_init( + &wait_set, + sufficient_capacities.size_of_subscriptions, + sufficient_capacities.size_of_guard_conditions, + sufficient_capacities.size_of_timers, + sufficient_capacities.size_of_clients, + sufficient_capacities.size_of_services, + sufficient_capacities.size_of_events, + rcl_context, + allocator); + if (ret != RCL_RET_OK) { + return ::testing::AssertionFailure() << + "Calling rcl_wait_set_init() with expected sufficient capacities failed"; + } + + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set)); + }); + + if (!allocator_memory_strategy()->add_handles_to_wait_set(&wait_set)) { + return ::testing::AssertionFailure() << + "Calling add_handles_to_wait_set() with a wait_set with expected sufficient capacities" + " failed"; + } + + rcl_wait_set_t wait_set_no_capacity = rcl_get_zero_initialized_wait_set(); + ret = rcl_wait_set_init( + &wait_set_no_capacity, + insufficient_capacities.size_of_subscriptions, + insufficient_capacities.size_of_guard_conditions, + insufficient_capacities.size_of_timers, + insufficient_capacities.size_of_clients, + insufficient_capacities.size_of_services, + insufficient_capacities.size_of_events, + rcl_context, + allocator); + + if (ret != RCL_RET_OK) { + return ::testing::AssertionFailure() << + "Calling rcl_wait_set_init() with expected insufficient capacities failed"; + } + + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set_no_capacity)); + }); + + if (allocator_memory_strategy()->add_handles_to_wait_set(&wait_set_no_capacity)) { + return ::testing::AssertionFailure() << + "Calling add_handles_to_wait_set() with a wait_set with insufficient capacities" + " unexpectedly succeeded"; + } + return ::testing::AssertionSuccess(); + } + + ::testing::AssertionResult TestGetNextEntity( + std::shared_ptr node_with_entity1, + std::shared_ptr node_with_entity2, + std::function get_next_entity_func) + { + WeakNodeList nodes; + auto basic_node = std::make_shared("basic_node", "ns"); + nodes.push_back(node_with_entity1->get_node_base_interface()); + nodes.push_back(basic_node->get_node_base_interface()); + allocator_memory_strategy()->collect_entities(nodes); + + rclcpp::AnyExecutable result = get_next_entity_func(nodes); + if (result.node_base != node_with_entity1->get_node_base_interface()) { + return ::testing::AssertionFailure() << + "Failed to get expected entity with specified get_next_*() function"; + } + + WeakNodeList uncollected_nodes; + auto basic_node2 = std::make_shared("basic_node2", "ns"); + uncollected_nodes.push_back(node_with_entity2->get_node_base_interface()); + uncollected_nodes.push_back(basic_node2->get_node_base_interface()); + + rclcpp::AnyExecutable failed_result = get_next_entity_func(uncollected_nodes); + if (nullptr != failed_result.node_base) { + return ::testing::AssertionFailure() << + "A node was retrieved with the specified get_next_*() function despite" + " none of the nodes that were passed to it were added to the" + " allocator_memory_strategy"; + } + return ::testing::AssertionSuccess(); + } + + ::testing::AssertionResult TestGetNextEntityMutuallyExclusive( + std::shared_ptr node_with_entity, + std::function get_next_entity_func) + { + WeakNodeList nodes; + auto basic_node = std::make_shared("basic_node", "ns"); + + auto node_base = node_with_entity->get_node_base_interface(); + auto basic_node_base = basic_node->get_node_base_interface(); + nodes.push_back(node_base); + nodes.push_back(basic_node_base); + allocator_memory_strategy()->collect_entities(nodes); + + // It's important that these be set after collect_entities() otherwise collect_entities() will + // not do anything + node_base->get_default_callback_group()->can_be_taken_from() = false; + basic_node_base->get_default_callback_group()->can_be_taken_from() = false; + for (auto & callback_group : callback_groups_) { + callback_group->can_be_taken_from() = false; + } + + rclcpp::AnyExecutable result = get_next_entity_func(nodes); + + if (nullptr != result.node_base) { + return ::testing::AssertionFailure() << + "A node was retrieved with the specified get_next_*() function despite" + " setting can_be_taken_from() to false for all nodes and callback_groups"; + } + + return ::testing::AssertionSuccess(); + } + + std::vector> callback_groups_; + +private: + std::shared_ptr> allocator_memory_strategy_; + + size_t num_ready_subscriptions_of_basic_node_; + size_t num_ready_services_of_basic_node_; + size_t num_ready_events_of_basic_node_; + size_t num_ready_clients_of_basic_node_; + size_t num_guard_conditions_of_basic_node_; + size_t num_ready_timers_of_basic_node_; + size_t num_waitables_of_basic_node_; + + // These are generally kept as weak pointers in the rclcpp::Node interfaces, so they need to be + // owned by this class. + std::vector subscriptions_; + std::vector services_; + std::vector clients_; + std::vector timers_; + std::vector waitables_; +}; + +TEST_F(TestAllocatorMemoryStrategy, construct_destruct) { + WeakNodeList nodes; + auto basic_node = std::make_shared("node", "ns"); + nodes.push_back(basic_node->get_node_base_interface()); + allocator_memory_strategy()->collect_entities(nodes); + EXPECT_EQ(0u, number_of_ready_subscriptions_in_addition_to_basic_node()); + EXPECT_EQ(0u, number_of_ready_services_in_addition_to_basic_node()); + EXPECT_EQ(0u, number_of_ready_events_in_addition_to_basic_node()); + EXPECT_EQ(0u, number_of_ready_clients_in_addition_to_basic_node()); + EXPECT_EQ(0u, number_of_guard_conditions_in_addition_to_basic_node()); + EXPECT_EQ(0u, number_of_ready_timers_in_addition_to_basic_node()); + EXPECT_EQ(0u, number_of_waitables_in_addition_to_basic_node()); +} + +TEST_F(TestAllocatorMemoryStrategy, add_remove_guard_conditions) { + rcl_guard_condition_t guard_condition1 = rcl_get_zero_initialized_guard_condition(); + rcl_guard_condition_t guard_condition2 = rcl_get_zero_initialized_guard_condition(); + rcl_guard_condition_t guard_condition3 = rcl_get_zero_initialized_guard_condition(); + + EXPECT_NO_THROW(allocator_memory_strategy()->add_guard_condition(&guard_condition1)); + EXPECT_NO_THROW(allocator_memory_strategy()->add_guard_condition(&guard_condition2)); + EXPECT_NO_THROW(allocator_memory_strategy()->add_guard_condition(&guard_condition3)); + EXPECT_EQ(3u, allocator_memory_strategy()->number_of_guard_conditions()); + + // Adding a second time should not add to vector + EXPECT_NO_THROW(allocator_memory_strategy()->add_guard_condition(&guard_condition1)); + EXPECT_NO_THROW(allocator_memory_strategy()->add_guard_condition(&guard_condition2)); + EXPECT_NO_THROW(allocator_memory_strategy()->add_guard_condition(&guard_condition3)); + EXPECT_EQ(3u, allocator_memory_strategy()->number_of_guard_conditions()); + + EXPECT_NO_THROW(allocator_memory_strategy()->remove_guard_condition(&guard_condition1)); + EXPECT_NO_THROW(allocator_memory_strategy()->remove_guard_condition(&guard_condition2)); + EXPECT_NO_THROW(allocator_memory_strategy()->remove_guard_condition(&guard_condition3)); + EXPECT_EQ(0u, allocator_memory_strategy()->number_of_guard_conditions()); + + // Removing second time should have no effect + EXPECT_NO_THROW(allocator_memory_strategy()->remove_guard_condition(&guard_condition1)); + EXPECT_NO_THROW(allocator_memory_strategy()->remove_guard_condition(&guard_condition2)); + EXPECT_NO_THROW(allocator_memory_strategy()->remove_guard_condition(&guard_condition3)); + EXPECT_EQ(0u, allocator_memory_strategy()->number_of_guard_conditions()); +} + +TEST_F(TestAllocatorMemoryStrategy, add_remove_waitables) { + EXPECT_THROW(allocator_memory_strategy()->add_waitable_handle(nullptr), std::runtime_error); + EXPECT_EQ(0u, allocator_memory_strategy()->number_of_waitables()); + + rclcpp::Waitable::SharedPtr waitable = std::make_shared(); + EXPECT_NO_THROW(allocator_memory_strategy()->add_waitable_handle(waitable)); + EXPECT_EQ(1u, allocator_memory_strategy()->number_of_waitables()); + + EXPECT_NO_THROW(allocator_memory_strategy()->clear_handles()); + EXPECT_EQ(0u, allocator_memory_strategy()->number_of_waitables()); +} + +TEST_F(TestAllocatorMemoryStrategy, number_of_entities_with_subscription) { + RclWaitSetSizes expected_sizes = {}; + expected_sizes.size_of_subscriptions = 1; + auto node_with_subscription = create_node_with_subscription("subscription_node", false); + EXPECT_TRUE(TestNumberOfEntitiesAfterCollection(node_with_subscription, expected_sizes)); +} + +TEST_F(TestAllocatorMemoryStrategy, number_of_entities_with_service) { + RclWaitSetSizes expected_sizes = {}; + expected_sizes.size_of_services = 1; + auto node_with_service = create_node_with_service("service_node"); + EXPECT_TRUE(TestNumberOfEntitiesAfterCollection(node_with_service, expected_sizes)); +} + +TEST_F(TestAllocatorMemoryStrategy, number_of_entities_with_client) { + RclWaitSetSizes expected_sizes = {}; + expected_sizes.size_of_clients = 1; + auto node_with_client = create_node_with_client("client_node"); + EXPECT_TRUE(TestNumberOfEntitiesAfterCollection(node_with_client, expected_sizes)); +} + +TEST_F(TestAllocatorMemoryStrategy, number_of_entities_with_timer) { + RclWaitSetSizes expected_sizes = {}; + expected_sizes.size_of_timers = 1; + auto node_with_timer = create_node_with_timer("timer_node"); + EXPECT_TRUE(TestNumberOfEntitiesAfterCollection(node_with_timer, expected_sizes)); +} + +TEST_F(TestAllocatorMemoryStrategy, add_handles_to_wait_set_bad_arguments) { + auto node = create_node_with_subscription("subscription_node", false); + WeakNodeList nodes; + nodes.push_back(node->get_node_base_interface()); + allocator_memory_strategy()->collect_entities(nodes); + EXPECT_FALSE(allocator_memory_strategy()->add_handles_to_wait_set(nullptr)); + EXPECT_TRUE(rcl_error_is_set()); + rcl_reset_error(); +} + +TEST_F(TestAllocatorMemoryStrategy, add_handles_to_wait_set_subscription) { + auto node_with_subscription = create_node_with_subscription("subscription_node", false); + RclWaitSetSizes insufficient_capacities = SufficientWaitSetCapacities(); + insufficient_capacities.size_of_subscriptions = 0; + EXPECT_TRUE(TestAddHandlesToWaitSet(node_with_subscription, insufficient_capacities)); +} + +TEST_F(TestAllocatorMemoryStrategy, add_handles_to_wait_set_service) { + auto node_with_service = create_node_with_service("service_node"); + RclWaitSetSizes insufficient_capacities = SufficientWaitSetCapacities(); + insufficient_capacities.size_of_services = 0; + EXPECT_TRUE(TestAddHandlesToWaitSet(node_with_service, insufficient_capacities)); +} + +TEST_F(TestAllocatorMemoryStrategy, add_handles_to_wait_set_client) { + auto node_with_client = create_node_with_client("client_node"); + RclWaitSetSizes insufficient_capacities = SufficientWaitSetCapacities(); + insufficient_capacities.size_of_clients = 0; + EXPECT_TRUE(TestAddHandlesToWaitSet(node_with_client, insufficient_capacities)); +} + +TEST_F(TestAllocatorMemoryStrategy, add_handles_to_wait_set_timer) { + auto node_with_timer = create_node_with_timer("timer_node"); + RclWaitSetSizes insufficient_capacities = SufficientWaitSetCapacities(); + insufficient_capacities.size_of_timers = 0; + EXPECT_TRUE(TestAddHandlesToWaitSet(node_with_timer, insufficient_capacities)); +} + +TEST_F(TestAllocatorMemoryStrategy, add_handles_to_wait_set_waitable) { + rclcpp::Waitable::SharedPtr waitable = std::make_shared(); + EXPECT_NO_THROW(allocator_memory_strategy()->add_waitable_handle(waitable)); + EXPECT_EQ(1u, allocator_memory_strategy()->number_of_waitables()); + + test_waitable_result = true; + EXPECT_TRUE(allocator_memory_strategy()->add_handles_to_wait_set(nullptr)); + + test_waitable_result = false; + EXPECT_FALSE(allocator_memory_strategy()->add_handles_to_wait_set(nullptr)); + + // This calls TestWaitable's functions, so rcl errors are not set + EXPECT_FALSE(rcl_error_is_set()); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_subscription) { + auto node1 = create_node_with_subscription("node1", false); + auto node2 = create_node_with_subscription("node2", false); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_subscription(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntity(node1, node2, get_next_entity)); + + // Allocator memory strategy clears subscription handles in this case + EXPECT_EQ(0u, allocator_memory_strategy()->number_of_ready_subscriptions()); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_service) { + auto node1 = create_node_with_service("node1", false); + auto node2 = create_node_with_service("node2", false); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_service(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntity(node1, node2, get_next_entity)); + + // Allocator memory strategy clears subscription handles in this case + EXPECT_EQ(0u, allocator_memory_strategy()->number_of_ready_services()); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_client) { + auto node1 = create_node_with_client("node1", false); + auto node2 = create_node_with_client("node2", false); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_client(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntity(node1, node2, get_next_entity)); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_timer) { + auto node1 = create_node_with_timer("node1", false); + auto node2 = create_node_with_timer("node2", false); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_timer(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntity(node1, node2, get_next_entity)); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_waitable) { + auto node1 = std::make_shared("waitable_node", "ns"); + auto node2 = std::make_shared("waitable_node2", "ns"); + rclcpp::Waitable::SharedPtr waitable = std::make_shared(); + node1->get_node_waitables_interface()->add_waitable(waitable, nullptr); + node2->get_node_waitables_interface()->add_waitable(waitable, nullptr); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_waitable(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntity(node1, node2, get_next_entity)); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_subscription_mutually_exclusive) { + auto node = create_node_with_subscription("node", true); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_subscription(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntityMutuallyExclusive(node, get_next_entity)); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_service_mutually_exclusive) { + auto node = create_node_with_service("node", true); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_service(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntityMutuallyExclusive(node, get_next_entity)); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_client_mutually_exclusive) { + auto node = create_node_with_client("node", true); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_client(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntityMutuallyExclusive(node, get_next_entity)); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_timer_mutually_exclusive) { + auto node = create_node_with_timer("node", true); + + auto get_next_entity = [this](const WeakNodeList & nodes) { + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_timer(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntityMutuallyExclusive(node, get_next_entity)); +} + +TEST_F(TestAllocatorMemoryStrategy, get_next_waitable_mutually_exclusive) { + auto node = std::make_shared("waitable_node", "ns"); + rclcpp::Waitable::SharedPtr waitable = std::make_shared(); + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + node->get_node_waitables_interface()->add_waitable(waitable, callback_group); + + auto get_next_entity = [this, callback_group](const WeakNodeList & nodes) { + // This callback group isn't in the base class' callback_group list, so this needs to be done + // before get_next_waitable() is called. + callback_group->can_be_taken_from() = false; + + rclcpp::AnyExecutable result; + allocator_memory_strategy()->get_next_waitable(result, nodes); + return result; + }; + + EXPECT_TRUE(TestGetNextEntityMutuallyExclusive(node, get_next_entity)); +} diff --git a/rclcpp/test/rclcpp/strategies/test_message_pool_memory_strategy.cpp b/rclcpp/test/rclcpp/strategies/test_message_pool_memory_strategy.cpp new file mode 100644 index 0000000000..1ff9510d1e --- /dev/null +++ b/rclcpp/test/rclcpp/strategies/test_message_pool_memory_strategy.cpp @@ -0,0 +1,64 @@ +// 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 "gtest/gtest.h" + +#include "rclcpp/strategies/message_pool_memory_strategy.hpp" +#include "test_msgs/msg/empty.hpp" + +using rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy; + +class TestMessagePoolMemoryStrategy : public ::testing::Test +{ +public: + void SetUp() + { + message_memory_strategy_ = + std::make_shared>(); + } + +protected: + std::shared_ptr> message_memory_strategy_; +}; + +TEST_F(TestMessagePoolMemoryStrategy, construct_destruct) { +} + +TEST_F(TestMessagePoolMemoryStrategy, borrow_return) { + auto message = message_memory_strategy_->borrow_message(); + ASSERT_NE(nullptr, message); + + EXPECT_NO_THROW(message_memory_strategy_->return_message(message)); +} + +TEST_F(TestMessagePoolMemoryStrategy, borrow_too_many) { + auto message = message_memory_strategy_->borrow_message(); + ASSERT_NE(nullptr, message); + + // Size is 1, borrowing second time should fail + EXPECT_THROW(message_memory_strategy_->borrow_message(), std::runtime_error); + EXPECT_NO_THROW(message_memory_strategy_->return_message(message)); +} + +TEST_F(TestMessagePoolMemoryStrategy, return_unrecognized) { + auto message = message_memory_strategy_->borrow_message(); + ASSERT_NE(nullptr, message); + + auto unrecognized = std::make_shared(); + // Unrecognized does not belong to pool + EXPECT_THROW(message_memory_strategy_->return_message(unrecognized), std::runtime_error); + EXPECT_NO_THROW(message_memory_strategy_->return_message(message)); +} diff --git a/rclcpp/test/rclcpp/test_memory_strategy.cpp b/rclcpp/test/rclcpp/test_memory_strategy.cpp new file mode 100644 index 0000000000..3631a1fed8 --- /dev/null +++ b/rclcpp/test/rclcpp/test_memory_strategy.cpp @@ -0,0 +1,399 @@ +// 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 + +#include "rclcpp/strategies/allocator_memory_strategy.hpp" +#include "rclcpp/memory_strategy.hpp" +#include "test_msgs/msg/empty.hpp" +#include "test_msgs/srv/empty.hpp" + +using rclcpp::memory_strategy::MemoryStrategy; +using WeakNodeList = std::list; + +/** + * Mock Waitable class + */ +class TestWaitable : public rclcpp::Waitable +{ +public: + bool add_to_wait_set(rcl_wait_set_t *) override {return true;} + bool is_ready(rcl_wait_set_t *) override {return true;} + void execute() override {} +}; + +class TestMemoryStrategy : public ::testing::Test +{ +public: + TestMemoryStrategy() + : memory_strategy_(nullptr) {} + + void SetUp() override + { + rclcpp::init(0, nullptr); + + // This doesn't test AllocatorMemoryStrategy directly, so we cast to the base class. + // AllocatorMemoryStrategy is more commonly used than MessagePoolMemoryStrategy + // so we use this derived class for these tests. + memory_strategy_ = + std::make_shared< + rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<>>(); + } + + void TearDown() override + { + rclcpp::shutdown(); + } + +protected: + std::shared_ptr memory_strategy() + { + return memory_strategy_; + } + +private: + std::shared_ptr memory_strategy_; +}; + +TEST_F(TestMemoryStrategy, construct_destruct) { +} + +TEST_F(TestMemoryStrategy, get_subscription_by_handle) { + WeakNodeList nodes; + std::shared_ptr subscription_handle; + rclcpp::SubscriptionBase::SharedPtr found_subscription = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto subscription_callback = [](const test_msgs::msg::Empty::SharedPtr) {}; + const rclcpp::QoS qos(10); + + { + auto subscription = node->create_subscription< + test_msgs::msg::Empty, decltype(subscription_callback)>( + "topic", qos, std::move(subscription_callback)); + + subscription_handle = subscription->get_subscription_handle(); + + EXPECT_EQ( + subscription, + memory_strategy()->get_subscription_by_handle(subscription_handle, nodes)); + } // subscription goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_subscription_by_handle(subscription_handle, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_subscription_by_handle(subscription_handle, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_subscription_by_handle(subscription_handle, nodes)); +} + +TEST_F(TestMemoryStrategy, get_service_by_handle) { + WeakNodeList nodes; + std::shared_ptr service_handle; + rclcpp::ServiceBase::SharedPtr found_service = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto service_callback = + [](const test_msgs::srv::Empty::Request::SharedPtr, + test_msgs::srv::Empty::Response::SharedPtr) {}; + const rclcpp::QoS qos(10); + + { + auto service = node->create_service( + "service", std::move(service_callback), + rmw_qos_profile_services_default, callback_group); + + service_handle = service->get_service_handle(); + + EXPECT_EQ( + service, + memory_strategy()->get_service_by_handle(service_handle, nodes)); + } // service goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_service_by_handle(service_handle, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_service_by_handle(service_handle, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_service_by_handle(service_handle, nodes)); +} + +TEST_F(TestMemoryStrategy, get_client_by_handle) { + WeakNodeList nodes; + std::shared_ptr client_handle; + rclcpp::ClientBase::SharedPtr found_client = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + { + auto client = node->create_client( + "service", rmw_qos_profile_services_default, callback_group); + + client_handle = client->get_client_handle(); + + EXPECT_EQ( + client, + memory_strategy()->get_client_by_handle(client_handle, nodes)); + } // client goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_client_by_handle(client_handle, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_client_by_handle(client_handle, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_client_by_handle(client_handle, nodes)); +} + +TEST_F(TestMemoryStrategy, get_timer_by_handle) { + WeakNodeList nodes; + std::shared_ptr timer_handle; + rclcpp::TimerBase::SharedPtr found_timer = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + { + auto timer_callback = []() {}; + auto timer = node->create_wall_timer( + std::chrono::milliseconds(1), timer_callback, callback_group); + + timer_handle = timer->get_timer_handle(); + + EXPECT_EQ( + timer, + memory_strategy()->get_timer_by_handle(timer_handle, nodes)); + } // timer goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_timer_by_handle(timer_handle, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_timer_by_handle(timer_handle, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_timer_by_handle(timer_handle, nodes)); +} + +TEST_F(TestMemoryStrategy, get_node_by_group) { + WeakNodeList nodes; + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr; + { + auto node = std::make_shared("node", "ns"); + auto node_handle = node->get_node_base_interface(); + nodes.push_back(node_handle); + memory_strategy()->collect_entities(nodes); + EXPECT_EQ( + nullptr, + memory_strategy()->get_node_by_group(nullptr, nodes)); + + callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + + EXPECT_EQ( + node_handle, + memory_strategy()->get_node_by_group(callback_group, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_node_by_group(callback_group, nodes)); +} + +TEST_F(TestMemoryStrategy, get_group_by_subscription) { + WeakNodeList nodes; + rclcpp::SubscriptionBase::SharedPtr subscription = nullptr; + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + // This group is just used to test that a callback group that is held as a weak pointer + // by node, doesn't confuse get_groupp_by_subscription() when it goes out of scope + auto non_persistant_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + + callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto subscription_callback = [](const test_msgs::msg::Empty::SharedPtr) {}; + const rclcpp::QoS qos(10); + + rclcpp::SubscriptionOptions subscription_options; + + // This callback group is held as a shared_ptr in subscription_options, which means it + // stays alive as long as subscription does. + subscription_options.callback_group = callback_group; + + subscription = node->create_subscription< + test_msgs::msg::Empty, decltype(subscription_callback)>( + "topic", qos, std::move(subscription_callback), subscription_options); + + EXPECT_EQ( + callback_group, + memory_strategy()->get_group_by_subscription(subscription, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + callback_group, + memory_strategy()->get_group_by_subscription(subscription, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_subscription(subscription, nodes)); +} + +TEST_F(TestMemoryStrategy, get_group_by_service) { + WeakNodeList nodes; + rclcpp::ServiceBase::SharedPtr service = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto service_callback = + [](const test_msgs::srv::Empty::Request::SharedPtr, + test_msgs::srv::Empty::Response::SharedPtr) {}; + const rclcpp::QoS qos(10); + + service = node->create_service( + "service", std::move(service_callback), + rmw_qos_profile_services_default, callback_group); + + EXPECT_EQ( + callback_group, + memory_strategy()->get_group_by_service(service, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_service(service, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_service(service, nodes)); +} + +TEST_F(TestMemoryStrategy, get_group_by_client) { + WeakNodeList nodes; + rclcpp::ClientBase::SharedPtr client = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + + client = node->create_client( + "service", rmw_qos_profile_services_default, callback_group); + + EXPECT_EQ( + callback_group, + memory_strategy()->get_group_by_client(client, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_client(client, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_client(client, nodes)); +} + +TEST_F(TestMemoryStrategy, get_group_by_timer) { + WeakNodeList nodes; + rclcpp::TimerBase::SharedPtr timer = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto timer_callback = []() {}; + timer = node->create_wall_timer( + std::chrono::milliseconds(1), timer_callback, callback_group); + + EXPECT_EQ( + callback_group, + memory_strategy()->get_group_by_timer(timer, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_timer(timer, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_timer(timer, nodes)); +} + +TEST_F(TestMemoryStrategy, get_group_by_waitable) { + WeakNodeList nodes; + rclcpp::Waitable::SharedPtr waitable = nullptr; + { + auto node = std::make_shared("node", "ns"); + nodes.push_back(node->get_node_base_interface()); + memory_strategy()->collect_entities(nodes); + { + waitable = std::make_shared(); + auto callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + node->get_node_waitables_interface()->add_waitable(waitable, callback_group); + + EXPECT_EQ( + callback_group, + memory_strategy()->get_group_by_waitable(waitable, nodes)); + } // callback_group goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_waitable(waitable, nodes)); + } // Node goes out of scope + EXPECT_EQ( + nullptr, + memory_strategy()->get_group_by_waitable(waitable, nodes)); +} diff --git a/rclcpp/test/rclcpp/test_message_memory_strategy.cpp b/rclcpp/test/rclcpp/test_message_memory_strategy.cpp new file mode 100644 index 0000000000..686acf2a5d --- /dev/null +++ b/rclcpp/test/rclcpp/test_message_memory_strategy.cpp @@ -0,0 +1,49 @@ +// 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 "rclcpp/message_memory_strategy.hpp" +#include "test_msgs/msg/empty.hpp" + +TEST(TestMemoryStrategies, construct_destruct) { + rclcpp::message_memory_strategy::MessageMemoryStrategy memory_strategy1; + + auto allocator = std::make_shared>(); + rclcpp::message_memory_strategy::MessageMemoryStrategy memory_strategy2( + allocator); +} + +TEST(TestMemoryStrategies, standard_allocation) { + rclcpp::message_memory_strategy::MessageMemoryStrategy memory_strategy; + auto default_message = memory_strategy.create_default(); + ASSERT_NE(nullptr, default_message); + + auto borrowed_message = memory_strategy.borrow_message(); + ASSERT_NE(nullptr, borrowed_message); + EXPECT_NO_THROW(memory_strategy.return_message(borrowed_message)); + + auto serialized_message = memory_strategy.borrow_serialized_message(); + ASSERT_NE(nullptr, serialized_message); + EXPECT_EQ(0u, serialized_message->capacity()); + EXPECT_NO_THROW(memory_strategy.return_serialized_message(serialized_message)); + + memory_strategy.set_default_buffer_capacity(42); + serialized_message = memory_strategy.borrow_serialized_message(); + ASSERT_NE(nullptr, serialized_message); + EXPECT_EQ(42u, serialized_message->capacity()); + EXPECT_NO_THROW(memory_strategy.return_serialized_message(serialized_message)); +}