|
| 1 | +// Copyright 2021 Open Source Robotics Foundation, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | +#include <chrono> |
| 15 | +#include <memory> |
| 16 | +#include <gtest/gtest.h> |
| 17 | + |
| 18 | +#include "rclcpp/executors/events_executor.hpp" |
| 19 | +#include "rclcpp/experimental/buffers/bounded_events_queue.hpp" |
| 20 | + |
| 21 | +#include "test_msgs/msg/empty.hpp" |
| 22 | + |
| 23 | +using namespace std::chrono_literals; |
| 24 | + |
| 25 | +using rclcpp::executors::EventsExecutor; |
| 26 | + |
| 27 | +class TestEventsQueue : public ::testing::Test |
| 28 | +{ |
| 29 | +public: |
| 30 | + void SetUp() |
| 31 | + { |
| 32 | + rclcpp::init(0, nullptr); |
| 33 | + } |
| 34 | + |
| 35 | + void TearDown() |
| 36 | + { |
| 37 | + rclcpp::shutdown(); |
| 38 | + } |
| 39 | +}; |
| 40 | + |
| 41 | +TEST_F(TestEventsQueue, BoundedQueue) |
| 42 | +{ |
| 43 | + // Create BoundedEventsQueue and set limit to 10 events. |
| 44 | + auto bounded_queue = std::make_unique<rclcpp::experimental::buffers::BoundedEventsQueue>(); |
| 45 | + bounded_queue->set_queue_size_limit(10); |
| 46 | + |
| 47 | + // Create an events executor using the bounded queue |
| 48 | + EventsExecutor executor_sub(std::move(bounded_queue)); |
| 49 | + |
| 50 | + // Create a subscription node |
| 51 | + auto node_sub = std::make_shared<rclcpp::Node>("node_sub"); |
| 52 | + |
| 53 | + size_t callback_count = 0; |
| 54 | + |
| 55 | + auto subscription = |
| 56 | + node_sub->create_subscription<test_msgs::msg::Empty>( |
| 57 | + "topic", |
| 58 | + rclcpp::QoS(10), |
| 59 | + [&](test_msgs::msg::Empty::SharedPtr) { |
| 60 | + callback_count++; |
| 61 | + }); |
| 62 | + |
| 63 | + // Add susbscription node to the executor, so the queue can start getting events |
| 64 | + executor_sub.add_node(node_sub); |
| 65 | + |
| 66 | + // Create a publisher node |
| 67 | + auto node_pub = std::make_shared<rclcpp::Node>("node_pub"); |
| 68 | + auto publisher = node_pub->create_publisher<test_msgs::msg::Empty>("topic", rclcpp::QoS(10)); |
| 69 | + |
| 70 | + // Let subscriptions executor spin to execute any previous events |
| 71 | + // not related to the subscription, so we start with an empty queue |
| 72 | + executor_sub.spin_some(10ms); |
| 73 | + |
| 74 | + // Publish 11 messages, the eleventh msg should prune the queue |
| 75 | + // and we should end up with only one event on it |
| 76 | + for (int i = 0; i < 11; i++) { |
| 77 | + publisher->publish(std::make_unique<test_msgs::msg::Empty>()); |
| 78 | + std::this_thread::sleep_for(1ms); |
| 79 | + } |
| 80 | + |
| 81 | + // Let subscriptions executor spin |
| 82 | + executor_sub.spin_some(10ms); |
| 83 | + |
| 84 | + // The callback count should be 1 |
| 85 | + EXPECT_EQ(1u, callback_count); |
| 86 | + |
| 87 | + // Reset callback count |
| 88 | + callback_count = 0; |
| 89 | + |
| 90 | + // Publish 5 messages |
| 91 | + for (int i = 0; i < 5; i++) { |
| 92 | + publisher->publish(std::make_unique<test_msgs::msg::Empty>()); |
| 93 | + std::this_thread::sleep_for(1ms); |
| 94 | + } |
| 95 | + |
| 96 | + // Let subscriptions executor spin |
| 97 | + executor_sub.spin_some(10ms); |
| 98 | + |
| 99 | + // The callback count should be 5, the queue shouldn't have been pruned |
| 100 | + EXPECT_EQ(5u, callback_count); |
| 101 | +} |
| 102 | + |
| 103 | +TEST_F(TestEventsQueue, SimpleQueue) |
| 104 | +{ |
| 105 | + // Create SimpleEventsQueue |
| 106 | + auto simple_queue = std::make_unique<rclcpp::experimental::buffers::SimpleEventsQueue>(); |
| 107 | + |
| 108 | + // Create an events executor using the simple queue |
| 109 | + EventsExecutor executor_sub(std::move(simple_queue)); |
| 110 | + |
| 111 | + // Create a subscription node with QoS->depth = 10 |
| 112 | + auto node_sub = std::make_shared<rclcpp::Node>("node_sub"); |
| 113 | + |
| 114 | + size_t callback_count = 0; |
| 115 | + |
| 116 | + auto subscription = |
| 117 | + node_sub->create_subscription<test_msgs::msg::Empty>( |
| 118 | + "topic", |
| 119 | + rclcpp::QoS(10), |
| 120 | + [&](test_msgs::msg::Empty::SharedPtr) { |
| 121 | + callback_count++; |
| 122 | + }); |
| 123 | + |
| 124 | + // Add susbscription node to the executor, so the queue can start getting events |
| 125 | + executor_sub.add_node(node_sub); |
| 126 | + |
| 127 | + // Create a publisher node |
| 128 | + auto node_pub = std::make_shared<rclcpp::Node>("node_pub"); |
| 129 | + auto publisher = node_pub->create_publisher<test_msgs::msg::Empty>("topic", rclcpp::QoS(10)); |
| 130 | + |
| 131 | + // Let subscriptions executor spin to execute any previous events |
| 132 | + // not related to the subscription, so we start with an empty queue |
| 133 | + executor_sub.spin_some(10ms); |
| 134 | + |
| 135 | + // Publish 11 messages, but as the subscription has only 10 as queue depth, |
| 136 | + // we should lost a message (the events queue finish with 11 messages but one is not valid) |
| 137 | + for (int i = 0; i < 11; i++) { |
| 138 | + publisher->publish(std::make_unique<test_msgs::msg::Empty>()); |
| 139 | + std::this_thread::sleep_for(1ms); |
| 140 | + } |
| 141 | + |
| 142 | + // Let subscriptions executor spin |
| 143 | + executor_sub.spin_some(10ms); |
| 144 | + |
| 145 | + // The callback count should be 10 |
| 146 | + EXPECT_EQ(10u, callback_count); |
| 147 | +} |
0 commit comments