From e2ae4246b172d1b953bb078b0fc5f0b50f581fcf Mon Sep 17 00:00:00 2001 From: Pete Baughman Date: Tue, 12 Mar 2019 11:13:34 -0700 Subject: [PATCH] apex_launchtest_ros add better example --- .../apex_launchtest_ros/__init__.py | 2 + .../apex_launchtest_ros/data_republisher.py | 79 ++++++++ apex_launchtest_ros/example_nodes/dying_node | 33 --- apex_launchtest_ros/example_nodes/echo_node | 42 ---- apex_launchtest_ros/example_nodes/empty_node | 16 -- .../example_nodes/exception_node | 23 --- .../example_nodes/message_counter | 62 ------ .../example_nodes/terminating_node | 20 -- apex_launchtest_ros/examples/README.md | 29 ++- .../examples/dying_node.test.py | 61 ------ apex_launchtest_ros/examples/echo.test.py | 91 --------- .../examples/message_counter.launch.py | 110 ---------- .../examples/talker_listener.test.py | 189 ++++++++++++++++++ apex_launchtest_ros/package.xml | 2 + apex_launchtest_ros/test/test_examples.py | 40 ++++ 15 files changed, 338 insertions(+), 461 deletions(-) create mode 100644 apex_launchtest_ros/apex_launchtest_ros/data_republisher.py delete mode 100755 apex_launchtest_ros/example_nodes/dying_node delete mode 100755 apex_launchtest_ros/example_nodes/echo_node delete mode 100755 apex_launchtest_ros/example_nodes/empty_node delete mode 100755 apex_launchtest_ros/example_nodes/exception_node delete mode 100755 apex_launchtest_ros/example_nodes/message_counter delete mode 100755 apex_launchtest_ros/example_nodes/terminating_node delete mode 100644 apex_launchtest_ros/examples/dying_node.test.py delete mode 100644 apex_launchtest_ros/examples/echo.test.py delete mode 100644 apex_launchtest_ros/examples/message_counter.launch.py create mode 100644 apex_launchtest_ros/examples/talker_listener.test.py create mode 100644 apex_launchtest_ros/test/test_examples.py diff --git a/apex_launchtest_ros/apex_launchtest_ros/__init__.py b/apex_launchtest_ros/apex_launchtest_ros/__init__.py index e3f8af0..c98ec3a 100644 --- a/apex_launchtest_ros/apex_launchtest_ros/__init__.py +++ b/apex_launchtest_ros/apex_launchtest_ros/__init__.py @@ -13,9 +13,11 @@ # limitations under the License. +from .data_republisher import DataRepublisher from .message_pump import MessagePump __all__ = [ + 'DataRepublisher', 'MessagePump', ] diff --git a/apex_launchtest_ros/apex_launchtest_ros/data_republisher.py b/apex_launchtest_ros/apex_launchtest_ros/data_republisher.py new file mode 100644 index 0000000..02510bc --- /dev/null +++ b/apex_launchtest_ros/apex_launchtest_ros/data_republisher.py @@ -0,0 +1,79 @@ +# Copyright 2019 Apex.AI, 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. + + +class DataRepublisher: + """Republish mesasges with a transform function applied.""" + + def __init__(self, node, listen_topic, publish_topic, msg_type, transform_fn): + """ + Create a DataRepublisher. + + :param node: A rclpy node that will run the publisher and subscriber + + :param listen_topic: The topic to listen for incoming messages on + + :param publish_topic: The topic to republish messages on + + :param msg_type: The type of ROS msg to receive and republish + + :param transfor_fn: A function that takes one mesasge and returns a new message to + republish or None to drop the message + """ + self.__num_received = 0 + self.__republished_list = [] + + self.__node = node + self.__subscriber = node.create_subscription( + msg_type, + listen_topic, + callback=self.__cb + ) + + self.__publisher = node.create_publisher( + msg_type, + publish_topic + ) + + self.__transform_fn = transform_fn + + def shutdown(self): + """Stop republishing messages.""" + self.__node.destroy_subscription(self.__subscriber) + self.__node.destroy_publisher(self.__publisher) + + def get_num_received(self): + """Get the number of messages received on the listen_topic.""" + return self.__num_received + + def get_num_republished(self): + """ + Get the number of messages published on publish_topic. + + This may be lower than get_num_received if the transform_fn indicated a message + should be dropped + """ + return len(self.__republished_list) + + def get_republished(self): + """Get a list of all of the transformed messages republished.""" + return self.__republished_list + + def __cb(self, msg): + self.__num_received += 1 + repub = self.__transform_fn(msg) + + if repub: + self.__republished_list.append(msg) + self.__publisher.publish(repub) diff --git a/apex_launchtest_ros/example_nodes/dying_node b/apex_launchtest_ros/example_nodes/dying_node deleted file mode 100755 index abb4ec7..0000000 --- a/apex_launchtest_ros/example_nodes/dying_node +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 - -import sys - -import rclpy -import std_msgs.msg - -# This ROS node listens on the self_destruct topic and will die with a non-zero exit code -# once any message is received on that topic - -def kaboom(msg): - print(msg.data) - sys.exit(1) - -def main(): - rclpy.init() - node = rclpy.create_node("dying_node") - - sub = node.create_subscription( - msg_type=std_msgs.msg.String, - topic="self_destruct", - callback=kaboom - ) - - try: - rclpy.spin(node) - except KeyboardInterrupt: - pass - finally: - node.destroy_node() - -if __name__ == "__main__": - main() diff --git a/apex_launchtest_ros/example_nodes/echo_node b/apex_launchtest_ros/example_nodes/echo_node deleted file mode 100755 index b24a367..0000000 --- a/apex_launchtest_ros/example_nodes/echo_node +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -import time - -import rclpy - -import std_msgs.msg - - -def main(): - print("rclpy.init()") - rclpy.init() - - node = rclpy.create_node("echo_py") - - print("sleeping") - - time.sleep(2.0) - print("done sleeping") - - pub = node.create_publisher( - msg_type=std_msgs.msg.String, - topic="echo" - ) - - sub = node.create_subscription( - msg_type=std_msgs.msg.String, - topic="listen", - callback=lambda msg: pub.publish(msg) - ) - - print("ready") - - try: - rclpy.spin(node) - except KeyboardInterrupt: - pass - finally: - node.destroy_node() - -if __name__ == "__main__": - main() diff --git a/apex_launchtest_ros/example_nodes/empty_node b/apex_launchtest_ros/example_nodes/empty_node deleted file mode 100755 index 863a460..0000000 --- a/apex_launchtest_ros/example_nodes/empty_node +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env python3 - -import time - -# If all nodes launched by apex_launchtest die before the tests are over, apex_launchtest treats that -# like a test failure. To allow testing in this situation, apex_launchtest provides the empty_node -# which can be launched alongside the other nodes under test allowing them to terminate on their -# own without causing a test failure - -if __name__ == "__main__": - - try: - while True: - time.sleep(1 * 60 * 60 * 24) - except KeyboardInterrupt: - pass diff --git a/apex_launchtest_ros/example_nodes/exception_node b/apex_launchtest_ros/example_nodes/exception_node deleted file mode 100755 index 5ac6257..0000000 --- a/apex_launchtest_ros/example_nodes/exception_node +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env python3 - -import sys -import time - -import rclpy -import std_msgs.msg - - -def main(): - rclpy.init() - node = rclpy.create_node("exception_node") - - try: - time.sleep(0.5) - raise Exception("Node had an exception") - except KeyboardInterrupt: - pass - finally: - node.destroy_node() - -if __name__ == "__main__": - main() diff --git a/apex_launchtest_ros/example_nodes/message_counter b/apex_launchtest_ros/example_nodes/message_counter deleted file mode 100755 index d2e803f..0000000 --- a/apex_launchtest_ros/example_nodes/message_counter +++ /dev/null @@ -1,62 +0,0 @@ -#!/usr/bin/env python3 - -import rclpy - -import std_msgs.msg -import test_msgs.srv - - -# This is a simple ROS node for demonstrating apex_launchtest. It subscribes to a ROS topic and -# listens for strings which will be printed to stdout. It also keeps a running count of the -# number of strings which can be read via a ROS service -# ROS Topics: -# /msg - type: std_msgs/String -# ROS Services: -# /get_message_count - type: test_msgs/Primitives. The 'request' part of this service is not -# used. The 'response' part of the primitive will put the current message count in the -# int32_value field - - -class MsgCounter(object): - - def __init__(self): - self._count = 0 - - def sub(self, msg): - self._count += 1 - print (msg.data) - print ("Count is {}".format(self._count)) - - def srv_cb(self, req, resp): - resp.int32_value = self._count - return resp - - -def main(): - rclpy.init() - - node = rclpy.create_node("msg_counter_py") - - counter = MsgCounter() - - sub = node.create_subscription( - msg_type=std_msgs.msg.String, - topic="msgs", - callback=counter.sub - ) - - srv = node.create_service( - srv_type=test_msgs.srv.Primitives, - srv_name="get_message_count", - callback=counter.srv_cb - ) - - try: - rclpy.spin(node) - except KeyboardInterrupt: - pass - finally: - node.destroy_node() - -if __name__ == "__main__": - main() diff --git a/apex_launchtest_ros/example_nodes/terminating_node b/apex_launchtest_ros/example_nodes/terminating_node deleted file mode 100755 index 67f31a5..0000000 --- a/apex_launchtest_ros/example_nodes/terminating_node +++ /dev/null @@ -1,20 +0,0 @@ -#!/usr/bin/env python3 - -import sys -import time - -if __name__ == "__main__": - - print("Emulating Setup") - time.sleep(1.0) - print("Ready") - - if sys.argv[1:]: - print("Called with arguments {}".format(sys.argv[1:])) - - try: - print("Emulating Work") - time.sleep(1.0) - print("Done") - except KeyboardInterrupt: - pass diff --git a/apex_launchtest_ros/examples/README.md b/apex_launchtest_ros/examples/README.md index 7457460..711efe7 100644 --- a/apex_launchtest_ros/examples/README.md +++ b/apex_launchtest_ros/examples/README.md @@ -1,8 +1,31 @@ # Examples -## message_counter.launch.py +## `talker_listener.test.py` Usage: -> apex_launchtest examples/message_counter.launch.py +> apex_launchtest examples/talker_listener.test.py -Launches a message counter node and runs a few tests to interact with the node +This test launchtes the talker and listener example nodes from demo_nodes_py and interacts +with them via their ROS interfaces. Remaps are used so that one of the tests can sit in +between the talker and the listener and change the data on the fly. + +Node that in the setUpClass method, the test makes sure that the listener is subscribed and +republishing messages. Since the listener process provides no synchronization mechanism to +inform the outside world that it's up and running, this step is necessary especially in resource +constrained environments where process startup may take a non negligable amount of time. This +is often the cause of "flakyness" in tests on CI systems. A more robust design of the talker and +listener processes might provide some positive feedback that the node is up and running, but these +are simple example nodes. + +#### test_fuzzy_data +This test gives an example of what a test that fuzzes data might look like. A ROS subscriber +and publisher pair encapsulated in a `DataRepublisher` object changes the string "Hello World" to +"Aloha World" as it travles between the talker and the listener + +#### test_listener_receives +This test publishes unique messages on the /chatter topic and asserts that the same messages +go to the stdout of the listener node + +#### test_talker_transmits +This test subscribes to the remapped /talker_chatter topic and makes sure the talker node also +writes the data it's transmitting to stdout diff --git a/apex_launchtest_ros/examples/dying_node.test.py b/apex_launchtest_ros/examples/dying_node.test.py deleted file mode 100644 index 6b1ec6f..0000000 --- a/apex_launchtest_ros/examples/dying_node.test.py +++ /dev/null @@ -1,61 +0,0 @@ -# Copyright 2018 Apex.AI, 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 time -import unittest - -from launch import LaunchDescription -from launch_ros.actions import Node - -import std_msgs.msg - - -def generate_test_description(ready_fn): - # This is wrong - but here for test purposes. We shouldn't signal ready until the node starts - # Once we have some utilities built to enable waiting on nodes, this ready_fn should be - # triggered as part of the LaunchDecription - ready_fn() - - return LaunchDescription([ - Node(package='apex_launchtest', node_executable='dying_node', output='screen') - ]) - - -class ExampleTest(unittest.TestCase): - - def test_a1(self): - time.sleep(1.0) - - def test_that_kills_node(self): - - test_pub = self.node.create_publisher( - msg_type=std_msgs.msg.String, - topic="self_destruct" - ) - - time.sleep(1.0) - msg = std_msgs.msg.String() - msg.data = "kill the node under test" - test_pub.publish(msg) - - time.sleep(1.0) - - def test_z1(self): - time.sleep(1.0) - - def test_z2(self): - time.sleep(1.0) - - def test_z3(self): - time.sleep(1.0) diff --git a/apex_launchtest_ros/examples/echo.test.py b/apex_launchtest_ros/examples/echo.test.py deleted file mode 100644 index 37a5c50..0000000 --- a/apex_launchtest_ros/examples/echo.test.py +++ /dev/null @@ -1,91 +0,0 @@ -# Copyright 2018 Apex.AI, 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 threading -import unittest -import uuid - -from launch import LaunchDescription -from launch.actions import RegisterEventHandler -from launch.actions import OpaqueFunction -from launch_ros.actions import Node -import rclpy - -import std_msgs.msg - -from apex_launchtest.event_handlers import StdoutReadyListener - - -def generate_test_description(ready_fn): - node_env = os.environ.copy() - node_env["PYTHONUNBUFFERED"] = "1" - - return LaunchDescription([ - Node(package='apex_launchtest', node_executable='echo_node', env=node_env), - RegisterEventHandler( - StdoutReadyListener( - "echo_node", - "ready", - actions=[OpaqueFunction(function=lambda context: ready_fn())] - ) - ) - ]) - - -class MessageListener: - - def __init__(self): - self.msg = None - self.event = threading.Event() - - def callback(self, msg): - print("got msg {}".format(msg.data)) - self.msg = msg - self.event.set() - - -class TestEcho(unittest.TestCase): - - def test_node_echo(self): - - msg_listener = MessageListener() - - # Publish to the 'echo' node on the 'listen' topic and look for a response on the - # echo topic - pub = self.node.create_publisher( - msg_type=std_msgs.msg.String, - topic="listen" - ) - - self.node.create_subscription( - msg_type=std_msgs.msg.String, - topic="echo", - callback=msg_listener.callback - ) - - msg = std_msgs.msg.String() - msg.data = str(uuid.uuid4()) - - pub.publish(msg) - - for _ in range(5): - rclpy.spin_once(self.node, timeout_sec=1.0) - if msg_listener.event.is_set(): - break - - self.assertTrue(msg_listener.event.wait(0), - "Timed out waiting for echo") - - self.assertEqual(msg.data, msg_listener.msg.data) diff --git a/apex_launchtest_ros/examples/message_counter.launch.py b/apex_launchtest_ros/examples/message_counter.launch.py deleted file mode 100644 index 9c05725..0000000 --- a/apex_launchtest_ros/examples/message_counter.launch.py +++ /dev/null @@ -1,110 +0,0 @@ -# Copyright 2018 Apex.AI, 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 unittest -import uuid - -from launch import LaunchDescription -from launch_ros.actions import Node -import rclpy - -from apex_launchtest import post_shutdown_test - -import std_msgs.msg -import test_msgs.srv - - -test_uuid = str(uuid.uuid4()) - - -def generate_test_description(ready_fn): - # This is wrong - but here for test purposes. We shouldn't signal ready until the node starts - # Once we have some utilities built to enable waiting on nodes, this ready_fn should be - # triggered as part of the LaunchDecription - ready_fn() - - return LaunchDescription([ - Node(package='apex_launchtest', node_executable='message_counter', output='screen') - ]) - - -class ExampleTest(unittest.TestCase): - - def test_that_will_pass(self): - self.assertIsNotNone(object()) - - def test_that_talks_to_node(self): - # This test will read the message counter's msg count, attempt to increment it, and then - # verify that the count goes up - - msg_count_client = self.node.create_client( - srv_type=test_msgs.srv.Primitives, - srv_name="/get_message_count", - ) - - test_pub = self.node.create_publisher( - msg_type=std_msgs.msg.String, - topic="msgs" - ) - - # See how many messages the message counter node has seen so far: - self.assertTrue( - msg_count_client.wait_for_service(timeout_sec=5.0), - "Timed out waiting for service" - ) - - def get_msg_count(): - future = msg_count_client.call_async(test_msgs.srv.Primitives.Request()) - rclpy.spin_until_future_complete(self.node, future) - return future.result().int32_value - - initial_msg_count = get_msg_count() - - msg = std_msgs.msg.String() - msg.data = test_uuid - test_pub.publish(msg) - - import time - time.sleep(1.0) # message_counter lacks synchronizatoin - - final_msg_count = get_msg_count() - self.assertEquals(final_msg_count, initial_msg_count + 1) - - -@post_shutdown_test() -class PostShutdownTests(unittest.TestCase): - - def test_good_exit_code(self): - for info in self.proc_info: - self.assertEquals( - info.returncode, - 0, - "Non-zero exit code for process {}".format(info.process_name) - ) - - def test_node_stdout(self): - # Check that we see "Count is 1" somewhere in stdout - self.assertTrue( - any( - map(lambda x: b"Count is 1" in x.text, self.proc_output), - ) - ) - - def test_msg_output(self): - # Check that the UUID we sent to the node appears in stdout - self.assertTrue( - any( - map(lambda x: test_uuid.encode('ascii') in x.text, self.proc_output), - ) - ) diff --git a/apex_launchtest_ros/examples/talker_listener.test.py b/apex_launchtest_ros/examples/talker_listener.test.py new file mode 100644 index 0000000..f856faa --- /dev/null +++ b/apex_launchtest_ros/examples/talker_listener.test.py @@ -0,0 +1,189 @@ +# Copyright 2019 Apex.AI, 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 time +import unittest +import uuid + +import launch +import launch_ros +import launch_ros.actions +import rclpy +import rclpy.context +import rclpy.executors +import std_msgs.msg + +import apex_launchtest_ros +from apex_launchtest.util import NoMatchingProcessException + + +def generate_test_description(ready_fn): + # Necessary to get real-time stdout from python processes: + proc_env = os.environ.copy() + proc_env["PYTHONUNBUFFERED"] = "1" + + # Normally, talker publishes on the 'chatter' topic and listener listens on the + # 'chatter' topic, but we want to show how to use remappings to munge the data so we + # will remap these topics when we launch the nodes and insert our own node that can + # change the data as it passes through + talker_node = launch_ros.actions.Node( + package="demo_nodes_py", + node_executable="talker", + env=proc_env, + remappings=[("chatter", "talker_chatter")], + ) + + listener_node = launch_ros.actions.Node( + package="demo_nodes_py", + node_executable="listener", + env=proc_env, + ) + + return ( + launch.LaunchDescription([ + talker_node, + listener_node, + # Start tests right away - no need to wait for anything + launch.actions.OpaqueFunction(function=lambda context: ready_fn()), + ]), + { + "talker": talker_node, + "listener": listener_node, + } + ) + + +class TestTalkerListenerLink(unittest.TestCase): + + @classmethod + def setUpClass(cls, proc_output, listener): + cls.context = rclpy.context.Context() + rclpy.init(context=cls.context) + cls.node = rclpy.create_node("test_node", context=cls.context) + + # The demo node listener has no synchronization to indicate when it's ready to start + # receiving messages on the /chatter topic. This plumb_listener method will attempt + # to publish for a few seconds until it sees output + publisher = cls.node.create_publisher( + std_msgs.msg.String, + "chatter" + ) + msg = std_msgs.msg.String() + msg.data = "test message {}".format(uuid.uuid4()) + for _ in range(5): + try: + publisher.publish(msg) + proc_output.assertWaitFor( + msg=msg.data, + process=listener, + timeout=1.0 + ) + except AssertionError: + continue + except NoMatchingProcessException: + continue + else: + return + else: + assert False, "Failed to plumb chatter topic to listener process" + + @classmethod + def tearDownClass(cls): + cls.node.destroy_node() + + def spin_rclpy(self, timeout_sec): + executor = rclpy.executors.SingleThreadedExecutor(context=self.context) + executor.add_node(self.node) + try: + executor.spin_once(timeout_sec=timeout_sec) + finally: + executor.remove_node(self.node) + + def test_talker_transmits(self, talker): + # Expect the talker to publish strings on '/talker_chatter' and also write to stdout + msgs_rx = [] + sub = self.node.create_subscription( + std_msgs.msg.String, + "talker_chatter", + callback=lambda msg: msgs_rx.append(msg) + ) + self.addCleanup(self.node.destroy_subscription, sub) + + # Wait until the talker transmits two messages over the ROS topic + end_time = time.time() + 10 + while time.time() < end_time: + self.spin_rclpy(1.0) + if len(msgs_rx) > 2: + break + + self.assertGreater(len(msgs_rx), 2) + + # Make sure the talker also output the same data via stdout + for txt in [msg.data for msg in msgs_rx]: + self.proc_output.assertWaitFor( + msg=txt, + process=talker + ) + + def test_listener_receives(self, listener): + pub = self.node.create_publisher( + std_msgs.msg.String, + "chatter" + ) + self.addCleanup(self.node.destroy_publisher, pub) + + # Publish some unique messages on /chatter and verify that the listener gets them + # and prints them + for _ in range(5): + msg = std_msgs.msg.String() + msg.data = str(uuid.uuid4()) + + pub.publish(msg) + self.proc_output.assertWaitFor( + msg=msg.data, + process=listener + ) + + def test_fuzzy_data(self, listener): + # This test shows how to insert a node in between the talker and the listener to + # change the data. Here we're going to change "Hello World" to "Aloha World" + def data_mangler(msg): + msg.data = msg.data.replace("Hello", "Aloha") + return msg + + republisher = apex_launchtest_ros.DataRepublisher( + self.node, + "talker_chatter", + "chatter", + std_msgs.msg.String, + data_mangler + ) + self.addCleanup(republisher.shutdown) + + # Spin for a few seconds until we've republished some mangled messages + end_time = time.time() + 10 + while time.time() < end_time: + self.spin_rclpy(1.0) + if republisher.get_num_republished() > 2: + break + + self.assertGreater(republisher.get_num_republished(), 2) + + # Sanity check that we're changing 'Hello World' + self.proc_output.assertWaitFor("Aloha World") + + # Check for the actual messages we sent + for msg in republisher.get_republished(): + self.proc_output.assertWaitFor(msg.data, listener) diff --git a/apex_launchtest_ros/package.xml b/apex_launchtest_ros/package.xml index 5c0e37d..75d43bb 100644 --- a/apex_launchtest_ros/package.xml +++ b/apex_launchtest_ros/package.xml @@ -15,6 +15,8 @@ ament_flake8 ament_pep257 python3-pytest + demo_nodes_py + std_msgs ament_python diff --git a/apex_launchtest_ros/test/test_examples.py b/apex_launchtest_ros/test/test_examples.py new file mode 100644 index 0000000..f00a37c --- /dev/null +++ b/apex_launchtest_ros/test/test_examples.py @@ -0,0 +1,40 @@ +# Copyright 2019 Apex.AI, 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 glob +import os +import subprocess + +import pytest + +import ament_index_python + + +testdata = glob.glob( + os.path.join( + ament_index_python.get_package_share_directory('apex_launchtest_ros'), + 'examples', + '*.test.py' + ) +) + + +# This test will automatically run for any *.test.py file in the examples folder and expect +# it to pass +@pytest.mark.parametrize("example_path", testdata, ids=[os.path.basename(d) for d in testdata]) +def test_examples(example_path): + + proc = ['apex_launchtest', example_path] + + assert 0 == subprocess.run(args=proc).returncode