Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 9 additions & 5 deletions launch_testing_ros/launch_testing_ros/wait_for_topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ def method_2():
print(wait_for_topics.messages_received('topic_1')) # Should be [message_1, ...]
wait_for_topics.shutdown()

# Method3, calling a trigger function before the wait. The trigger function takes
# Method 3, calling a trigger function before the wait. The trigger function takes
# the WaitForTopics node object as the first argument. Any additional arguments have
# to be passed to the wait(*args, **kwargs) method directly.
def trigger_function(node, arg=""):
Expand All @@ -70,12 +70,13 @@ def method_3():
"""

def __init__(self, topic_tuples, timeout=5.0, messages_received_buffer_length=10,
trigger=None, node_namespace=None) -> None:
trigger=None, node_namespace=None, qos_profile=10) -> None:
self.topic_tuples = topic_tuples
self.timeout = timeout
self.messages_received_buffer_length = messages_received_buffer_length
self.trigger = trigger
self.node_namespace = node_namespace
self.qos_profile = qos_profile
if self.trigger is not None and not callable(self.trigger):
raise TypeError('The passed trigger is not callable')
self.__ros_context = rclpy.Context()
Expand All @@ -102,7 +103,8 @@ def _prepare_ros_node(self):
name=node_name,
node_context=self.__ros_context,
messages_received_buffer_length=self.messages_received_buffer_length,
node_namespace=self.node_namespace
node_namespace=self.node_namespace,
qos_profile=self.qos_profile
)
self.__ros_executor.add_node(self.__ros_node)

Expand Down Expand Up @@ -150,7 +152,8 @@ def __init__(
self, name='test_node',
node_context=None,
messages_received_buffer_length=None,
node_namespace=None
node_namespace=None,
qos_profile=10
) -> None:
super().__init__(node_name=name, context=node_context, namespace=node_namespace)
self.msg_event_object = Event()
Expand All @@ -161,6 +164,7 @@ def __init__(
self.received_topics = set()
self.received_messages_buffer = {}
self.any_publisher_connected = Event()
self.qos_profile = qos_profile

def _sub_matched_event_callback(self, info: QoSSubscriptionMatchedInfo):
if info.current_count != 0:
Expand Down Expand Up @@ -193,7 +197,7 @@ def start_subscribers(self, topic_tuples):
topic_type,
topic_name,
self.callback_template(topic_name),
10,
self.qos_profile,
event_callbacks=sub_event_callback,
)
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import launch_testing.markers
from launch_testing_ros import WaitForTopics
import pytest
from rclpy import qos
from std_msgs.msg import String


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

def trigger_function(node):
if not hasattr(node, 'my_publisher'):
node.my_publisher = node.create_publisher(String, 'input', 10)
node.my_publisher = node.create_publisher(
String, 'input',
qos.QoSProfile(depth=10)
)
while node.my_publisher.get_subscription_count() == 0:
time.sleep(0.1)
msg = String()
Expand Down