Skip to content

Commit 9ca2014

Browse files
committed
Give the option to inject a quality of service profile
Signed-off-by: Giorgio Pintaudi <[email protected]> When testing subscribers and publishers, usually we do not want to miss any message due to race issues or other network instabilities. So we give the option to the user to specify a QoS profile best suited for the test scenario. The default is to set the durability to transient local, so that the publisher do not drop any packages in case of late joining subscribers.
1 parent ba3073b commit 9ca2014

File tree

2 files changed

+14
-6
lines changed

2 files changed

+14
-6
lines changed

launch_testing_ros/launch_testing_ros/wait_for_topics.py

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ def method_2():
5353
print(wait_for_topics.messages_received('topic_1')) # Should be [message_1, ...]
5454
wait_for_topics.shutdown()
5555
56-
# Method3, calling a trigger function before the wait. The trigger function takes
56+
# Method 3, calling a trigger function before the wait. The trigger function takes
5757
# the WaitForTopics node object as the first argument. Any additional arguments have
5858
# to be passed to the wait(*args, **kwargs) method directly.
5959
def trigger_function(node, arg=""):
@@ -70,12 +70,13 @@ def method_3():
7070
"""
7171

7272
def __init__(self, topic_tuples, timeout=5.0, messages_received_buffer_length=10,
73-
trigger=None, node_namespace=None) -> None:
73+
trigger=None, node_namespace=None, qos_profile=10) -> None:
7474
self.topic_tuples = topic_tuples
7575
self.timeout = timeout
7676
self.messages_received_buffer_length = messages_received_buffer_length
7777
self.trigger = trigger
7878
self.node_namespace = node_namespace
79+
self.qos_profile = qos_profile
7980
if self.trigger is not None and not callable(self.trigger):
8081
raise TypeError('The passed trigger is not callable')
8182
self.__ros_context = rclpy.Context()
@@ -102,7 +103,8 @@ def _prepare_ros_node(self):
102103
name=node_name,
103104
node_context=self.__ros_context,
104105
messages_received_buffer_length=self.messages_received_buffer_length,
105-
node_namespace=self.node_namespace
106+
node_namespace=self.node_namespace,
107+
qos_profile=self.qos_profile
106108
)
107109
self.__ros_executor.add_node(self.__ros_node)
108110

@@ -150,7 +152,8 @@ def __init__(
150152
self, name='test_node',
151153
node_context=None,
152154
messages_received_buffer_length=None,
153-
node_namespace=None
155+
node_namespace=None,
156+
qos_profile=10
154157
) -> None:
155158
super().__init__(node_name=name, context=node_context, namespace=node_namespace)
156159
self.msg_event_object = Event()
@@ -161,6 +164,7 @@ def __init__(
161164
self.received_topics = set()
162165
self.received_messages_buffer = {}
163166
self.any_publisher_connected = Event()
167+
self.qos_profile = qos_profile
164168

165169
def _sub_matched_event_callback(self, info: QoSSubscriptionMatchedInfo):
166170
if info.current_count != 0:
@@ -193,7 +197,7 @@ def start_subscribers(self, topic_tuples):
193197
topic_type,
194198
topic_name,
195199
self.callback_template(topic_name),
196-
10,
200+
self.qos_profile,
197201
event_callbacks=sub_event_callback,
198202
)
199203
)

launch_testing_ros/test/examples/wait_for_topic_inject_trigger_test.py

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
import launch_testing.markers
2424
from launch_testing_ros import WaitForTopics
2525
import pytest
26+
from rclpy import qos
2627
from std_msgs.msg import String
2728

2829

@@ -39,7 +40,10 @@ def generate_node():
3940

4041
def trigger_function(node):
4142
if not hasattr(node, 'my_publisher'):
42-
node.my_publisher = node.create_publisher(String, 'input', 10)
43+
node.my_publisher = node.create_publisher(
44+
String, 'input',
45+
qos.QoSProfile(depth=10)
46+
)
4347
while node.my_publisher.get_subscription_count() == 0:
4448
time.sleep(0.1)
4549
msg = String()

0 commit comments

Comments
 (0)