From 4acb50ae538a5dad1ab7126d3a38c4f499ac059a Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Mon, 4 Oct 2021 10:15:18 -0700 Subject: [PATCH 01/11] Made a separate module, accepts a single topic Signed-off-by: Aditya Pande --- .../launch_testing_ros/__init__.py | 2 + .../launch_testing_ros/wait_for_topics.py | 48 +++++++++++++++++++ 2 files changed, 50 insertions(+) create mode 100644 launch_testing_ros/launch_testing_ros/wait_for_topics.py diff --git a/launch_testing_ros/launch_testing_ros/__init__.py b/launch_testing_ros/launch_testing_ros/__init__.py index ba190ceb..a9cad179 100644 --- a/launch_testing_ros/launch_testing_ros/__init__.py +++ b/launch_testing_ros/launch_testing_ros/__init__.py @@ -17,10 +17,12 @@ from .data_republisher import DataRepublisher from .message_pump import MessagePump from .test_runner import LaunchTestRunner +from . wait_for_topics import WaitForTopics __all__ = [ 'DataRepublisher', 'LaunchTestRunner', 'MessagePump', 'tools', + 'WaitForTopics', ] diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py new file mode 100644 index 00000000..2c89d5d0 --- /dev/null +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -0,0 +1,48 @@ +from threading import Event +from threading import Thread + +import rclpy +from rclpy.node import Node + +class WaitForTopics: + def __init__(self, topic_name, topic_type): + self.__ros_context = None + self.__ros_node = None + self.topic_name = topic_name + self.topic_type = topic_type + + self.start() + + def start(self): + self.__ros_context = rclpy.Context() + rclpy.init() + self.__ros_node = MakeTestNode(name='test_node') + + def wait(self, timeout=5.0): + self.__ros_node.start_subscriber(self.topic_name, self.topic_type) + return self.__ros_node.msg_event_object.wait(timeout) + + def shutdown(self): + rclpy.shutdown() + + +class MakeTestNode(Node): + def __init__(self, name='test_node'): + super().__init__(node_name=name) + self.msg_event_object = Event() + + def start_subscriber(self, topic_name, topic_type): + # Create a subscriber + self.subscription = self.create_subscription( + topic_type, + topic_name, + self.subscriber_callback, + 10 + ) + + # Add a spin thread + self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def subscriber_callback(self, data): + self.msg_event_object.set() From 33d4d2503b8c6e84964d32febed9ef3c7f15d9ca Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Mon, 4 Oct 2021 11:30:04 -0700 Subject: [PATCH 02/11] Support for multiple topics Signed-off-by: Aditya Pande --- .../launch_testing_ros/wait_for_topics.py | 70 +++++++++++++++---- 1 file changed, 55 insertions(+), 15 deletions(-) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index 2c89d5d0..5d62a0da 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -1,16 +1,32 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from threading import Event +from threading import Lock from threading import Thread import rclpy from rclpy.node import Node + class WaitForTopics: - def __init__(self, topic_name, topic_type): + """Wait to receive messages on supplied nodes.""" + + def __init__(self, topic_tuples): self.__ros_context = None self.__ros_node = None - self.topic_name = topic_name - self.topic_type = topic_type - + self.topic_tuples = topic_tuples self.start() def start(self): @@ -19,7 +35,7 @@ def start(self): self.__ros_node = MakeTestNode(name='test_node') def wait(self, timeout=5.0): - self.__ros_node.start_subscriber(self.topic_name, self.topic_type) + self.__ros_node.start_subscribers(self.topic_tuples) return self.__ros_node.msg_event_object.wait(timeout) def shutdown(self): @@ -27,22 +43,46 @@ def shutdown(self): class MakeTestNode(Node): + """Mock node to be used for listening on topics.""" + def __init__(self, name='test_node'): super().__init__(node_name=name) self.msg_event_object = Event() + self.logger = rclpy.logging.get_logger('wait_for_topics') - def start_subscriber(self, topic_name, topic_type): - # Create a subscriber - self.subscription = self.create_subscription( - topic_type, - topic_name, - self.subscriber_callback, - 10 - ) + def start_subscribers(self, topic_tuples): + self.subscriber_list = [] + self.expected_topics = [name for name, _ in topic_tuples] + self.expected_topics.sort() + self.received_topics = [] + self.topic_mutex = Lock() + + for topic_name, topic_type in topic_tuples: + # Create a subscriber + self.subscriber_list.append( + self.create_subscription( + topic_type, + topic_name, + self.callback_template(topic_name), + 10 + ) + ) # Add a spin thread self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) self.ros_spin_thread.start() - def subscriber_callback(self, data): - self.msg_event_object.set() + def callback_template(self, topic_name): + + def topic_callback(data): + self.topic_mutex.acquire() + if topic_name not in self.received_topics: + self.logger.info('Message received for ' + topic_name) + self.received_topics.append(topic_name) + self.received_topics.sort() + if self.received_topics == self.expected_topics: + self.msg_event_object.set() + + self.topic_mutex.release() + + return topic_callback From 178e8e78fbf5d7b8a484558153b2fa8f91436354 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Mon, 4 Oct 2021 13:34:44 -0700 Subject: [PATCH 03/11] Spin in a separate context Signed-off-by: Aditya Pande --- .../launch_testing_ros/wait_for_topics.py | 30 +++++++++++++------ 1 file changed, 21 insertions(+), 9 deletions(-) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index 5d62a0da..da2480ca 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -17,6 +17,7 @@ from threading import Thread import rclpy +from rclpy.executors import SingleThreadedExecutor from rclpy.node import Node @@ -26,27 +27,42 @@ class WaitForTopics: def __init__(self, topic_tuples): self.__ros_context = None self.__ros_node = None + self.__ros_executor = None self.topic_tuples = topic_tuples self.start() def start(self): self.__ros_context = rclpy.Context() - rclpy.init() - self.__ros_node = MakeTestNode(name='test_node') + rclpy.init(context=self.__ros_context) + self.__ros_executor = SingleThreadedExecutor(context=self.__ros_context) + self.__ros_node = MakeTestNode(name='test_node', node_context=self.__ros_context) + self.__ros_executor.add_node(self.__ros_node) + + # Start spinning + self.__running = True + self.__ros_spin_thread = Thread(target=self.spin_function) + self.__ros_spin_thread.start() + + def spin_function(self): + while self.__running: + self.__ros_executor.spin_once(1.0) def wait(self, timeout=5.0): self.__ros_node.start_subscribers(self.topic_tuples) return self.__ros_node.msg_event_object.wait(timeout) def shutdown(self): - rclpy.shutdown() + self.__running = False + self.__ros_spin_thread.join() + self.__ros_node.destroy_node() + rclpy.shutdown(context=self.__ros_context) class MakeTestNode(Node): """Mock node to be used for listening on topics.""" - def __init__(self, name='test_node'): - super().__init__(node_name=name) + def __init__(self, name='test_node', node_context=None): + super().__init__(node_name=name, context=node_context) self.msg_event_object = Event() self.logger = rclpy.logging.get_logger('wait_for_topics') @@ -68,10 +84,6 @@ def start_subscribers(self, topic_tuples): ) ) - # Add a spin thread - self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) - self.ros_spin_thread.start() - def callback_template(self, topic_name): def topic_callback(data): From 00cc79191c7b1e2cb27c6754d0fe41fd0fc3f1b3 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Mon, 4 Oct 2021 14:08:28 -0700 Subject: [PATCH 04/11] Added magic methods Signed-off-by: Aditya Pande --- .../launch_testing_ros/wait_for_topics.py | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index da2480ca..d616dc1c 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -24,11 +24,12 @@ class WaitForTopics: """Wait to receive messages on supplied nodes.""" - def __init__(self, topic_tuples): + def __init__(self, topic_tuples, timeout=5.0): self.__ros_context = None self.__ros_node = None self.__ros_executor = None self.topic_tuples = topic_tuples + self.timeout = timeout self.start() def start(self): @@ -47,9 +48,9 @@ def spin_function(self): while self.__running: self.__ros_executor.spin_once(1.0) - def wait(self, timeout=5.0): + def wait(self): self.__ros_node.start_subscribers(self.topic_tuples) - return self.__ros_node.msg_event_object.wait(timeout) + return self.__ros_node.msg_event_object.wait(self.timeout) def shutdown(self): self.__running = False @@ -57,6 +58,15 @@ def shutdown(self): self.__ros_node.destroy_node() rclpy.shutdown(context=self.__ros_context) + def __enter__(self): + self.wait() + return self + + def __exit__(self, exep_type, exep_value, trace): + if exep_type is not None: + raise Exception('Exception occured, value: ', exep_value) + self.shutdown() + class MakeTestNode(Node): """Mock node to be used for listening on topics.""" From 54e0a53565d23dd6a8c145f2a98d697284ffc521 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 5 Oct 2021 01:10:30 -0700 Subject: [PATCH 05/11] Review changes Signed-off-by: Aditya Pande --- .../launch_testing_ros/wait_for_topics.py | 53 ++++++++++++------- 1 file changed, 35 insertions(+), 18 deletions(-) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index d616dc1c..ed51dcbe 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +import random +import string from threading import Event from threading import Lock from threading import Thread @@ -22,21 +24,39 @@ class WaitForTopics: - """Wait to receive messages on supplied nodes.""" + """ + Wait to receive messages on supplied topics. + + Example usage: + -------------- + + from std_msgs.msg import String + + # Method 1, using the 'with' keyword + def method_1(): + topic_list = [('topic_1', String), ('topic_2', String)] + with WaitForTopics(topic_list, timeout=5.0): + # 'topic_1' and 'topic_2' received at least one message each + print('Given topics are receiving messages !') + + # Method 2, calling wait() and shutdown() manually + def method_2(): + topic_list = [('topic_1', String), ('topic_2', String)] + wait_for_topics = WaitForTopics(topic_list, timeout=5.0) + assert wait_for_topics.wait() + print('Given topics are receiving messages !') + wait_for_topics.shutdown() + """ def __init__(self, topic_tuples, timeout=5.0): - self.__ros_context = None - self.__ros_node = None - self.__ros_executor = None self.topic_tuples = topic_tuples self.timeout = timeout - self.start() - - def start(self): self.__ros_context = rclpy.Context() rclpy.init(context=self.__ros_context) self.__ros_executor = SingleThreadedExecutor(context=self.__ros_context) - self.__ros_node = MakeTestNode(name='test_node', node_context=self.__ros_context) + node_name = '_test_node_' +\ + ''.join(random.choices(string.ascii_uppercase + string.digits, k=10)) + self.__ros_node = _WaitForTopicsNode(name=node_name, node_context=self.__ros_context) self.__ros_executor.add_node(self.__ros_node) # Start spinning @@ -59,7 +79,7 @@ def shutdown(self): rclpy.shutdown(context=self.__ros_context) def __enter__(self): - self.wait() + assert self.wait() return self def __exit__(self, exep_type, exep_value, trace): @@ -68,19 +88,17 @@ def __exit__(self, exep_type, exep_value, trace): self.shutdown() -class MakeTestNode(Node): - """Mock node to be used for listening on topics.""" +class _WaitForTopicsNode(Node): + """Internal dummy node to be used for listening on topics.""" def __init__(self, name='test_node', node_context=None): super().__init__(node_name=name, context=node_context) self.msg_event_object = Event() - self.logger = rclpy.logging.get_logger('wait_for_topics') def start_subscribers(self, topic_tuples): self.subscriber_list = [] - self.expected_topics = [name for name, _ in topic_tuples] - self.expected_topics.sort() - self.received_topics = [] + self.expected_topics = {name for name, _ in topic_tuples} + self.received_topics = set() self.topic_mutex = Lock() for topic_name, topic_type in topic_tuples: @@ -99,9 +117,8 @@ def callback_template(self, topic_name): def topic_callback(data): self.topic_mutex.acquire() if topic_name not in self.received_topics: - self.logger.info('Message received for ' + topic_name) - self.received_topics.append(topic_name) - self.received_topics.sort() + self.get_logger().debug('Message received for ' + topic_name) + self.received_topics.add(topic_name) if self.received_topics == self.expected_topics: self.msg_event_object.set() From e721e7dd5adcb33f78b2d58585a0292c521e119f Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 5 Oct 2021 09:50:17 -0700 Subject: [PATCH 06/11] Removed mutex Signed-off-by: Aditya Pande --- launch_testing_ros/launch_testing_ros/wait_for_topics.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index ed51dcbe..58f1bba5 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -15,7 +15,6 @@ import random import string from threading import Event -from threading import Lock from threading import Thread import rclpy @@ -99,7 +98,6 @@ def start_subscribers(self, topic_tuples): self.subscriber_list = [] self.expected_topics = {name for name, _ in topic_tuples} self.received_topics = set() - self.topic_mutex = Lock() for topic_name, topic_type in topic_tuples: # Create a subscriber @@ -115,13 +113,10 @@ def start_subscribers(self, topic_tuples): def callback_template(self, topic_name): def topic_callback(data): - self.topic_mutex.acquire() if topic_name not in self.received_topics: self.get_logger().debug('Message received for ' + topic_name) self.received_topics.add(topic_name) if self.received_topics == self.expected_topics: self.msg_event_object.set() - self.topic_mutex.release() - return topic_callback From c1b5f5a941cec2072761ec2970fb5637e311734b Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 5 Oct 2021 11:22:56 -0700 Subject: [PATCH 07/11] Added RuntimeError info Signed-off-by: Aditya Pande --- .../launch_testing_ros/wait_for_topics.py | 29 ++++++++++++++----- 1 file changed, 22 insertions(+), 7 deletions(-) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index 58f1bba5..cdd71c7c 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -44,6 +44,7 @@ def method_2(): wait_for_topics = WaitForTopics(topic_list, timeout=5.0) assert wait_for_topics.wait() print('Given topics are receiving messages !') + print(wait_for_topics.topics_not_received()) # Should be an empty set wait_for_topics.shutdown() """ @@ -53,17 +54,21 @@ def __init__(self, topic_tuples, timeout=5.0): self.__ros_context = rclpy.Context() rclpy.init(context=self.__ros_context) self.__ros_executor = SingleThreadedExecutor(context=self.__ros_context) - node_name = '_test_node_' +\ - ''.join(random.choices(string.ascii_uppercase + string.digits, k=10)) - self.__ros_node = _WaitForTopicsNode(name=node_name, node_context=self.__ros_context) - self.__ros_executor.add_node(self.__ros_node) + + self._prepare_ros_node() # Start spinning self.__running = True - self.__ros_spin_thread = Thread(target=self.spin_function) + self.__ros_spin_thread = Thread(target=self._spin_function) self.__ros_spin_thread.start() - def spin_function(self): + def _prepare_ros_node(self): + node_name = '_test_node_' +\ + ''.join(random.choices(string.ascii_uppercase + string.digits, k=10)) + self.__ros_node = _WaitForTopicsNode(name=node_name, node_context=self.__ros_context) + self.__ros_executor.add_node(self.__ros_node) + + def _spin_function(self): while self.__running: self.__ros_executor.spin_once(1.0) @@ -77,8 +82,18 @@ def shutdown(self): self.__ros_node.destroy_node() rclpy.shutdown(context=self.__ros_context) + def topics_received(self): + """Topics that received at least one message.""" + return self.__ros_node.received_topics + + def topics_not_received(self): + """Topics that did not receive any messages.""" + return self.__ros_node.expected_topics - self.__ros_node.received_topics + def __enter__(self): - assert self.wait() + if not self.wait(): + raise RuntimeError('Did not receive messages on these topics: ', + self.topics_not_received()) return self def __exit__(self, exep_type, exep_value, trace): From 71454305b112832fc457160ccea4f132255ceb1c Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 5 Oct 2021 11:25:21 -0700 Subject: [PATCH 08/11] Changed docstring Signed-off-by: Aditya Pande --- launch_testing_ros/launch_testing_ros/wait_for_topics.py | 1 + 1 file changed, 1 insertion(+) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index cdd71c7c..b7e56158 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -45,6 +45,7 @@ def method_2(): assert wait_for_topics.wait() print('Given topics are receiving messages !') print(wait_for_topics.topics_not_received()) # Should be an empty set + print(wait_for_topics.topics_received()) # Should be {'topic_1', 'topic_2'} wait_for_topics.shutdown() """ From 0c1ca8e17ad0590e3fe804f0c68d758db5416778 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 5 Oct 2021 11:27:02 -0700 Subject: [PATCH 09/11] Changed docstring Signed-off-by: Aditya Pande --- launch_testing_ros/launch_testing_ros/wait_for_topics.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch_testing_ros/launch_testing_ros/wait_for_topics.py b/launch_testing_ros/launch_testing_ros/wait_for_topics.py index b7e56158..170e185d 100644 --- a/launch_testing_ros/launch_testing_ros/wait_for_topics.py +++ b/launch_testing_ros/launch_testing_ros/wait_for_topics.py @@ -104,7 +104,7 @@ def __exit__(self, exep_type, exep_value, trace): class _WaitForTopicsNode(Node): - """Internal dummy node to be used for listening on topics.""" + """Internal node used for subscribing to a set of topics.""" def __init__(self, name='test_node', node_context=None): super().__init__(node_name=name, context=node_context) From 6bdaf7bd858a8c7cf2939e047f7cf3b43a0226f1 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 5 Oct 2021 12:24:19 -0700 Subject: [PATCH 10/11] Added test case Signed-off-by: Aditya Pande --- .../examples/wait_for_topic_launch_test.py | 91 +++++++++++++++++++ 1 file changed, 91 insertions(+) create mode 100644 launch_testing_ros/test/examples/wait_for_topic_launch_test.py diff --git a/launch_testing_ros/test/examples/wait_for_topic_launch_test.py b/launch_testing_ros/test/examples/wait_for_topic_launch_test.py new file mode 100644 index 00000000..acc1027e --- /dev/null +++ b/launch_testing_ros/test/examples/wait_for_topic_launch_test.py @@ -0,0 +1,91 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import sys +import unittest + +import launch +import launch.actions +import launch_ros.actions +import launch_testing.actions +import launch_testing.markers +from launch_testing_ros import WaitForTopics +import pytest +from std_msgs.msg import String + + +def generate_node(i): + """Return node and remap the topic based on the index provided.""" + path_to_test = os.path.dirname(__file__) + return launch_ros.actions.Node( + executable=sys.executable, + arguments=[os.path.join(path_to_test, 'talker.py')], + name='demo_node_' + str(i), + additional_env={'PYTHONUNBUFFERED': '1'}, + remappings=[('chatter', 'chatter_' + str(i))] + ) + + +@pytest.mark.launch_test +@launch_testing.markers.keep_alive +def generate_test_description(): + # 'n' changes the number of nodes and topics generated for this test + n = 5 + description = [generate_node(i) for i in range(n)] + [launch_testing.actions.ReadyToTest()] + return launch.LaunchDescription(description), {'count': n} + + +class TestFixture(unittest.TestCase): + + def test_topics_successful(self, count): + """All the supplied topics should be read successfully.""" + topic_list = [('chatter_' + str(i), String) for i in range(count)] + expected_topics = {'chatter_' + str(i) for i in range(count)} + + # Method 1 : Using the magic methods and 'with' keyword + wait_for_node_object_1 = WaitForTopics(topic_list, timeout=2.0) + with wait_for_node_object_1: + assert wait_for_node_object_1.topics_received() == expected_topics + assert wait_for_node_object_1.topics_not_received() == set() + + # Multiple instances of WaitForNode() can be created safely as + # their internal nodes spin in separate contexts + # Method 2 : Manually calling wait() and shutdown() + wait_for_node_object_2 = WaitForTopics(topic_list, timeout=2.0) + assert wait_for_node_object_2.wait() + assert wait_for_node_object_2.topics_received() == expected_topics + assert wait_for_node_object_2.topics_not_received() == set() + wait_for_node_object_2.shutdown() + + def test_topics_unsuccessful(self, count): + """All topics should be read except for the 'invalid_topic'.""" + topic_list = [('chatter_' + str(i), String) for i in range(count)] + # Add a topic that will never have anything published on it + topic_list.append(('invalid_topic', String)) + expected_topics = {'chatter_' + str(i) for i in range(count)} + + # Method 1 + wait_for_node_object_1 = WaitForTopics(topic_list, timeout=2.0) + with pytest.raises(RuntimeError): + with wait_for_node_object_1: + assert wait_for_node_object_1.topics_received() == expected_topics + assert wait_for_node_object_1.topics_not_received() == {'invalid_topic'} + + # Method 2 + wait_for_node_object_2 = WaitForTopics(topic_list, timeout=2.0) + assert not wait_for_node_object_2.wait() + assert wait_for_node_object_2.topics_received() == expected_topics + assert wait_for_node_object_2.topics_not_received() == {'invalid_topic'} + wait_for_node_object_2.shutdown() From 7a848e5da6f8774c28a537f4dcaf35d3b771d7bf Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 5 Oct 2021 15:01:26 -0700 Subject: [PATCH 11/11] Review changes Signed-off-by: Aditya Pande --- .../examples/wait_for_topic_launch_test.py | 19 ++++++++----------- 1 file changed, 8 insertions(+), 11 deletions(-) diff --git a/launch_testing_ros/test/examples/wait_for_topic_launch_test.py b/launch_testing_ros/test/examples/wait_for_topic_launch_test.py index acc1027e..7e901691 100644 --- a/launch_testing_ros/test/examples/wait_for_topic_launch_test.py +++ b/launch_testing_ros/test/examples/wait_for_topic_launch_test.py @@ -55,8 +55,7 @@ def test_topics_successful(self, count): expected_topics = {'chatter_' + str(i) for i in range(count)} # Method 1 : Using the magic methods and 'with' keyword - wait_for_node_object_1 = WaitForTopics(topic_list, timeout=2.0) - with wait_for_node_object_1: + with WaitForTopics(topic_list, timeout=2.0) as wait_for_node_object_1: assert wait_for_node_object_1.topics_received() == expected_topics assert wait_for_node_object_1.topics_not_received() == set() @@ -77,15 +76,13 @@ def test_topics_unsuccessful(self, count): expected_topics = {'chatter_' + str(i) for i in range(count)} # Method 1 - wait_for_node_object_1 = WaitForTopics(topic_list, timeout=2.0) with pytest.raises(RuntimeError): - with wait_for_node_object_1: - assert wait_for_node_object_1.topics_received() == expected_topics - assert wait_for_node_object_1.topics_not_received() == {'invalid_topic'} + with WaitForTopics(topic_list, timeout=2.0): + pass # Method 2 - wait_for_node_object_2 = WaitForTopics(topic_list, timeout=2.0) - assert not wait_for_node_object_2.wait() - assert wait_for_node_object_2.topics_received() == expected_topics - assert wait_for_node_object_2.topics_not_received() == {'invalid_topic'} - wait_for_node_object_2.shutdown() + wait_for_node_object = WaitForTopics(topic_list, timeout=2.0) + assert not wait_for_node_object.wait() + assert wait_for_node_object.topics_received() == expected_topics + assert wait_for_node_object.topics_not_received() == {'invalid_topic'} + wait_for_node_object.shutdown()