diff --git a/apex_rostest/.gitignore b/apex_rostest/.gitignore deleted file mode 100644 index 527df80a..00000000 --- a/apex_rostest/.gitignore +++ /dev/null @@ -1,12 +0,0 @@ -*.swp - -.eggs/ -*.egg-info -*.pyc -*.pytest_cache -*.coverage -htmlcov/ - -build/ -install/ -log/ diff --git a/apex_rostest/README.md b/apex_rostest/README.md deleted file mode 100644 index 93d2356e..00000000 --- a/apex_rostest/README.md +++ /dev/null @@ -1,129 +0,0 @@ -# apex_launchtest -![build status](https://gitlab.com/ApexAI/apex_rostest/badges/master/build.svg) ![coverage](https://gitlab.com/ApexAI/apex_rostest/badges/master/coverage.svg) - -This tool is a framework for ROS2 integration testing using the [ros2 style launch description](https://github.com/ros2/launch/blob/master/ros2launch/examples/example.launch.py). -It works similarly to rostest, but makes it easier to inspect the processes under test. For example - - * The exit codes of all processes are available to the tests. Tests can check that all processes shut down normally, or with specific exit codes. Tests can fail when a process dies unexpectedly - * The stdout and stderr of all processes are available to the tests. - * The command-line used to launch the processes are avilalbe to the tests. - * Some tests run concurrently with the launch and can interact with the running processes. - -## Compatibility -Designed to work with [ros2 crystal](https://index.ros.org/doc/ros2/Installation/) - -## Quick start example -Start with the apex_launchtest example [good_proc.test.py](apex_launchtest/examples/good_proc.test.py). Run the example by doing ->apex_launchtest apex_launchtest/examples/good_proc.test.py - -apex_launchtest will launch the nodes found in the `generate_test_description` function, run the tests from the `TestGoodProcess` class, shut down the launched nodes, and then run the tests from the `TestNodeOutput` class. - -#### The Launch Description -```python -def generate_test_description(ready_fn): - - return launch.LaunchDescription([ - launch.actions.ExecuteProcess( - cmd=[path_to_process], - ), - - # Start tests right away - no need to wait for anything in this example - launch.actions.OpaqueFunction(function=lambda context: ready_fn()), - ]) -``` - -The `generate_test_description` function should return a launch.LaunchDescription object that launches the system to be tested. -It should also call the `ready_fn` that is passed in to signal when the tests should start. In the good_proc.test.py example, there -is no need to delay the start of the tests so the `ready_fn` is called concurrently when the launching of the process under test - -#### Active Tests -Any classes that inherit from unittest.TestCase and not decorated with the post_shutdown_test descriptor will be run concurrently -with the proccess under test. These tests are expected to interact with the running processes in some way - -#### Post-Shutdown Tests -Any classes that inherit from unittest.TestCase that are decorated with the post_shutdown_test descriptor will be run after the launched -processes have been shut down. These tests have access to the exit codes and the stdout of all of the launched processes, as well -as any data created as a side-effect of running the processes - -#### Exit Codes and Standard Out -the apex_launchtest framework automatically adds some member fields to each test case so that the tests can access process output and exit codes - - * self.proc_info - a [ProcInfoHandler object](apex_launchtest/apex_launchtest/proc_info_handler.py) - * self.proc_output - an [IoHandler object](apex_launchtest/apex_launchtest/io_handler.py) - -These objects provide dictionary like access to information about the running processes. They also contain methods that the active tests can -use to wait for a process to exit or to wait for specific output - -## Assertions -The apex_launchtest framework automatically records all stdout from the launched processes as well as the exit codes from any processes -that are launched. This information is made available to the tests via the `proc_info` and `proc_output` object. These objects can be used -by one of several assert methods to check the output or exit codes of the process: - -`apex_launchtest.asserts.assertInStdout(proc_output, msg, proc, cmd_args=None, *, strict_proc_matching=True)` - -Asserts that a message 'msg' is found in the stdout of a particular process. - - msg: The text to look for in the process standard out - - proc: Either the process name as a string, or a launch.actions.ExecuteProcess object that was used to start the process. Pass None or - an empty string to search all processes - - cmd_args: When looking up processes by process by name, cmd_args can be used to disambiguate multiple processes with the same name - - strict_proc_matching: When looking up a process by name, strict_proc_matching=True will make it an error to match multiple processes. - This prevents an assert from accidentally passing if the output came from a different process than the one the user was expecting - -`apex_launchtest.asserts.assertExitCodes(proc_info, allowable_exit_codes=[EXIT_OK], proc, cmd_args=None, *, strict_proc_matching=True)` - -Asserts that the specified processes exited with a particular exit code - - allowable_exit_codes: A list of allowable exit codes. By default EXIT_OK (0). Other exit codes provided are EXIT_SIGINT (130), EXIT_SIGQUIT (131), EXIT_SIGKILL (137) and EXIT_SIGSEGV (139) - - The proc, cmd_args, and strict_proc_matching arguments behave the same way as assertInStdout. By default, assert on the exit codes of all processes - -`apex_launchtest.asserts.assertSequentialStdout(proc_output, proc, cmd_args=None)` - -Asserts that standard out was seen in a particular order - - Returns a context manager that will check that a series of assertions happen in order - - The proc and cmd_args are the same as assertInStdout and assertExitCodes, however it is not possible to match multiple processes because there is no way to determine - the order of stdout that came from multiple processes. -Example: -```python -with assertSequentialStdout(self.proc_output, "proc_name") as cm: - cm.assertInStdout("Loop 1") - cm.assertInStdout("Loop 2") - cm.assertInStdout("Loop 3") -``` - -#### Waiting for Output or Exit Codes -The ActiveTests can also call methods that wait for particular output or a particular process to exit or time out. These asserts are methods on the `proc_output` and `proc_info` objects - -`proc_output.assertWaitFor(msg, proc=None, cmd_args=None, *, strict_proc_matching=True, timeout=10)` - - The msg, proc, cmd_args, and strict_proc_matching arguments work the same as the other assert methods. By default, this method waits on output from any process - - timeout: The amount of time to wait before raising an AssertionError - -`proc_info.assertWaitForShutdown(proc, cmd_args=None, *, timeout=10)` - - The proc and cmd_args work the same as the other assertions, but it is not possible to wait on multiple processes to shut down - - timeout: The amount of time to wait before raising an AssertionError - -## Arguments -apex_launchtest uses the same [syntax as ros2 launch](https://github.com/ros2/launch/pull/123) to pass arguments to tests. - -Arguments are declared in the launch description and can be accessed by the test vi a test_args dictionary that's injected into the tests similar to `proc_info` and `proc_output`. - -See the [apex_launchtest example with arguments](apex_launchtest/examples/args.test.py) -``` ->apex_launhtest --show-args examples/args.test.py ->apex_launchtest examples/args.test.py dut_arg:=value -``` - -## Using CMake -To run apex_launchtest from a CMakeLists file, you'll need to declare a dependency on -apex_launchtest_cmake in your package.xml. Then, in the CMakeLists file, add - -``` -find_package(apex_launchtest_cmake) -add_apex_launchtest(test/name_of_test.test.py) -``` - -Arguments can be passed to the tests via the CMake function, too: -``` -add_apex_launchtest( - test/test_with_args.test.py - ARGS "arg1:=foo" -) -``` diff --git a/apex_rostest/apex_launchtest_ros/example_nodes/dying_node b/apex_rostest/apex_launchtest_ros/example_nodes/dying_node deleted file mode 100755 index abb4ec73..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/example_nodes/echo_node b/apex_rostest/apex_launchtest_ros/example_nodes/echo_node deleted file mode 100755 index b24a367c..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/example_nodes/empty_node b/apex_rostest/apex_launchtest_ros/example_nodes/empty_node deleted file mode 100755 index 863a460f..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/example_nodes/exception_node b/apex_rostest/apex_launchtest_ros/example_nodes/exception_node deleted file mode 100755 index 5ac62577..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/example_nodes/message_counter b/apex_rostest/apex_launchtest_ros/example_nodes/message_counter deleted file mode 100755 index d2e803f0..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/example_nodes/terminating_node b/apex_rostest/apex_launchtest_ros/example_nodes/terminating_node deleted file mode 100755 index 67f31a5e..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/examples/dying_node.test.py b/apex_rostest/apex_launchtest_ros/examples/dying_node.test.py deleted file mode 100644 index 6b1ec6f4..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/examples/echo.test.py b/apex_rostest/apex_launchtest_ros/examples/echo.test.py deleted file mode 100644 index 37a5c500..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/examples/message_counter.launch.py b/apex_rostest/apex_launchtest_ros/examples/message_counter.launch.py deleted file mode 100644 index 9c05725d..00000000 --- a/apex_rostest/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_rostest/apex_launchtest_ros/resource/apex_launchtest_ros b/apex_rostest/apex_launchtest_ros/resource/apex_launchtest_ros deleted file mode 100644 index e69de29b..00000000 diff --git a/apex_rostest/apex_launchtest_ros/setup.py b/apex_rostest/apex_launchtest_ros/setup.py deleted file mode 100644 index 0db4cf46..00000000 --- a/apex_rostest/apex_launchtest_ros/setup.py +++ /dev/null @@ -1,27 +0,0 @@ -#!/usr/bin/env python - -import glob - -from setuptools import setup - -package_name = 'apex_launchtest_ros' - -setup( - name=package_name, - version='0.1', - description='Apex integration test runner and utilities', - - author='Pete Baughman', - author_email='pete.baughman@apex.ai', - - data_files=[ - ('share/ament_index/resource_index/packages', ['resource/apex_launchtest_ros']), - ('lib/' + package_name, glob.glob('example_nodes/**')), - ('share/' + package_name + '/examples', glob.glob('examples/[!_]**')), - ], - packages=[ - 'apex_launchtest_ros', - ], - tests_require=['pytest'], - zip_safe=True, -) diff --git a/apex_rostest/apex_launchtest_ros/examples/README.md b/launch_testing_ros/examples/README.md similarity index 96% rename from apex_rostest/apex_launchtest_ros/examples/README.md rename to launch_testing_ros/examples/README.md index b279bd33..ed7b5524 100644 --- a/apex_rostest/apex_launchtest_ros/examples/README.md +++ b/launch_testing_ros/examples/README.md @@ -3,7 +3,7 @@ ## `talker_listener.test.py` Usage: -> apex_launchtest examples/talker_listener.test.py +> launch_test examples/talker_listener.test.py This test launches the talker and listener example nodes from demo_nodes_py and interacts with them via their ROS interfaces. Remapping rules are used so that one of the tests can sit in diff --git a/apex_rostest/apex_launchtest_ros/examples/talker_listener.test.py b/launch_testing_ros/examples/talker_listener.test.py similarity index 95% rename from apex_rostest/apex_launchtest_ros/examples/talker_listener.test.py rename to launch_testing_ros/examples/talker_listener.test.py index 6424a1d9..9933e78a 100644 --- a/apex_rostest/apex_launchtest_ros/examples/talker_listener.test.py +++ b/launch_testing_ros/examples/talker_listener.test.py @@ -17,11 +17,11 @@ import unittest import uuid -from apex_launchtest.util import NoMatchingProcessException -import apex_launchtest_ros import launch import launch_ros import launch_ros.actions +import launch_testing.util +import launch_testing_ros import rclpy import rclpy.context import rclpy.executors @@ -85,13 +85,13 @@ def setUpClass(cls, proc_output, listener): try: publisher.publish(msg) proc_output.assertWaitFor( - msg=msg.data, + expected_output=msg.data, process=listener, timeout=1.0 ) except AssertionError: continue - except NoMatchingProcessException: + except launch_testing.util.NoMatchingProcessException: continue else: return @@ -132,7 +132,7 @@ def test_talker_transmits(self, talker): # 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, + expected_output=txt, process=talker ) @@ -151,7 +151,7 @@ def test_listener_receives(self, listener): pub.publish(msg) self.proc_output.assertWaitFor( - msg=msg.data, + expected_output=msg.data, process=listener ) @@ -162,7 +162,7 @@ def data_mangler(msg): msg.data = msg.data.replace('Hello', 'Aloha') return msg - republisher = apex_launchtest_ros.DataRepublisher( + republisher = launch_testing_ros.DataRepublisher( self.node, 'talker_chatter', 'chatter', diff --git a/apex_rostest/apex_launchtest_ros/apex_launchtest_ros/__init__.py b/launch_testing_ros/launch_testing_ros/__init__.py similarity index 95% rename from apex_rostest/apex_launchtest_ros/apex_launchtest_ros/__init__.py rename to launch_testing_ros/launch_testing_ros/__init__.py index c98ec3af..96e63dff 100644 --- a/apex_rostest/apex_launchtest_ros/apex_launchtest_ros/__init__.py +++ b/launch_testing_ros/launch_testing_ros/__init__.py @@ -13,6 +13,7 @@ # limitations under the License. +from . import tools from .data_republisher import DataRepublisher from .message_pump import MessagePump @@ -20,4 +21,5 @@ __all__ = [ 'DataRepublisher', 'MessagePump', + 'tools', ] diff --git a/apex_rostest/apex_launchtest_ros/apex_launchtest_ros/data_republisher.py b/launch_testing_ros/launch_testing_ros/data_republisher.py similarity index 100% rename from apex_rostest/apex_launchtest_ros/apex_launchtest_ros/data_republisher.py rename to launch_testing_ros/launch_testing_ros/data_republisher.py diff --git a/apex_rostest/apex_launchtest_ros/apex_launchtest_ros/message_pump.py b/launch_testing_ros/launch_testing_ros/message_pump.py similarity index 100% rename from apex_rostest/apex_launchtest_ros/apex_launchtest_ros/message_pump.py rename to launch_testing_ros/launch_testing_ros/message_pump.py diff --git a/launch_testing_ros/launch_testing_ros/tools/__init__.py b/launch_testing_ros/launch_testing_ros/tools/__init__.py new file mode 100644 index 00000000..4f3abdef --- /dev/null +++ b/launch_testing_ros/launch_testing_ros/tools/__init__.py @@ -0,0 +1,19 @@ +# Copyright 2019 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 .output import basic_output_filter + +__all__ = [ + 'basic_output_filter' +] diff --git a/launch_testing_ros/launch_testing_ros/tools/output.py b/launch_testing_ros/launch_testing_ros/tools/output.py new file mode 100644 index 00000000..87770a5d --- /dev/null +++ b/launch_testing_ros/launch_testing_ros/tools/output.py @@ -0,0 +1,65 @@ +# Copyright 2019 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 ament_index_python + + +def get_rmw_output_filter(rmw_implementation, filter_type): + supported_filter_types = ['prefixes', 'patterns'] + if filter_type not in supported_filter_types: + raise TypeError( + 'Unsupported filter_type "{0}". Supported types: {1}' + .format(filter_type, supported_filter_types)) + resource_name = 'rmw_output_' + filter_type + prefix_with_resource = ament_index_python.has_resource( + resource_name, rmw_implementation) + if not prefix_with_resource: + return [] + + # Treat each line of the resource as an independent filter. + rmw_output_filter, _ = ament_index_python.get_resource(resource_name, rmw_implementation) + return [l for l in rmw_output_filter.splitlines()] + + +def basic_output_filter( + filtered_prefixes=None, + filtered_patterns=None, + filtered_rmw_implementation=None +): + """ + Create a line filtering function to help output testing. + + :param filtered_prefixes: A list of byte strings representing prefixes that will cause + output lines to be ignored if they start with one of the prefixes. By default lines + starting with the process ID (`b'pid'`) and return code (`b'rc'`) will be ignored. + :param filtered_patterns: A list of byte strings representing regexes that will cause + output lines to be ignored if they match one of the regexes. + :param filtered_rmw_implementation: RMW implementation for which the output will be + ignored in addition to the `filtered_prefixes`/`filtered_patterns`. + """ + from launch_testing.tools.output import basic_output_filter as base_output_filter + from launch_testing.tools.output import get_default_filtered_prefixes + from launch_testing.tools.output import get_default_filtered_patterns + if filtered_prefixes is None: + filtered_prefixes = get_default_filtered_prefixes() + if filtered_patterns is None: + filtered_patterns = get_default_filtered_patterns() + if filtered_rmw_implementation: + filtered_prefixes = filtered_prefixes + get_rmw_output_filter( + filtered_rmw_implementation, 'prefixes' + ) + filtered_patterns = filtered_patterns + get_rmw_output_filter( + filtered_rmw_implementation, 'patterns' + ) + return base_output_filter(filtered_prefixes, filtered_patterns) diff --git a/apex_rostest/apex_launchtest_ros/package.xml b/launch_testing_ros/package.xml similarity index 86% rename from apex_rostest/apex_launchtest_ros/package.xml rename to launch_testing_ros/package.xml index 75d43bb7..1d77bd8a 100644 --- a/apex_rostest/apex_launchtest_ros/package.xml +++ b/launch_testing_ros/package.xml @@ -1,13 +1,13 @@ - apex_launchtest_ros + launch_testing_ros 0.1.0 - A package providing utilities for writing ROS2 enabled apex_launchtests. + A package providing utilities for writing ROS2 enabled launch tests. Pete Baughman Apache License 2.0 - apex_launchtest + launch_testing launch_ros rclpy @@ -21,5 +21,4 @@ ament_python - diff --git a/apex_rostest/apex_launchtest_ros/pytest.ini b/launch_testing_ros/pytest.ini similarity index 100% rename from apex_rostest/apex_launchtest_ros/pytest.ini rename to launch_testing_ros/pytest.ini diff --git a/apex_rostest/AMENT_IGNORE b/launch_testing_ros/resource/launch_testing_ros similarity index 100% rename from apex_rostest/AMENT_IGNORE rename to launch_testing_ros/resource/launch_testing_ros diff --git a/apex_rostest/apex_launchtest_ros/setup.cfg b/launch_testing_ros/setup.cfg similarity index 100% rename from apex_rostest/apex_launchtest_ros/setup.cfg rename to launch_testing_ros/setup.cfg diff --git a/launch_testing_ros/setup.py b/launch_testing_ros/setup.py new file mode 100644 index 00000000..d92e4e41 --- /dev/null +++ b/launch_testing_ros/setup.py @@ -0,0 +1,34 @@ +import glob + +from setuptools import find_packages +from setuptools import setup + +setup( + name='launch_testing_ros', + version='0.1', + packages=find_packages(exclude=['test']), + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/launch_testing_ros']), + ('lib/launch_testing_ros', glob.glob('example_nodes/**')), + ('share/launch_testing_ros/examples', glob.glob('examples/[!_]**')), + ], + install_requires=['setuptools'], + zip_safe=True, + author='Pete Baughman', + author_email='pete.baughman@apex.ai', + maintainer='Pete Baughman', + maintainer_email='pete.baughman@apex.ai', + url='https://github.com/ros2/launch_ros', + download_url='https://github.com/ros2/launch_ros/releases', + keywords=['ROS'], + classifiers=[ + 'Intended Audience :: Developers', + 'License :: OSI Approved :: Apache Software License', + 'Programming Language :: Python', + 'Topic :: Software Development', + ], + description='Test the output of a ROS node.', + long_description='A package providing utilities for writing ROS2 enabled launch tests.', + license='Apache License, Version 2.0', + tests_require=['pytest'], +) diff --git a/apex_rostest/apex_launchtest_ros/test/test_copyright.py b/launch_testing_ros/test/test_copyright.py similarity index 100% rename from apex_rostest/apex_launchtest_ros/test/test_copyright.py rename to launch_testing_ros/test/test_copyright.py diff --git a/apex_rostest/apex_launchtest_ros/test/test_examples.py b/launch_testing_ros/test/test_examples.py similarity index 89% rename from apex_rostest/apex_launchtest_ros/test/test_examples.py rename to launch_testing_ros/test/test_examples.py index e0f9344d..fe13cf2c 100644 --- a/apex_rostest/apex_launchtest_ros/test/test_examples.py +++ b/launch_testing_ros/test/test_examples.py @@ -17,12 +17,13 @@ import subprocess import ament_index_python + import pytest testdata = glob.glob( os.path.join( - ament_index_python.get_package_share_directory('apex_launchtest_ros'), + ament_index_python.get_package_share_directory('launch_testing_ros'), 'examples', '*.test.py' ) @@ -34,6 +35,6 @@ @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] + proc = ['launch_test', example_path] assert 0 == subprocess.run(args=proc).returncode diff --git a/apex_rostest/apex_launchtest_ros/test/test_flake8.py b/launch_testing_ros/test/test_flake8.py similarity index 100% rename from apex_rostest/apex_launchtest_ros/test/test_flake8.py rename to launch_testing_ros/test/test_flake8.py diff --git a/apex_rostest/apex_launchtest_ros/test/test_pep257.py b/launch_testing_ros/test/test_pep257.py similarity index 100% rename from apex_rostest/apex_launchtest_ros/test/test_pep257.py rename to launch_testing_ros/test/test_pep257.py