Skip to content

Commit a229b1b

Browse files
committed
Use deque instead of list and added unit tests
Signed-off-by: Pintaudi Giorgio <[email protected]>
1 parent 8143f1d commit a229b1b

File tree

2 files changed

+25
-7
lines changed

2 files changed

+25
-7
lines changed

launch_testing_ros/launch_testing_ros/wait_for_topics.py

Lines changed: 16 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
import string
1717
from threading import Event
1818
from threading import Thread
19+
from collections import deque
1920

2021
import rclpy
2122
from rclpy.executors import SingleThreadedExecutor
@@ -50,9 +51,10 @@ def method_2():
5051
wait_for_topics.shutdown()
5152
"""
5253

53-
def __init__(self, topic_tuples, timeout=5.0):
54+
def __init__(self, topic_tuples, timeout=5.0, max_number_of_messages=100):
5455
self.topic_tuples = topic_tuples
5556
self.timeout = timeout
57+
self.max_number_of_messages = max_number_of_messages
5658
self.__ros_context = rclpy.Context()
5759
rclpy.init(context=self.__ros_context)
5860
self.__ros_executor = SingleThreadedExecutor(context=self.__ros_context)
@@ -64,9 +66,13 @@ def __init__(self, topic_tuples, timeout=5.0):
6466
self.__ros_spin_thread.start()
6567

6668
def _prepare_ros_node(self):
67-
node_name = '_test_node_' +\
68-
''.join(random.choices(string.ascii_uppercase + string.digits, k=10))
69-
self.__ros_node = _WaitForTopicsNode(name=node_name, node_context=self.__ros_context)
69+
node_name = '_test_node_' + ''.join(
70+
random.choices(string.ascii_uppercase + string.digits, k=10)
71+
)
72+
self.__ros_node = _WaitForTopicsNode(
73+
name=node_name, node_context=self.__ros_context,
74+
max_number_of_messages=self.max_number_of_messages
75+
)
7076
self.__ros_executor.add_node(self.__ros_node)
7177

7278
def wait(self):
@@ -108,9 +114,11 @@ def __exit__(self, exep_type, exep_value, trace):
108114
class _WaitForTopicsNode(Node):
109115
"""Internal node used for subscribing to a set of topics."""
110116

111-
def __init__(self, name='test_node', node_context=None):
117+
def __init__(self, name='test_node', node_context=None,
118+
max_number_of_messages=None):
112119
super().__init__(node_name=name, context=node_context)
113120
self.msg_event_object = Event()
121+
self.max_number_of_messages = max_number_of_messages
114122

115123
def start_subscribers(self, topic_tuples):
116124
self.subscriber_list = []
@@ -128,14 +136,16 @@ def start_subscribers(self, topic_tuples):
128136
10
129137
)
130138
)
139+
# Initialize ring buffer of received messages
140+
self.received_messages[topic_name] = deque(maxlen=self.max_number_of_messages)
131141

132142
def callback_template(self, topic_name):
133143

134144
def topic_callback(data):
135145
if topic_name not in self.received_topics:
136146
self.get_logger().debug('Message received for ' + topic_name)
137147
self.received_topics.add(topic_name)
138-
self.received_messages.setdefault(topic_name, []).append(data)
148+
self.received_messages[topic_name].append(data)
139149
if self.received_topics == self.expected_topics:
140150
self.msg_event_object.set()
141151

launch_testing_ros/test/examples/wait_for_topic_launch_test.py

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
import os
1616
import sys
1717
import unittest
18+
import re
1819

1920
import launch
2021
import launch.actions
@@ -57,11 +58,15 @@ def test_topics_successful(self, count):
5758
"""All the supplied topics should be read successfully."""
5859
topic_list = [('chatter_' + str(i), String) for i in range(count)]
5960
expected_topics = {'chatter_' + str(i) for i in range(count)}
61+
message_pattern = re.compile('Hello World: \d+')
6062

6163
# Method 1 : Using the magic methods and 'with' keyword
62-
with WaitForTopics(topic_list, timeout=2.0) as wait_for_node_object_1:
64+
with WaitForTopics(topic_list, timeout=2.0, max_number_of_messages=10) as wait_for_node_object_1:
6365
assert wait_for_node_object_1.topics_received() == expected_topics
6466
assert wait_for_node_object_1.topics_not_received() == set()
67+
for topic_name, _ in topic_list:
68+
message = wait_for_node_object_1.messages_received(topic_name).pop().data
69+
assert message_pattern.match(message)
6570

6671
# Multiple instances of WaitForNode() can be created safely as
6772
# their internal nodes spin in separate contexts
@@ -70,6 +75,9 @@ def test_topics_successful(self, count):
7075
assert wait_for_node_object_2.wait()
7176
assert wait_for_node_object_2.topics_received() == expected_topics
7277
assert wait_for_node_object_2.topics_not_received() == set()
78+
for topic_name, _ in topic_list:
79+
message = wait_for_node_object_2.messages_received(topic_name).pop().data
80+
assert message_pattern.match(message)
7381
wait_for_node_object_2.shutdown()
7482

7583
def test_topics_unsuccessful(self, count):

0 commit comments

Comments
 (0)