diff --git a/launch_pytest/test/launch_pytest/examples/check_node_msgs.py b/launch_pytest/test/launch_pytest/examples/check_node_msgs.py index bae89e689..38eb0da5a 100644 --- a/launch_pytest/test/launch_pytest/examples/check_node_msgs.py +++ b/launch_pytest/test/launch_pytest/examples/check_node_msgs.py @@ -39,11 +39,12 @@ def generate_test_description(): arguments=[str(path_to_test / 'executables' / 'talker.py')], additional_env={'PYTHONUNBUFFERED': '1'}, name='demo_node_1', + output='screen', ), ]) -@pytest.mark.launch +@pytest.mark.launch(fixture=generate_test_description) def test_check_if_msgs_published(): rclpy.init() try: diff --git a/launch_pytest/test/launch_pytest/examples/executables/listener.py b/launch_pytest/test/launch_pytest/examples/executables/talker.py similarity index 67% rename from launch_pytest/test/launch_pytest/examples/executables/listener.py rename to launch_pytest/test/launch_pytest/examples/executables/talker.py index 861ae743d..46cc60756 100644 --- a/launch_pytest/test/launch_pytest/examples/executables/listener.py +++ b/launch_pytest/test/launch_pytest/examples/executables/talker.py @@ -18,22 +18,26 @@ from std_msgs.msg import String -class Listener(Node): +class Talker(Node): def __init__(self): - super().__init__('listener') - self.subscription = self.create_subscription( - String, 'chatter', self.callback, 10 - ) + super().__init__('talker') + self.count = 0 + self.publisher = self.create_publisher(String, 'chatter', 10) + self.timer = self.create_timer(1.0, self.callback) - def callback(self, msg): - self.get_logger().info('I heard: [%s]' % msg.data) + def callback(self): + data = 'Hello World: {0}'.format(self.count) + self.get_logger().info('Publishing: "{0}"'.format(data)) + self.publisher.publish(String(data=data)) + self.count += 1 def main(args=None): rclpy.init(args=args) - node = Listener() + node = Talker() + try: rclpy.spin(node) except KeyboardInterrupt: diff --git a/launch_pytest/test/launch_pytest/test_function_scope.py b/launch_pytest/test/launch_pytest/examples/function_scope.py similarity index 100% rename from launch_pytest/test/launch_pytest/test_function_scope.py rename to launch_pytest/test/launch_pytest/examples/function_scope.py diff --git a/launch_pytest/test/launch_pytest/test_module_scope.py b/launch_pytest/test/launch_pytest/examples/module_scope.py similarity index 100% rename from launch_pytest/test/launch_pytest/test_module_scope.py rename to launch_pytest/test/launch_pytest/examples/module_scope.py diff --git a/launch_pytest/test/launch_pytest/examples/pytest_hello_world.py b/launch_pytest/test/launch_pytest/examples/pytest_hello_world.py index 89246a232..ced833c42 100644 --- a/launch_pytest/test/launch_pytest/examples/pytest_hello_world.py +++ b/launch_pytest/test/launch_pytest/examples/pytest_hello_world.py @@ -49,7 +49,8 @@ def test_read_stdout(hello_world_proc, launch_context): def validate_output(output): # this function can use assertions to validate the output or return a boolean. # pytest generates easier to understand failures when assertions are used. - assert output == 'hello_world\n', 'process never printed hello_world' + assert output.splitlines() == ['hello_world'], 'process never printed hello_world' + return True assert process_tools.wait_for_output_sync( launch_context, hello_world_proc, validate_output, timeout=5) diff --git a/launch_pytest/test/launch_pytest/test_plugin.py b/launch_pytest/test/launch_pytest/test_plugin.py index deb9fbd12..a2e375e0e 100644 --- a/launch_pytest/test/launch_pytest/test_plugin.py +++ b/launch_pytest/test/launch_pytest/test_plugin.py @@ -12,6 +12,9 @@ # See the License for the specific language governing permissions and # limitations under the License. +from pathlib import Path +import shutil + def test_launch_fixture_is_not_a_launch_description(testdir): testdir.makepyfile("""\ @@ -313,3 +316,17 @@ async def test_case(): result = testdir.runpytest() result.assert_outcomes(failed=1, skipped=1) + + +def test_examples(testdir): + examples_dir = Path(__file__).parent / 'examples' + for example in examples_dir.iterdir(): + # Ignoring `check_node_msgs.py` because we cannot depend on launch_ros here + # as it creates a circular dependency between repositories. + # We need to move that example elsewhere. + if example.is_file() and example.name != 'check_node_msgs.py': + copied_example = Path(testdir.copy_example(example)) + copied_example.rename(copied_example.parent / f'test_{copied_example.name}') + shutil.copytree(examples_dir / 'executables', Path(str(testdir.tmpdir)) / 'executables') + result = testdir.runpytest() + result.assert_outcomes(passed=22) diff --git a/launch_pytest/test/launch_pytest/tools/test_process.py b/launch_pytest/test/launch_pytest/tools/test_process.py index f3281dd91..7d1de121e 100644 --- a/launch_pytest/test/launch_pytest/tools/test_process.py +++ b/launch_pytest/test/launch_pytest/tools/test_process.py @@ -48,25 +48,35 @@ def launch_description(dut): @pytest.mark.launch(fixture=launch_description) async def test_async_process_tools(dut, launch_context): - await tools.wait_for_start(launch_context, dut, timeout=10) - def check_output(output): assert output.splitlines() == ['hello'] - await tools.wait_for_output( + assert await tools.wait_for_start(launch_context, dut, timeout=10) + + def check_output(output): + assert output.splitlines() == ['hello'] + return True + assert await tools.wait_for_output( launch_context, dut, check_output, timeout=10) - def check_stderr(err): assert err.splitlines() == ['world'] - await tools.wait_for_stderr( + def check_stderr(err): + assert err.splitlines() == ['world'] + return True + assert await tools.wait_for_stderr( launch_context, dut, check_stderr, timeout=10) - await tools.wait_for_exit(launch_context, dut, timeout=10) + assert await tools.wait_for_exit(launch_context, dut, timeout=10) @pytest.mark.launch(fixture=launch_description) def test_sync_process_tools(dut, launch_context): tools.wait_for_start_sync(launch_context, dut, timeout=10) - def check_output(output): assert output.splitlines() == ['hello'] - tools.wait_for_output_sync( + + def check_output(output): + assert output.splitlines() == ['hello'] + return True + assert tools.wait_for_output_sync( launch_context, dut, check_output, timeout=10) - def check_stderr(err): assert err.splitlines() == ['world'] - tools.wait_for_stderr_sync( + def check_stderr(err): + assert err.splitlines() == ['world'] + return True + assert tools.wait_for_stderr_sync( launch_context, dut, check_stderr, timeout=10) - tools.wait_for_exit_sync(launch_context, dut, timeout=10) + assert tools.wait_for_exit_sync(launch_context, dut, timeout=10)