Skip to content

Commit 6fb2463

Browse files
author
Mauro Passerino
committed
Test all events queue APIs
1 parent 5780ccf commit 6fb2463

File tree

3 files changed

+77
-86
lines changed

3 files changed

+77
-86
lines changed

rclcpp/include/rclcpp/experimental/buffers/bounded_events_queue.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <queue>
1919
#include <utility>
2020

21-
#include "rclcpp/executors/events_queue.hpp"
21+
#include "rclcpp/experimental/buffers/events_queue.hpp"
2222

2323
namespace rclcpp
2424
{

rclcpp/include/rclcpp/experimental/buffers/simple_events_queue.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <queue>
1919
#include <utility>
2020

21-
#include "rclcpp/executors/events_queue.hpp"
21+
#include "rclcpp/experimental/buffers/events_queue.hpp"
2222

2323
namespace rclcpp
2424
{

rclcpp/test/rclcpp/executors/test_events_queue.cpp

Lines changed: 75 additions & 84 deletions
Original file line numberDiff line numberDiff line change
@@ -12,18 +12,15 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414
#include <chrono>
15-
#include <memory>
15+
#include <queue>
16+
1617
#include <gtest/gtest.h>
1718

18-
#include "rclcpp/executors/events_executor.hpp"
19+
#include "rclcpp/experimental/buffers/simple_events_queue.hpp"
1920
#include "rclcpp/experimental/buffers/bounded_events_queue.hpp"
2021

21-
#include "test_msgs/msg/empty.hpp"
22-
2322
using namespace std::chrono_literals;
2423

25-
using rclcpp::executors::EventsExecutor;
26-
2724
class TestEventsQueue : public ::testing::Test
2825
{
2926
public:
@@ -38,109 +35,103 @@ class TestEventsQueue : public ::testing::Test
3835
}
3936
};
4037

41-
TEST_F(TestEventsQueue, BoundedQueue)
38+
TEST_F(TestEventsQueue, SimpleQueueTest)
4239
{
43-
// Create BoundedEventsQueue and set limit to 10 events.
44-
auto bounded_queue = std::make_unique<rclcpp::experimental::buffers::BoundedEventsQueue>(10);
40+
// Create a SimpleEventsQueue and a local queue
41+
auto simple_queue = std::make_unique<rclcpp::experimental::buffers::SimpleEventsQueue>();
42+
std::queue<rmw_listener_event_t> local_events_queue;
43+
44+
// Make sure the queue is empty after init
45+
simple_queue->init();
46+
EXPECT_TRUE(simple_queue->empty());
4547

46-
// Create an events executor using the bounded queue
47-
EventsExecutor executor_sub(std::move(bounded_queue));
48+
// Push 11 messages
49+
for (int i = 0; i < 11; i++) {
50+
rmw_listener_event_t stub_event;
51+
simple_queue->push(stub_event);
52+
}
4853

49-
// Create a subscription node
50-
auto node_sub = std::make_shared<rclcpp::Node>("node_sub");
54+
// Pop one message
55+
simple_queue->pop();
5156

52-
size_t callback_count = 0;
57+
local_events_queue = simple_queue->get_all_events();
5358

54-
auto subscription =
55-
node_sub->create_subscription<test_msgs::msg::Empty>(
56-
"topic",
57-
rclcpp::QoS(10),
58-
[&](test_msgs::msg::Empty::SharedPtr) {
59-
callback_count++;
60-
});
59+
// We should have (11 - 1) events in the local queue
60+
size_t local_queue_size = local_events_queue.size();
6161

62-
// Add susbscription node to the executor, so the queue can start getting events
63-
executor_sub.add_node(node_sub);
62+
// The local queue size should be 10
63+
EXPECT_EQ(10u, local_queue_size);
6464

65-
// Create a publisher node
66-
auto node_pub = std::make_shared<rclcpp::Node>("node_pub");
67-
auto publisher = node_pub->create_publisher<test_msgs::msg::Empty>("topic", rclcpp::QoS(10));
65+
// The simple queue should be empty after taking all events
66+
EXPECT_TRUE(simple_queue->empty());
6867

69-
// Let subscriptions executor spin to execute any previous events
70-
// not related to the subscription, so we start with an empty queue
71-
executor_sub.spin_some(10ms);
68+
// Lets push an event into the queue and get it back
69+
rmw_listener_event_t push_event = {simple_queue.get(), SUBSCRIPTION_EVENT};
7270

73-
// Publish 11 messages, the eleventh msg should prune the queue
74-
// and we should end up with only one event on it
75-
for (int i = 0; i < 11; i++) {
76-
publisher->publish(std::make_unique<test_msgs::msg::Empty>());
77-
std::this_thread::sleep_for(1ms);
78-
}
71+
simple_queue->push(push_event);
7972

80-
// Let subscriptions executor spin
81-
executor_sub.spin_some(10ms);
73+
rmw_listener_event_t front_event = simple_queue->front();
8274

83-
// The callback count should be 1
84-
EXPECT_EQ(1u, callback_count);
75+
// The events should be equal
76+
EXPECT_EQ(push_event.entity, front_event.entity);
77+
EXPECT_EQ(push_event.type, front_event.type);
78+
}
8579

86-
// Reset callback count
87-
callback_count = 0;
8880

89-
// Publish 5 messages
90-
for (int i = 0; i < 5; i++) {
91-
publisher->publish(std::make_unique<test_msgs::msg::Empty>());
92-
std::this_thread::sleep_for(1ms);
81+
TEST_F(TestEventsQueue, BoundedQueueTest)
82+
{
83+
// Create a BoundedEventsQueue with limit of 10 events and a local events queue
84+
auto bounded_queue = std::make_unique<rclcpp::experimental::buffers::BoundedEventsQueue>(10);
85+
std::queue<rmw_listener_event_t> local_events_queue;
86+
87+
// Make sure the queue is empty after init
88+
bounded_queue->init();
89+
EXPECT_TRUE(bounded_queue->empty());
90+
91+
// Push 11 messages, the eleventh msg should prune the queue
92+
// and we should end up with only one event on it
93+
for (int i = 0; i < 11; i++) {
94+
rmw_listener_event_t stub_event;
95+
bounded_queue->push(stub_event);
9396
}
9497

95-
// Let subscriptions executor spin
96-
executor_sub.spin_some(10ms);
98+
local_events_queue = bounded_queue->get_all_events();
9799

98-
// The callback count should be 5, the queue shouldn't have been pruned
99-
EXPECT_EQ(5u, callback_count);
100-
}
100+
size_t local_queue_size = local_events_queue.size();
101101

102-
TEST_F(TestEventsQueue, SimpleQueue)
103-
{
104-
// Create SimpleEventsQueue
105-
auto simple_queue = std::make_unique<rclcpp::experimental::buffers::SimpleEventsQueue>();
102+
// The queue size should be 1
103+
EXPECT_EQ(1u, local_queue_size);
104+
105+
// The bounded queue should be empty after taking all events
106+
EXPECT_TRUE(bounded_queue->empty());
106107

107-
// Create an events executor using the simple queue
108-
EventsExecutor executor_sub(std::move(simple_queue));
108+
// Push 5 messages
109+
for (int i = 0; i < 5; i++) {
110+
rmw_listener_event_t stub_event;
111+
bounded_queue->push(stub_event);
112+
}
109113

110-
// Create a subscription node with QoS->depth = 10
111-
auto node_sub = std::make_shared<rclcpp::Node>("node_sub");
114+
// Pop one message
115+
bounded_queue->pop();
112116

113-
size_t callback_count = 0;
117+
local_events_queue = bounded_queue->get_all_events();
114118

115-
auto subscription =
116-
node_sub->create_subscription<test_msgs::msg::Empty>(
117-
"topic",
118-
rclcpp::QoS(10),
119-
[&](test_msgs::msg::Empty::SharedPtr) {
120-
callback_count++;
121-
});
119+
local_queue_size = local_events_queue.size();
122120

123-
// Add susbscription node to the executor, so the queue can start getting events
124-
executor_sub.add_node(node_sub);
121+
// The local queue size should be 4 as the bounded queue shouldn't have been pruned
122+
EXPECT_EQ(4u, local_queue_size);
125123

126-
// Create a publisher node
127-
auto node_pub = std::make_shared<rclcpp::Node>("node_pub");
128-
auto publisher = node_pub->create_publisher<test_msgs::msg::Empty>("topic", rclcpp::QoS(10));
124+
// The bounded queue should be empty after taking all events
125+
EXPECT_TRUE(bounded_queue->empty());
129126

130-
// Let subscriptions executor spin to execute any previous events
131-
// not related to the subscription, so we start with an empty queue
132-
executor_sub.spin_some(10ms);
127+
// Lets push an event into the queue and get it back
128+
rmw_listener_event_t push_event = {bounded_queue.get(), WAITABLE_EVENT};
133129

134-
// Publish 11 messages, but as the subscription has only 10 as queue depth,
135-
// we should lost a message (the events queue finish with 11 messages but one is not valid)
136-
for (int i = 0; i < 11; i++) {
137-
publisher->publish(std::make_unique<test_msgs::msg::Empty>());
138-
std::this_thread::sleep_for(1ms);
139-
}
130+
bounded_queue->push(push_event);
140131

141-
// Let subscriptions executor spin
142-
executor_sub.spin_some(10ms);
132+
rmw_listener_event_t front_event = bounded_queue->front();
143133

144-
// The callback count should be 10
145-
EXPECT_EQ(10u, callback_count);
134+
// The events should be the equal
135+
EXPECT_EQ(push_event.entity, front_event.entity);
136+
EXPECT_EQ(push_event.type, front_event.type);
146137
}

0 commit comments

Comments
 (0)