From fee00b5f14d6a65b65306ecfa91a176f4988a58b Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Fri, 1 Nov 2019 13:23:59 -0300 Subject: [PATCH 1/9] Add tests for ros2component Signed-off-by: Brian Ezequiel Marchi --- ros2component/test/test_cli.py | 268 +++++++++++++++++++++++++++++++++ 1 file changed, 268 insertions(+) create mode 100644 ros2component/test/test_cli.py diff --git a/ros2component/test/test_cli.py b/ros2component/test/test_cli.py new file mode 100644 index 000000000..8a487340d --- /dev/null +++ b/ros2component/test/test_cli.py @@ -0,0 +1,268 @@ +# 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 contextlib +import unittest + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch.actions import OpaqueFunction + +from launch_ros.actions import Node + +import launch_testing +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +import launch_testing_ros.tools + +import pytest + +from rmw_implementation import get_available_rmw_implementations + +DEMO_NODES_TYPES = """\ +demo_nodes_cpp + demo_nodes_cpp::OneOffTimerNode + demo_nodes_cpp::ReuseTimerNode + demo_nodes_cpp::ServerNode + demo_nodes_cpp::ClientNode + demo_nodes_cpp::ListParameters + demo_nodes_cpp::ParameterBlackboard + demo_nodes_cpp::SetAndGetParameters + demo_nodes_cpp::ParameterEventsAsyncNode + demo_nodes_cpp::EvenParameterNode + demo_nodes_cpp::Talker + demo_nodes_cpp::LoanedMessageTalker + demo_nodes_cpp::SerializedMessageTalker + demo_nodes_cpp::Listener + demo_nodes_cpp::SerializedMessageListener + demo_nodes_cpp::ListenerBestEffort +""" + +LIST_THREE_NODES = """\ +/ComponentManager + 2 /listener + 3 /talker + 4 /talker +""" + +LIST_FOUR_NODES = """\ +/ComponentManager + 2 /listener + 3 /talker + 4 /talker + 5 /talker +""" + + +@pytest.mark.rostest +@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) +def generate_test_description(rmw_implementation, ready_fn): + additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} + component_node = Node( + package='rclcpp_components', node_executable='component_container', output='screen') + return LaunchDescription([ + # Always restart daemon to isolate tests. + ExecuteProcess( + cmd=['ros2', 'daemon', 'stop'], + name='daemon-stop', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'daemon', 'start'], + name='daemon-start', + on_exit=[ + component_node, + OpaqueFunction(function=lambda context: ready_fn()) + ], + additional_env=additional_env + ) + ] + ), + ]), locals() + +# TODO(BMarchi): Open splice is returning a different code (2) when +# the launch of a component verb ends. It should return EXIT_OK unless +# the command returns a error string, which should be code 1. +class TestROS2ComponentCLI(unittest.TestCase): + + @classmethod + def setUpClass( + cls, + launch_service, + proc_info, + proc_output, + rmw_implementation + ): + @contextlib.contextmanager + def launch_node_command(self, arguments): + node_command_action = ExecuteProcess( + cmd=['ros2', 'component', *arguments], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + with launch_testing.tools.launch_process( + launch_service, node_command_action, proc_info, proc_output, + output_filter=launch_testing_ros.tools.basic_output_filter( + # ignore ros2cli daemon nodes + filtered_patterns=['.*ros2cli.*'], + filtered_rmw_implementation=rmw_implementation + ) + ) as node_command: + yield node_command + cls.launch_node_command = launch_node_command + + # Set verb tests + @launch_testing.markers.retry_on_failure(times=3) + def test_types_component(self): + with self.launch_node_command( + arguments=['types']) as node_command: + assert node_command.wait_for_shutdown(timeout=20) + assert node_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_text=DEMO_NODES_TYPES, + text=node_command.output, + strict=True + ) + + @launch_testing.markers.retry_on_failure(times=2) + def test_load_unload_verb(self): + with self.launch_node_command( + arguments=[ + 'load', '/ComponentManager', + 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: + assert talker_node.wait_for_shutdown(timeout=20) + assert talker_node.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=[ + "Loaded component 1 into '/ComponentManager' " + "container node as '/talker'"], + text=talker_node.output, + strict=True + ) + with self.launch_node_command( + arguments=[ + 'load', '/ComponentManager', + 'demo_nodes_cpp', 'demo_nodes_cpp::Listener']) as listener_node: + assert listener_node.wait_for_shutdown(timeout=20) + assert listener_node.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=[ + "Loaded component 2 into '/ComponentManager' " + "container node as '/listener'"], + text=listener_node.output, + strict=True + ) + with self.launch_node_command( + arguments=[ + 'unload', '/ComponentManager', '1']) as unload_command: + assert unload_command.wait_for_shutdown(timeout=20) + assert unload_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=["Unloaded component 1 from '/ComponentManager' container"], + text=unload_command.output, + strict=True + ) + # Test the unique id for loaded nodes. + with self.launch_node_command( + arguments=[ + 'load', '/ComponentManager', + 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: + assert talker_node.wait_for_shutdown(timeout=20) + assert talker_node.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=[ + "Loaded component 3 into '/ComponentManager' " + "container node as '/talker'"], + text=talker_node.output, + strict=True + ) + # Test we can load the same node more than once. + with self.launch_node_command( + arguments=[ + 'load', '/ComponentManager', + 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: + assert talker_node.wait_for_shutdown(timeout=20) + assert talker_node.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=[ + "Loaded component 4 into '/ComponentManager' " + "container node as '/talker'"], + text=talker_node.output, + strict=True + ) + with self.launch_node_command( + arguments=['list']) as list_command: + assert list_command.wait_for_shutdown(timeout=20) + assert list_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_text=LIST_THREE_NODES, + text=list_command.output, + strict=True + ) + + # Unexisting class in existing plugin + with self.launch_node_command( + arguments=[ + 'load', '/ComponentManager', + 'demo_nodes_cpp', 'demo_nodes_cpp::NonExistingPlugin']) as command: + assert command.wait_for_shutdown(timeout=20) + assert command.exit_code == 1 + assert launch_testing.tools.expect_output( + expected_lines=[ + 'Failed to load component: ' + 'Failed to find class with the requested plugin name.'], + text=command.output, + strict=True + ) + # Test unexisting plugin + with self.launch_node_command( + arguments=[ + 'load', '/ComponentManager', + 'non_existing_plugin', 'non_existing_plugin::Test']) as command: + assert command.wait_for_shutdown(timeout=20) + assert command.exit_code == 1 + assert launch_testing.tools.expect_output( + expected_lines=[ + 'Failed to load component: ' + 'Could not find requested resource in ament index'], + text=command.output, + strict=True + ) + with self.launch_node_command( + arguments=[ + 'load', '/ComponentManager', + 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: + assert talker_node.wait_for_shutdown(timeout=20) + assert talker_node.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=[ + "Loaded component 5 into '/ComponentManager' " + "container node as '/talker'"], + text=talker_node.output, + strict=True + ) + # Verify that we added just one talker and not the non existent nodes. + with self.launch_node_command( + arguments=['list']) as list_command: + assert list_command.wait_for_shutdown(timeout=20) + assert list_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_text=LIST_FOUR_NODES, + text=list_command.output, + strict=True + ) From c848cd20c9137cc083295b5b200e5cf714ef31a0 Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Mon, 4 Nov 2019 09:49:36 -0300 Subject: [PATCH 2/9] Add missing dependencies Signed-off-by: Brian Ezequiel Marchi --- ros2component/package.xml | 5 ++++- ros2component/test/test_cli.py | 1 + 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ros2component/package.xml b/ros2component/package.xml index f740557c3..175d8632a 100644 --- a/ros2component/package.xml +++ b/ros2component/package.xml @@ -9,12 +9,13 @@ Michel Hidalgo Apache License 2.0 + ros2cli + ament_index_python composition_interfaces rcl_interfaces rclcpp_components rclpy - ros2cli ros2node ros2param ros2pkg @@ -23,7 +24,9 @@ ament_flake8 ament_pep257 ament_xmllint + demo_nodes_cpp python3-pytest + ros_testing ament_python diff --git a/ros2component/test/test_cli.py b/ros2component/test/test_cli.py index 8a487340d..3f3f47d31 100644 --- a/ros2component/test/test_cli.py +++ b/ros2component/test/test_cli.py @@ -91,6 +91,7 @@ def generate_test_description(rmw_implementation, ready_fn): ), ]), locals() + # TODO(BMarchi): Open splice is returning a different code (2) when # the launch of a component verb ends. It should return EXIT_OK unless # the command returns a error string, which should be code 1. From 2bff91bb0a6684e215a7d0044b4ad4a0f4f3aec9 Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Tue, 5 Nov 2019 15:44:18 -0300 Subject: [PATCH 3/9] Make use of the composition package and separate verbs in different tests Signed-off-by: Brian Ezequiel Marchi --- ros2component/package.xml | 2 +- ros2component/test/test_cli_list.py | 150 +++++++++++++++ .../test/{test_cli.py => test_cli_load.py} | 111 ++--------- ros2component/test/test_cli_types.py | 113 +++++++++++ ros2component/test/test_cli_unload.py | 175 ++++++++++++++++++ 5 files changed, 457 insertions(+), 94 deletions(-) create mode 100644 ros2component/test/test_cli_list.py rename ros2component/test/{test_cli.py => test_cli_load.py} (64%) create mode 100644 ros2component/test/test_cli_types.py create mode 100644 ros2component/test/test_cli_unload.py diff --git a/ros2component/package.xml b/ros2component/package.xml index 175d8632a..7b8a419ea 100644 --- a/ros2component/package.xml +++ b/ros2component/package.xml @@ -24,7 +24,7 @@ ament_flake8 ament_pep257 ament_xmllint - demo_nodes_cpp + composition python3-pytest ros_testing diff --git a/ros2component/test/test_cli_list.py b/ros2component/test/test_cli_list.py new file mode 100644 index 000000000..58b85fe5a --- /dev/null +++ b/ros2component/test/test_cli_list.py @@ -0,0 +1,150 @@ +# 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 contextlib +import unittest + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch.actions import OpaqueFunction + +from launch_ros.actions import Node + +import launch_testing +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +import launch_testing_ros.tools + +import pytest + +from rmw_implementation import get_available_rmw_implementations + +LIST_THREE_NODES = """\ +/ComponentManager + 1 /listener + 2 /talker + 3 /talker +""" + + +# TODO(BMarchi): Opensplice doesn't get along with running any cli command with ExecuteProcess, +# it just hangs there making `wait_for_timeout` fail. All tests should run fine with opensplice. +@pytest.mark.rostest +@launch_testing.parametrize( + 'rmw_implementation', + [v for v in get_available_rmw_implementations() if v != 'rmw_opensplice_cpp']) +def generate_test_description(rmw_implementation, ready_fn): + additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} + component_node = Node( + package='rclcpp_components', node_executable='component_container', output='screen') + listener_command_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'composition', 'composition::Listener'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'composition', 'composition::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'composition', 'composition::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + ] + ) + ] + ) + return LaunchDescription([ + # Always restart daemon to isolate tests. + ExecuteProcess( + cmd=['ros2', 'daemon', 'stop'], + name='daemon-stop', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'daemon', 'start'], + name='daemon-start', + on_exit=[ + component_node, + OpaqueFunction(function=lambda context: ready_fn()), + listener_command_action + ], + additional_env=additional_env + ) + ] + ), + ]), locals() + + +class TestROS2ComponentListCLI(unittest.TestCase): + + @classmethod + def setUpClass( + cls, + launch_service, + proc_info, + proc_output, + rmw_implementation + ): + @contextlib.contextmanager + def launch_node_command(self, arguments): + node_command_action = ExecuteProcess( + cmd=['ros2', 'component', *arguments], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + with launch_testing.tools.launch_process( + launch_service, node_command_action, proc_info, proc_output, + output_filter=launch_testing_ros.tools.basic_output_filter( + # ignore ros2cli daemon nodes + filtered_patterns=['.*ros2cli.*'], + filtered_rmw_implementation=rmw_implementation + ) + ) as node_command: + yield node_command + cls.launch_node_command = launch_node_command + cls.rmw_implementation = rmw_implementation + + @launch_testing.markers.retry_on_failure(times=5) + def test_list_verb(self): + with self.launch_node_command( + arguments=['list']) as list_command: + assert list_command.wait_for_shutdown(timeout=5) + assert list_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_text=LIST_THREE_NODES, + text=list_command.output, + strict=True + ) diff --git a/ros2component/test/test_cli.py b/ros2component/test/test_cli_load.py similarity index 64% rename from ros2component/test/test_cli.py rename to ros2component/test/test_cli_load.py index 3f3f47d31..ab1ae4095 100644 --- a/ros2component/test/test_cli.py +++ b/ros2component/test/test_cli_load.py @@ -31,43 +31,13 @@ from rmw_implementation import get_available_rmw_implementations -DEMO_NODES_TYPES = """\ -demo_nodes_cpp - demo_nodes_cpp::OneOffTimerNode - demo_nodes_cpp::ReuseTimerNode - demo_nodes_cpp::ServerNode - demo_nodes_cpp::ClientNode - demo_nodes_cpp::ListParameters - demo_nodes_cpp::ParameterBlackboard - demo_nodes_cpp::SetAndGetParameters - demo_nodes_cpp::ParameterEventsAsyncNode - demo_nodes_cpp::EvenParameterNode - demo_nodes_cpp::Talker - demo_nodes_cpp::LoanedMessageTalker - demo_nodes_cpp::SerializedMessageTalker - demo_nodes_cpp::Listener - demo_nodes_cpp::SerializedMessageListener - demo_nodes_cpp::ListenerBestEffort -""" - -LIST_THREE_NODES = """\ -/ComponentManager - 2 /listener - 3 /talker - 4 /talker -""" - -LIST_FOUR_NODES = """\ -/ComponentManager - 2 /listener - 3 /talker - 4 /talker - 5 /talker -""" - +# TODO(BMarchi): Opensplice doesn't get along with running any cli command with ExecuteProcess, +# it just hangs there making `wait_for_timeout` fail. All tests should run fine with opensplice. @pytest.mark.rostest -@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) +@launch_testing.parametrize( + 'rmw_implementation', + [v for v in get_available_rmw_implementations() if v != 'rmw_opensplice_cpp']) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} component_node = Node( @@ -92,10 +62,7 @@ def generate_test_description(rmw_implementation, ready_fn): ]), locals() -# TODO(BMarchi): Open splice is returning a different code (2) when -# the launch of a component verb ends. It should return EXIT_OK unless -# the command returns a error string, which should be code 1. -class TestROS2ComponentCLI(unittest.TestCase): +class TestROS2ComponentLoadCLI(unittest.TestCase): @classmethod def setUpClass( @@ -127,25 +94,12 @@ def launch_node_command(self, arguments): yield node_command cls.launch_node_command = launch_node_command - # Set verb tests - @launch_testing.markers.retry_on_failure(times=3) - def test_types_component(self): - with self.launch_node_command( - arguments=['types']) as node_command: - assert node_command.wait_for_shutdown(timeout=20) - assert node_command.exit_code == launch_testing.asserts.EXIT_OK - assert launch_testing.tools.expect_output( - expected_text=DEMO_NODES_TYPES, - text=node_command.output, - strict=True - ) - @launch_testing.markers.retry_on_failure(times=2) - def test_load_unload_verb(self): + def test_load_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: + 'composition', 'composition::Talker']) as talker_node: assert talker_node.wait_for_shutdown(timeout=20) assert talker_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -158,7 +112,7 @@ def test_load_unload_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'demo_nodes_cpp', 'demo_nodes_cpp::Listener']) as listener_node: + 'composition', 'composition::Listener']) as listener_node: assert listener_node.wait_for_shutdown(timeout=20) assert listener_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -182,7 +136,7 @@ def test_load_unload_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: + 'composition', 'composition::Talker']) as talker_node: assert talker_node.wait_for_shutdown(timeout=20) assert talker_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -196,7 +150,7 @@ def test_load_unload_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: + 'composition', 'composition::Talker']) as talker_node: assert talker_node.wait_for_shutdown(timeout=20) assert talker_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -206,21 +160,13 @@ def test_load_unload_verb(self): text=talker_node.output, strict=True ) - with self.launch_node_command( - arguments=['list']) as list_command: - assert list_command.wait_for_shutdown(timeout=20) - assert list_command.exit_code == launch_testing.asserts.EXIT_OK - assert launch_testing.tools.expect_output( - expected_text=LIST_THREE_NODES, - text=list_command.output, - strict=True - ) - # Unexisting class in existing plugin + @launch_testing.markers.retry_on_failure(times=2) + def test_load_verb_nonexistent_class(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'demo_nodes_cpp', 'demo_nodes_cpp::NonExistingPlugin']) as command: + 'composition', 'composition::NonExistingPlugin']) as command: assert command.wait_for_shutdown(timeout=20) assert command.exit_code == 1 assert launch_testing.tools.expect_output( @@ -230,11 +176,13 @@ def test_load_unload_verb(self): text=command.output, strict=True ) - # Test unexisting plugin + + @launch_testing.markers.retry_on_failure(times=2) + def test_load_verb_nonexistent_plugin(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'non_existing_plugin', 'non_existing_plugin::Test']) as command: + 'non_existent_plugin', 'non_existent_plugin::Test']) as command: assert command.wait_for_shutdown(timeout=20) assert command.exit_code == 1 assert launch_testing.tools.expect_output( @@ -244,26 +192,3 @@ def test_load_unload_verb(self): text=command.output, strict=True ) - with self.launch_node_command( - arguments=[ - 'load', '/ComponentManager', - 'demo_nodes_cpp', 'demo_nodes_cpp::Talker']) as talker_node: - assert talker_node.wait_for_shutdown(timeout=20) - assert talker_node.exit_code == launch_testing.asserts.EXIT_OK - assert launch_testing.tools.expect_output( - expected_lines=[ - "Loaded component 5 into '/ComponentManager' " - "container node as '/talker'"], - text=talker_node.output, - strict=True - ) - # Verify that we added just one talker and not the non existent nodes. - with self.launch_node_command( - arguments=['list']) as list_command: - assert list_command.wait_for_shutdown(timeout=20) - assert list_command.exit_code == launch_testing.asserts.EXIT_OK - assert launch_testing.tools.expect_output( - expected_text=LIST_FOUR_NODES, - text=list_command.output, - strict=True - ) diff --git a/ros2component/test/test_cli_types.py b/ros2component/test/test_cli_types.py new file mode 100644 index 000000000..e65d584f6 --- /dev/null +++ b/ros2component/test/test_cli_types.py @@ -0,0 +1,113 @@ +# 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 contextlib +import unittest + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch.actions import OpaqueFunction + +from launch_ros.actions import Node + +import launch_testing +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +import launch_testing_ros.tools + +import pytest + +from rmw_implementation import get_available_rmw_implementations + +DEMO_NODES_TYPES = """\ +composition + composition::Talker + composition::Listener + composition::NodeLikeListener + composition::Server + composition::Client +""" + + +@pytest.mark.rostest +@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) +def generate_test_description(rmw_implementation, ready_fn): + additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} + component_node = Node( + package='rclcpp_components', node_executable='component_container', output='screen') + return LaunchDescription([ + # Always restart daemon to isolate tests. + ExecuteProcess( + cmd=['ros2', 'daemon', 'stop'], + name='daemon-stop', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'daemon', 'start'], + name='daemon-start', + on_exit=[ + component_node, + OpaqueFunction(function=lambda context: ready_fn()) + ], + additional_env=additional_env + ) + ] + ), + ]), locals() + + +class TestROS2ComponentTypesCLI(unittest.TestCase): + + @classmethod + def setUpClass( + cls, + launch_service, + proc_info, + proc_output, + rmw_implementation + ): + @contextlib.contextmanager + def launch_node_command(self, arguments): + node_command_action = ExecuteProcess( + cmd=['ros2', 'component', *arguments], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + with launch_testing.tools.launch_process( + launch_service, node_command_action, proc_info, proc_output, + output_filter=launch_testing_ros.tools.basic_output_filter( + # ignore ros2cli daemon nodes + filtered_patterns=['.*ros2cli.*'], + filtered_rmw_implementation=rmw_implementation + ) + ) as node_command: + yield node_command + cls.launch_node_command = launch_node_command + + # Set verb tests + @launch_testing.markers.retry_on_failure(times=3) + def test_types_verb(self): + with self.launch_node_command( + arguments=['types']) as node_command: + assert node_command.wait_for_shutdown(timeout=20) + assert node_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_text=DEMO_NODES_TYPES, + text=node_command.output, + strict=True + ) diff --git a/ros2component/test/test_cli_unload.py b/ros2component/test/test_cli_unload.py new file mode 100644 index 000000000..ec182e0bf --- /dev/null +++ b/ros2component/test/test_cli_unload.py @@ -0,0 +1,175 @@ +# 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 contextlib +import unittest + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch.actions import OpaqueFunction + +from launch_ros.actions import Node + +import launch_testing +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +import launch_testing_ros.tools + +import pytest + +from rmw_implementation import get_available_rmw_implementations + +NON_EXISTENT_ID = """\ +Failed to unload component 5 from '/ComponentManager' container node + No node found with unique_id: 5 +""" + + +# TODO(BMarchi): Opensplice doesn't get along with running any cli command with ExecuteProcess, +# it just hangs there making `wait_for_timeout` fail. All tests should run fine with opensplice. +@pytest.mark.rostest +@launch_testing.parametrize( + 'rmw_implementation', + [v for v in get_available_rmw_implementations() if v != 'rmw_opensplice_cpp']) +def generate_test_description(rmw_implementation, ready_fn): + additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} + component_node = Node( + package='rclcpp_components', node_executable='component_container', output='screen') + listener_command_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'composition', 'composition::Listener'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'composition', 'composition::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'composition', 'composition::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + ] + ) + ] + ) + return LaunchDescription([ + # Always restart daemon to isolate tests. + ExecuteProcess( + cmd=['ros2', 'daemon', 'stop'], + name='daemon-stop', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'daemon', 'start'], + name='daemon-start', + on_exit=[ + component_node, + OpaqueFunction(function=lambda context: ready_fn()), + listener_command_action + ], + additional_env=additional_env + ) + ] + ), + ]), locals() + + +class TestROS2ComponentUnloadCLI(unittest.TestCase): + + @classmethod + def setUpClass( + cls, + launch_service, + proc_info, + proc_output, + rmw_implementation + ): + @contextlib.contextmanager + def launch_node_command(self, arguments): + node_command_action = ExecuteProcess( + cmd=['ros2', 'component', *arguments], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + with launch_testing.tools.launch_process( + launch_service, node_command_action, proc_info, proc_output, + output_filter=launch_testing_ros.tools.basic_output_filter( + # ignore ros2cli daemon nodes + filtered_patterns=['.*ros2cli.*'], + filtered_rmw_implementation=rmw_implementation + ) + ) as node_command: + yield node_command + cls.launch_node_command = launch_node_command + cls.rmw_implementation = rmw_implementation + + @launch_testing.markers.retry_on_failure(times=4) + def test_unload_verb(self): + with self.launch_node_command( + arguments=[ + 'unload', '/ComponentManager', '1']) as unload_command: + assert unload_command.wait_for_shutdown(timeout=20) + assert unload_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=["Unloaded component 1 from '/ComponentManager' container"], + text=unload_command.output, + strict=True + ) + + @launch_testing.markers.retry_on_failure(times=4) + def test_unload_verb_nonexistent_id(self): + with self.launch_node_command( + arguments=[ + 'unload', '/ComponentManager', '5']) as unload_command: + assert unload_command.wait_for_shutdown(timeout=20) + assert unload_command.exit_code == 1 + assert launch_testing.tools.expect_output( + expected_text=NON_EXISTENT_ID, + text=unload_command.output, + strict=True + ) + + @launch_testing.markers.retry_on_failure(times=4) + def test_unload_verb_nonexistent_container(self): + with self.launch_node_command( + arguments=[ + 'unload', '/NonExistentContainer', '5']) as unload_command: + assert unload_command.wait_for_shutdown(timeout=20) + assert unload_command.exit_code == 1 + assert launch_testing.tools.expect_output( + expected_text="Unable to find container node '/NonExistentContainer'\n", + text=unload_command.output, + strict=True + ) From 9c2dda27464354ab3484c99a9d46aeeb50d00032 Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Wed, 6 Nov 2019 09:18:37 -0300 Subject: [PATCH 4/9] Add examples repository for ros2component Signed-off-by: Brian Ezequiel Marchi --- ros2component/package.xml | 2 +- ros2component/test/test_cli_list.py | 6 +- ros2component/test/test_cli_load.py | 12 ++-- ros2component/test/test_cli_types.py | 9 +-- ros2component/test/test_cli_unload.py | 6 +- ros2component_fixtures/CMakeLists.txt | 60 ++++++++++++++++++ .../listener_component.hpp | 37 +++++++++++ .../talker_component.hpp | 42 +++++++++++++ .../visibility_control.h | 58 +++++++++++++++++ ros2component_fixtures/package.xml | 27 ++++++++ .../src/listener_component.cpp | 55 ++++++++++++++++ .../src/talker_component.cpp | 62 +++++++++++++++++++ 12 files changed, 358 insertions(+), 18 deletions(-) create mode 100644 ros2component_fixtures/CMakeLists.txt create mode 100644 ros2component_fixtures/include/ros2component_fixtures/listener_component.hpp create mode 100644 ros2component_fixtures/include/ros2component_fixtures/talker_component.hpp create mode 100644 ros2component_fixtures/include/ros2component_fixtures/visibility_control.h create mode 100644 ros2component_fixtures/package.xml create mode 100644 ros2component_fixtures/src/listener_component.cpp create mode 100644 ros2component_fixtures/src/talker_component.cpp diff --git a/ros2component/package.xml b/ros2component/package.xml index 7b8a419ea..ea322f9db 100644 --- a/ros2component/package.xml +++ b/ros2component/package.xml @@ -24,8 +24,8 @@ ament_flake8 ament_pep257 ament_xmllint - composition python3-pytest + ros2component_fixtures ros_testing diff --git a/ros2component/test/test_cli_list.py b/ros2component/test/test_cli_list.py index 58b85fe5a..5973b3d78 100644 --- a/ros2component/test/test_cli_list.py +++ b/ros2component/test/test_cli_list.py @@ -51,7 +51,7 @@ def generate_test_description(rmw_implementation, ready_fn): package='rclcpp_components', node_executable='component_container', output='screen') listener_command_action = ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'composition', 'composition::Listener'], + 'ros2component_fixtures', 'ros2component_fixtures::Listener'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' @@ -61,7 +61,7 @@ def generate_test_description(rmw_implementation, ready_fn): on_exit=[ ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'composition', 'composition::Talker'], + 'ros2component_fixtures', 'ros2component_fixtures::Talker'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' @@ -71,7 +71,7 @@ def generate_test_description(rmw_implementation, ready_fn): on_exit=[ ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'composition', 'composition::Talker'], + 'ros2component_fixtures', 'ros2component_fixtures::Talker'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' diff --git a/ros2component/test/test_cli_load.py b/ros2component/test/test_cli_load.py index ab1ae4095..b7ca7adf5 100644 --- a/ros2component/test/test_cli_load.py +++ b/ros2component/test/test_cli_load.py @@ -99,7 +99,7 @@ def test_load_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'composition', 'composition::Talker']) as talker_node: + 'ros2component_fixtures', 'ros2component_fixtures::Talker']) as talker_node: assert talker_node.wait_for_shutdown(timeout=20) assert talker_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -112,7 +112,8 @@ def test_load_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'composition', 'composition::Listener']) as listener_node: + 'ros2component_fixtures', + 'ros2component_fixtures::Listener']) as listener_node: assert listener_node.wait_for_shutdown(timeout=20) assert listener_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -136,7 +137,7 @@ def test_load_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'composition', 'composition::Talker']) as talker_node: + 'ros2component_fixtures', 'ros2component_fixtures::Talker']) as talker_node: assert talker_node.wait_for_shutdown(timeout=20) assert talker_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -150,7 +151,7 @@ def test_load_verb(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'composition', 'composition::Talker']) as talker_node: + 'ros2component_fixtures', 'ros2component_fixtures::Talker']) as talker_node: assert talker_node.wait_for_shutdown(timeout=20) assert talker_node.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( @@ -166,7 +167,8 @@ def test_load_verb_nonexistent_class(self): with self.launch_node_command( arguments=[ 'load', '/ComponentManager', - 'composition', 'composition::NonExistingPlugin']) as command: + 'ros2component_fixtures', + 'ros2component_fixtures::NonExistingPlugin']) as command: assert command.wait_for_shutdown(timeout=20) assert command.exit_code == 1 assert launch_testing.tools.expect_output( diff --git a/ros2component/test/test_cli_types.py b/ros2component/test/test_cli_types.py index e65d584f6..d1b388428 100644 --- a/ros2component/test/test_cli_types.py +++ b/ros2component/test/test_cli_types.py @@ -32,12 +32,9 @@ from rmw_implementation import get_available_rmw_implementations DEMO_NODES_TYPES = """\ -composition - composition::Talker - composition::Listener - composition::NodeLikeListener - composition::Server - composition::Client +ros2component_fixtures + ros2component_fixtures::Talker + ros2component_fixtures::Listener """ diff --git a/ros2component/test/test_cli_unload.py b/ros2component/test/test_cli_unload.py index ec182e0bf..5fb9938af 100644 --- a/ros2component/test/test_cli_unload.py +++ b/ros2component/test/test_cli_unload.py @@ -49,7 +49,7 @@ def generate_test_description(rmw_implementation, ready_fn): package='rclcpp_components', node_executable='component_container', output='screen') listener_command_action = ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'composition', 'composition::Listener'], + 'ros2component_fixtures', 'ros2component_fixtures::Listener'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' @@ -59,7 +59,7 @@ def generate_test_description(rmw_implementation, ready_fn): on_exit=[ ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'composition', 'composition::Talker'], + 'ros2component_fixtures', 'ros2component_fixtures::Talker'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' @@ -69,7 +69,7 @@ def generate_test_description(rmw_implementation, ready_fn): on_exit=[ ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'composition', 'composition::Talker'], + 'ros2component_fixtures', 'ros2component_fixtures::Talker'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' diff --git a/ros2component_fixtures/CMakeLists.txt b/ros2component_fixtures/CMakeLists.txt new file mode 100644 index 000000000..ff5de6135 --- /dev/null +++ b/ros2component_fixtures/CMakeLists.txt @@ -0,0 +1,60 @@ +cmake_minimum_required(VERSION 3.5) + +project(ros2component_fixtures) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_components REQUIRED) +find_package(std_msgs REQUIRED) + +include_directories(include) + +# create ament index resource which references the libraries in the binary dir +set(node_plugins "") + +add_library(talker_component SHARED + src/talker_component.cpp) +target_compile_definitions(talker_component + PRIVATE "ROS2COMPONENT_FIXTURES_BUILDING_DLL") +ament_target_dependencies(talker_component + "rclcpp" + "rclcpp_components" + "std_msgs") +rclcpp_components_register_nodes(talker_component "ros2component_fixtures::Talker") +set(node_plugins "${node_plugins}ros2component_fixtures::Talker;$\n") + +add_library(listener_component SHARED + src/listener_component.cpp) +target_compile_definitions(listener_component + PRIVATE "ROS2COMPONENT_FIXTURES_BUILDING_DLL") +ament_target_dependencies(listener_component + "rclcpp" + "rclcpp_components" + "std_msgs") +rclcpp_components_register_nodes(listener_component "ros2component_fixtures::Listener") +set(node_plugins "${node_plugins}ros2component_fixtures::Listener;$\n") + +# since the package installs libraries without exporting them +# it needs to make sure that the library path is being exported +if(NOT WIN32) + ament_environment_hooks( + "${ament_cmake_package_templates_ENVIRONMENT_HOOK_LIBRARY_PATH}") +endif() + +install(TARGETS + talker_component + listener_component + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin) + +ament_package() diff --git a/ros2component_fixtures/include/ros2component_fixtures/listener_component.hpp b/ros2component_fixtures/include/ros2component_fixtures/listener_component.hpp new file mode 100644 index 000000000..bd6d2b7d0 --- /dev/null +++ b/ros2component_fixtures/include/ros2component_fixtures/listener_component.hpp @@ -0,0 +1,37 @@ +// 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. + +#ifndef ROS2COMPONENT_FIXTURES__LISTENER_COMPONENT_HPP_ +#define ROS2COMPONENT_FIXTURES__LISTENER_COMPONENT_HPP_ + +#include "ros2component_fixtures/visibility_control.h" +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + +namespace ros2component_fixtures +{ + +class Listener : public rclcpp::Node +{ +public: + ROS2COMPONENT_FIXTURES_PUBLIC + explicit Listener(const rclcpp::NodeOptions & options); + +private: + rclcpp::Subscription::SharedPtr sub_; +}; + +} // namespace ros2component_fixtures + +#endif // ROS2COMPONENT_FIXTURES__LISTENER_COMPONENT_HPP_ diff --git a/ros2component_fixtures/include/ros2component_fixtures/talker_component.hpp b/ros2component_fixtures/include/ros2component_fixtures/talker_component.hpp new file mode 100644 index 000000000..fdc07a45b --- /dev/null +++ b/ros2component_fixtures/include/ros2component_fixtures/talker_component.hpp @@ -0,0 +1,42 @@ +// 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. + +#ifndef ROS2COMPONENT_FIXTURES__TALKER_COMPONENT_HPP_ +#define ROS2COMPONENT_FIXTURES__TALKER_COMPONENT_HPP_ + +#include "ros2component_fixtures/visibility_control.h" +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + +namespace ros2component_fixtures +{ + +class Talker : public rclcpp::Node +{ +public: + ROS2COMPONENT_FIXTURES_PUBLIC + explicit Talker(const rclcpp::NodeOptions & options); + +protected: + void on_timer(); + +private: + size_t count_; + rclcpp::Publisher::SharedPtr pub_; + rclcpp::TimerBase::SharedPtr timer_; +}; + +} // namespace ros2component_fixtures + +#endif // ROS2COMPONENT_FIXTURES__TALKER_COMPONENT_HPP_ diff --git a/ros2component_fixtures/include/ros2component_fixtures/visibility_control.h b/ros2component_fixtures/include/ros2component_fixtures/visibility_control.h new file mode 100644 index 000000000..83cdbba8a --- /dev/null +++ b/ros2component_fixtures/include/ros2component_fixtures/visibility_control.h @@ -0,0 +1,58 @@ +// 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. + +#ifndef ROS2COMPONENT_FIXTURES__VISIBILITY_CONTROL_H_ +#define ROS2COMPONENT_FIXTURES__VISIBILITY_CONTROL_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROS2COMPONENT_FIXTURES_EXPORT __attribute__ ((dllexport)) + #define ROS2COMPONENT_FIXTURES_IMPORT __attribute__ ((dllimport)) + #else + #define ROS2COMPONENT_FIXTURES_EXPORT __declspec(dllexport) + #define ROS2COMPONENT_FIXTURES_IMPORT __declspec(dllimport) + #endif + #ifdef ROS2COMPONENT_FIXTURES_BUILDING_DLL + #define ROS2COMPONENT_FIXTURES_PUBLIC ROS2COMPONENT_FIXTURES_EXPORT + #else + #define ROS2COMPONENT_FIXTURES_PUBLIC ROS2COMPONENT_FIXTURES_IMPORT + #endif + #define ROS2COMPONENT_FIXTURES_PUBLIC_TYPE ROS2COMPONENT_FIXTURES_PUBLIC + #define ROS2COMPONENT_FIXTURES_LOCAL +#else + #define ROS2COMPONENT_FIXTURES_EXPORT __attribute__ ((visibility("default"))) + #define ROS2COMPONENT_FIXTURES_IMPORT + #if __GNUC__ >= 4 + #define ROS2COMPONENT_FIXTURES_PUBLIC __attribute__ ((visibility("default"))) + #define ROS2COMPONENT_FIXTURES_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROS2COMPONENT_FIXTURES_PUBLIC + #define ROS2COMPONENT_FIXTURES_LOCAL + #endif + #define ROS2COMPONENT_FIXTURES_PUBLIC_TYPE +#endif + +#ifdef __cplusplus +} +#endif + +#endif // ROS2COMPONENT_FIXTURES__VISIBILITY_CONTROL_H_ diff --git a/ros2component_fixtures/package.xml b/ros2component_fixtures/package.xml new file mode 100644 index 000000000..bfd16b8bf --- /dev/null +++ b/ros2component_fixtures/package.xml @@ -0,0 +1,27 @@ + + + + ros2component_fixtures + 0.1.0 + Examples for ros2component cli + Dirk Thomas + Apache License 2.0 + + ament_cmake + + rclcpp + rclcpp_components + std_msgs + + rclcpp + rclcpp_components + std_msgs + + ament_cmake_pytest + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros2component_fixtures/src/listener_component.cpp b/ros2component_fixtures/src/listener_component.cpp new file mode 100644 index 000000000..911e3bf56 --- /dev/null +++ b/ros2component_fixtures/src/listener_component.cpp @@ -0,0 +1,55 @@ +// 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. + +#include "ros2component_fixtures/listener_component.hpp" + +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + +namespace ros2component_fixtures +{ + +// Create a Listener "component" that subclasses the generic rclcpp::Node base class. +// Components get built into shared libraries and as such do not write their own main functions. +// The process using the component's shared library will instantiate the class as a ROS node. +Listener::Listener(const rclcpp::NodeOptions & options) +: Node("listener", options) +{ + // Create a callback function for when messages are received. + // Variations of this function also exist using, for example, UniquePtr for zero-copy transport. + auto callback = + [this](const typename std_msgs::msg::String::SharedPtr msg) -> void + { + RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str()); + std::flush(std::cout); + }; + + // Create a subscription to the "chatter" topic which can be matched with one or more + // compatible ROS publishers. + // Note that not all publishers on the same topic with the same type will be compatible: + // they must have compatible Quality of Service policies. + sub_ = create_subscription("chatter", 10, callback); +} + +} // namespace ros2component_fixtures + +#include "rclcpp_components/register_node_macro.hpp" + +// Register the component with class_loader. +// This acts as a sort of entry point, allowing the component to be discoverable when its library +// is being loaded into a running process. +RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_fixtures::Listener) diff --git a/ros2component_fixtures/src/talker_component.cpp b/ros2component_fixtures/src/talker_component.cpp new file mode 100644 index 000000000..7d08ef876 --- /dev/null +++ b/ros2component_fixtures/src/talker_component.cpp @@ -0,0 +1,62 @@ +// 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. + +#include "ros2component_fixtures/talker_component.hpp" + +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + +using namespace std::chrono_literals; + +namespace ros2component_fixtures +{ + +// Create a Talker "component" that subclasses the generic rclcpp::Node base class. +// Components get built into shared libraries and as such do not write their own main functions. +// The process using the component's shared library will instantiate the class as a ROS node. +Talker::Talker(const rclcpp::NodeOptions & options) +: Node("talker", options), count_(0) +{ + // Create a publisher of "std_mgs/String" messages on the "chatter" topic. + pub_ = create_publisher("chatter", 10); + + // Use a timer to schedule periodic message publishing. + timer_ = create_wall_timer(1s, std::bind(&Talker::on_timer, this)); +} + +void Talker::on_timer() +{ + auto msg = std::make_unique(); + msg->data = "Hello World: " + std::to_string(++count_); + RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str()); + std::flush(std::cout); + + // Put the message into a queue to be processed by the middleware. + // This call is non-blocking. + pub_->publish(std::move(msg)); +} + +} // namespace ros2component_fixtures + +#include "rclcpp_components/register_node_macro.hpp" + +// Register the component with class_loader. +// This acts as a sort of entry point, allowing the component to be discoverable when its library +// is being loaded into a running process. +RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_fixtures::Talker) From f1c21f31069c8419e7125290bae673f2427bb048 Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Thu, 7 Nov 2019 10:39:52 -0300 Subject: [PATCH 5/9] Address PR comments Signed-off-by: Brian Ezequiel Marchi --- ros2component/package.xml | 5 +- ros2component/test/test_cli_list.py | 53 ++++----- ros2component/test/test_cli_load.py | 108 +++++++++--------- ros2component/test/test_cli_types.py | 38 +++--- ros2component/test/test_cli_unload.py | 104 ++++++++--------- .../visibility_control.h | 58 ---------- .../CMakeLists.txt | 15 +-- .../listener_component.hpp | 14 +-- .../talker_component.hpp | 14 +-- .../visibility_control.h | 58 ++++++++++ .../package.xml | 2 +- .../src/listener_component.cpp | 8 +- .../src/talker_component.cpp | 8 +- 13 files changed, 234 insertions(+), 251 deletions(-) delete mode 100644 ros2component_fixtures/include/ros2component_fixtures/visibility_control.h rename {ros2component_fixtures => ros2component_test_fixtures}/CMakeLists.txt (73%) rename {ros2component_fixtures/include/ros2component_fixtures => ros2component_test_fixtures/include/ros2component_test_fixtures}/listener_component.hpp (70%) rename {ros2component_fixtures/include/ros2component_fixtures => ros2component_test_fixtures/include/ros2component_test_fixtures}/talker_component.hpp (72%) create mode 100644 ros2component_test_fixtures/include/ros2component_test_fixtures/visibility_control.h rename {ros2component_fixtures => ros2component_test_fixtures}/package.xml (95%) rename {ros2component_fixtures => ros2component_test_fixtures}/src/listener_component.cpp (90%) rename {ros2component_fixtures => ros2component_test_fixtures}/src/talker_component.cpp (90%) diff --git a/ros2component/package.xml b/ros2component/package.xml index ea322f9db..9821e719d 100644 --- a/ros2component/package.xml +++ b/ros2component/package.xml @@ -9,13 +9,12 @@ Michel Hidalgo Apache License 2.0 - ros2cli - ament_index_python composition_interfaces rcl_interfaces rclcpp_components rclpy + ros2cli ros2node ros2param ros2pkg @@ -25,7 +24,7 @@ ament_pep257 ament_xmllint python3-pytest - ros2component_fixtures + ros2component_test_fixtures ros_testing diff --git a/ros2component/test/test_cli_list.py b/ros2component/test/test_cli_list.py index 5973b3d78..be6e5f0bb 100644 --- a/ros2component/test/test_cli_list.py +++ b/ros2component/test/test_cli_list.py @@ -31,27 +31,17 @@ from rmw_implementation import get_available_rmw_implementations -LIST_THREE_NODES = """\ -/ComponentManager - 1 /listener - 2 /talker - 3 /talker -""" - -# TODO(BMarchi): Opensplice doesn't get along with running any cli command with ExecuteProcess, -# it just hangs there making `wait_for_timeout` fail. All tests should run fine with opensplice. @pytest.mark.rostest -@launch_testing.parametrize( - 'rmw_implementation', - [v for v in get_available_rmw_implementations() if v != 'rmw_opensplice_cpp']) +@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} component_node = Node( - package='rclcpp_components', node_executable='component_container', output='screen') + package='rclcpp_components', node_executable='component_container', output='screen', + additional_env=additional_env) listener_command_action = ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Listener'], + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Listener'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' @@ -61,7 +51,7 @@ def generate_test_description(rmw_implementation, ready_fn): on_exit=[ ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Talker'], + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' @@ -71,7 +61,7 @@ def generate_test_description(rmw_implementation, ready_fn): on_exit=[ ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Talker'], + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' @@ -94,8 +84,8 @@ def generate_test_description(rmw_implementation, ready_fn): name='daemon-start', on_exit=[ component_node, - OpaqueFunction(function=lambda context: ready_fn()), - listener_command_action + listener_command_action, + OpaqueFunction(function=lambda context: ready_fn()) ], additional_env=additional_env ) @@ -115,8 +105,8 @@ def setUpClass( rmw_implementation ): @contextlib.contextmanager - def launch_node_command(self, arguments): - node_command_action = ExecuteProcess( + def launch_component_command(self, arguments): + component_command_action = ExecuteProcess( cmd=['ros2', 'component', *arguments], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, @@ -126,25 +116,30 @@ def launch_node_command(self, arguments): output='screen' ) with launch_testing.tools.launch_process( - launch_service, node_command_action, proc_info, proc_output, + launch_service, component_command_action, proc_info, proc_output, output_filter=launch_testing_ros.tools.basic_output_filter( # ignore ros2cli daemon nodes filtered_patterns=['.*ros2cli.*'], filtered_rmw_implementation=rmw_implementation ) - ) as node_command: - yield node_command - cls.launch_node_command = launch_node_command - cls.rmw_implementation = rmw_implementation + ) as component_command: + yield component_command + cls.launch_component_command = launch_component_command @launch_testing.markers.retry_on_failure(times=5) def test_list_verb(self): - with self.launch_node_command( + with self.launch_component_command( arguments=['list']) as list_command: - assert list_command.wait_for_shutdown(timeout=5) + assert list_command.wait_for_shutdown(timeout=10) assert list_command.exit_code == launch_testing.asserts.EXIT_OK + LIST_THREE_NODES = [ + '/ComponentManager', + ' 1 /listener', + ' 2 /talker', + ' 3 /talker' + ] assert launch_testing.tools.expect_output( - expected_text=LIST_THREE_NODES, + expected_lines=LIST_THREE_NODES, text=list_command.output, - strict=True + strict=False ) diff --git a/ros2component/test/test_cli_load.py b/ros2component/test/test_cli_load.py index b7ca7adf5..272da0872 100644 --- a/ros2component/test/test_cli_load.py +++ b/ros2component/test/test_cli_load.py @@ -32,16 +32,13 @@ from rmw_implementation import get_available_rmw_implementations -# TODO(BMarchi): Opensplice doesn't get along with running any cli command with ExecuteProcess, -# it just hangs there making `wait_for_timeout` fail. All tests should run fine with opensplice. @pytest.mark.rostest -@launch_testing.parametrize( - 'rmw_implementation', - [v for v in get_available_rmw_implementations() if v != 'rmw_opensplice_cpp']) +@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} component_node = Node( - package='rclcpp_components', node_executable='component_container', output='screen') + package='rclcpp_components', node_executable='component_container', output='screen', + additional_env=additional_env) return LaunchDescription([ # Always restart daemon to isolate tests. ExecuteProcess( @@ -73,8 +70,8 @@ def setUpClass( rmw_implementation ): @contextlib.contextmanager - def launch_node_command(self, arguments): - node_command_action = ExecuteProcess( + def launch_component_command(self, arguments): + component_command_action = ExecuteProcess( cmd=['ros2', 'component', *arguments], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, @@ -84,46 +81,47 @@ def launch_node_command(self, arguments): output='screen' ) with launch_testing.tools.launch_process( - launch_service, node_command_action, proc_info, proc_output, + launch_service, component_command_action, proc_info, proc_output, output_filter=launch_testing_ros.tools.basic_output_filter( # ignore ros2cli daemon nodes filtered_patterns=['.*ros2cli.*'], filtered_rmw_implementation=rmw_implementation ) - ) as node_command: - yield node_command - cls.launch_node_command = launch_node_command + ) as component_command: + yield component_command + cls.launch_component_command = launch_component_command @launch_testing.markers.retry_on_failure(times=2) def test_load_verb(self): - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Talker']) as talker_node: - assert talker_node.wait_for_shutdown(timeout=20) - assert talker_node.exit_code == launch_testing.asserts.EXIT_OK + 'ros2component_test_fixtures', + 'ros2component_test_fixtures::Talker']) as load_command: + assert load_command.wait_for_shutdown(timeout=20) + assert load_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ "Loaded component 1 into '/ComponentManager' " "container node as '/talker'"], - text=talker_node.output, - strict=True + text=load_command.output, + strict=False ) - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'load', '/ComponentManager', - 'ros2component_fixtures', - 'ros2component_fixtures::Listener']) as listener_node: - assert listener_node.wait_for_shutdown(timeout=20) - assert listener_node.exit_code == launch_testing.asserts.EXIT_OK + 'ros2component_test_fixtures', + 'ros2component_test_fixtures::Listener']) as load_command: + assert load_command.wait_for_shutdown(timeout=20) + assert load_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ "Loaded component 2 into '/ComponentManager' " "container node as '/listener'"], - text=listener_node.output, - strict=True + text=load_command.output, + strict=False ) - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'unload', '/ComponentManager', '1']) as unload_command: assert unload_command.wait_for_shutdown(timeout=20) @@ -131,66 +129,68 @@ def test_load_verb(self): assert launch_testing.tools.expect_output( expected_lines=["Unloaded component 1 from '/ComponentManager' container"], text=unload_command.output, - strict=True + strict=False ) # Test the unique id for loaded nodes. - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Talker']) as talker_node: - assert talker_node.wait_for_shutdown(timeout=20) - assert talker_node.exit_code == launch_testing.asserts.EXIT_OK + 'ros2component_test_fixtures', + 'ros2component_test_fixtures::Talker']) as load_command: + assert load_command.wait_for_shutdown(timeout=20) + assert load_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ "Loaded component 3 into '/ComponentManager' " "container node as '/talker'"], - text=talker_node.output, - strict=True + text=load_command.output, + strict=False ) # Test we can load the same node more than once. - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Talker']) as talker_node: - assert talker_node.wait_for_shutdown(timeout=20) - assert talker_node.exit_code == launch_testing.asserts.EXIT_OK + 'ros2component_test_fixtures', + 'ros2component_test_fixtures::Talker']) as load_command: + assert load_command.wait_for_shutdown(timeout=20) + assert load_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ "Loaded component 4 into '/ComponentManager' " "container node as '/talker'"], - text=talker_node.output, - strict=True + text=load_command.output, + strict=False ) @launch_testing.markers.retry_on_failure(times=2) - def test_load_verb_nonexistent_class(self): - with self.launch_node_command( + def test_load_nonexistent_component(self): + with self.launch_component_command( arguments=[ 'load', '/ComponentManager', - 'ros2component_fixtures', - 'ros2component_fixtures::NonExistingPlugin']) as command: - assert command.wait_for_shutdown(timeout=20) - assert command.exit_code == 1 + 'ros2component_test_fixtures', + 'ros2component_test_fixtures::NonExistentComponent']) as load_command: + assert load_command.wait_for_shutdown(timeout=20) + assert load_command.exit_code == 1 assert launch_testing.tools.expect_output( expected_lines=[ 'Failed to load component: ' 'Failed to find class with the requested plugin name.'], - text=command.output, - strict=True + text=load_command.output, + strict=False ) @launch_testing.markers.retry_on_failure(times=2) - def test_load_verb_nonexistent_plugin(self): - with self.launch_node_command( + def test_load_nonexistent_plugin(self): + with self.launch_component_command( arguments=[ 'load', '/ComponentManager', - 'non_existent_plugin', 'non_existent_plugin::Test']) as command: - assert command.wait_for_shutdown(timeout=20) - assert command.exit_code == 1 + 'non_existent_plugin', 'non_existent_plugin::Test']) as load_command: + assert load_command.wait_for_shutdown(timeout=20) + assert load_command.exit_code == 1 assert launch_testing.tools.expect_output( expected_lines=[ 'Failed to load component: ' 'Could not find requested resource in ament index'], - text=command.output, - strict=True + text=load_command.output, + strict=False ) diff --git a/ros2component/test/test_cli_types.py b/ros2component/test/test_cli_types.py index d1b388428..203d3d881 100644 --- a/ros2component/test/test_cli_types.py +++ b/ros2component/test/test_cli_types.py @@ -31,19 +31,14 @@ from rmw_implementation import get_available_rmw_implementations -DEMO_NODES_TYPES = """\ -ros2component_fixtures - ros2component_fixtures::Talker - ros2component_fixtures::Listener -""" - @pytest.mark.rostest @launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} component_node = Node( - package='rclcpp_components', node_executable='component_container', output='screen') + package='rclcpp_components', node_executable='component_container', output='screen', + additional_env=additional_env) return LaunchDescription([ # Always restart daemon to isolate tests. ExecuteProcess( @@ -75,8 +70,8 @@ def setUpClass( rmw_implementation ): @contextlib.contextmanager - def launch_node_command(self, arguments): - node_command_action = ExecuteProcess( + def launch_component_command(self, arguments): + component_command_action = ExecuteProcess( cmd=['ros2', 'component', *arguments], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, @@ -86,25 +81,30 @@ def launch_node_command(self, arguments): output='screen' ) with launch_testing.tools.launch_process( - launch_service, node_command_action, proc_info, proc_output, + launch_service, component_command_action, proc_info, proc_output, output_filter=launch_testing_ros.tools.basic_output_filter( # ignore ros2cli daemon nodes filtered_patterns=['.*ros2cli.*'], filtered_rmw_implementation=rmw_implementation ) - ) as node_command: - yield node_command - cls.launch_node_command = launch_node_command + ) as component_command: + yield component_command + cls.launch_component_command = launch_component_command # Set verb tests @launch_testing.markers.retry_on_failure(times=3) def test_types_verb(self): - with self.launch_node_command( - arguments=['types']) as node_command: - assert node_command.wait_for_shutdown(timeout=20) - assert node_command.exit_code == launch_testing.asserts.EXIT_OK + with self.launch_component_command( + arguments=['types']) as component_command: + assert component_command.wait_for_shutdown(timeout=20) + assert component_command.exit_code == launch_testing.asserts.EXIT_OK + DEMO_NODES_TYPES = [ + 'ros2component_test_fixtures', + ' ros2component_test_fixtures::Talker', + ' ros2component_test_fixtures::Listener' + ] assert launch_testing.tools.expect_output( - expected_text=DEMO_NODES_TYPES, - text=node_command.output, + expected_lines=DEMO_NODES_TYPES, + text=component_command.output, strict=True ) diff --git a/ros2component/test/test_cli_unload.py b/ros2component/test/test_cli_unload.py index 5fb9938af..df42a3b4e 100644 --- a/ros2component/test/test_cli_unload.py +++ b/ros2component/test/test_cli_unload.py @@ -31,55 +31,48 @@ from rmw_implementation import get_available_rmw_implementations -NON_EXISTENT_ID = """\ -Failed to unload component 5 from '/ComponentManager' container node - No node found with unique_id: 5 -""" +NON_EXISTENT_ID = [ + "Failed to unload component 5 from '/ComponentManager' container node", + ' No node found with unique_id: 5' +] -# TODO(BMarchi): Opensplice doesn't get along with running any cli command with ExecuteProcess, -# it just hangs there making `wait_for_timeout` fail. All tests should run fine with opensplice. @pytest.mark.rostest -@launch_testing.parametrize( - 'rmw_implementation', - [v for v in get_available_rmw_implementations() if v != 'rmw_opensplice_cpp']) +@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} component_node = Node( - package='rclcpp_components', node_executable='component_container', output='screen') + package='rclcpp_components', node_executable='component_container', output='screen', + additional_env=additional_env) listener_command_action = ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Listener'], + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Listener'], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, 'PYTHONUNBUFFERED': '1' }, name='ros2component-cli', - output='screen', - on_exit=[ - ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen', - on_exit=[ - ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_fixtures', 'ros2component_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen' - ) - ] - ) - ] + output='screen' + ) + talker_one_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + talker_two_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' ) return LaunchDescription([ # Always restart daemon to isolate tests. @@ -92,8 +85,10 @@ def generate_test_description(rmw_implementation, ready_fn): name='daemon-start', on_exit=[ component_node, - OpaqueFunction(function=lambda context: ready_fn()), - listener_command_action + listener_command_action, + talker_one_action, + talker_two_action, + OpaqueFunction(function=lambda context: ready_fn()) ], additional_env=additional_env ) @@ -113,8 +108,8 @@ def setUpClass( rmw_implementation ): @contextlib.contextmanager - def launch_node_command(self, arguments): - node_command_action = ExecuteProcess( + def launch_component_command(self, arguments): + component_command_action = ExecuteProcess( cmd=['ros2', 'component', *arguments], additional_env={ 'RMW_IMPLEMENTATION': rmw_implementation, @@ -124,52 +119,51 @@ def launch_node_command(self, arguments): output='screen' ) with launch_testing.tools.launch_process( - launch_service, node_command_action, proc_info, proc_output, + launch_service, component_command_action, proc_info, proc_output, output_filter=launch_testing_ros.tools.basic_output_filter( # ignore ros2cli daemon nodes filtered_patterns=['.*ros2cli.*'], filtered_rmw_implementation=rmw_implementation ) - ) as node_command: - yield node_command - cls.launch_node_command = launch_node_command - cls.rmw_implementation = rmw_implementation + ) as component_command: + yield component_command + cls.launch_component_command = launch_component_command - @launch_testing.markers.retry_on_failure(times=4) + @launch_testing.markers.retry_on_failure(times=5) def test_unload_verb(self): - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'unload', '/ComponentManager', '1']) as unload_command: - assert unload_command.wait_for_shutdown(timeout=20) + assert unload_command.wait_for_shutdown(timeout=10) assert unload_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=["Unloaded component 1 from '/ComponentManager' container"], text=unload_command.output, - strict=True + strict=False ) @launch_testing.markers.retry_on_failure(times=4) def test_unload_verb_nonexistent_id(self): - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'unload', '/ComponentManager', '5']) as unload_command: assert unload_command.wait_for_shutdown(timeout=20) assert unload_command.exit_code == 1 assert launch_testing.tools.expect_output( - expected_text=NON_EXISTENT_ID, + expected_lines=NON_EXISTENT_ID, text=unload_command.output, - strict=True + strict=False ) @launch_testing.markers.retry_on_failure(times=4) def test_unload_verb_nonexistent_container(self): - with self.launch_node_command( + with self.launch_component_command( arguments=[ 'unload', '/NonExistentContainer', '5']) as unload_command: assert unload_command.wait_for_shutdown(timeout=20) assert unload_command.exit_code == 1 assert launch_testing.tools.expect_output( - expected_text="Unable to find container node '/NonExistentContainer'\n", + expected_lines=["Unable to find container node '/NonExistentContainer'"], text=unload_command.output, - strict=True + strict=False ) diff --git a/ros2component_fixtures/include/ros2component_fixtures/visibility_control.h b/ros2component_fixtures/include/ros2component_fixtures/visibility_control.h deleted file mode 100644 index 83cdbba8a..000000000 --- a/ros2component_fixtures/include/ros2component_fixtures/visibility_control.h +++ /dev/null @@ -1,58 +0,0 @@ -// 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. - -#ifndef ROS2COMPONENT_FIXTURES__VISIBILITY_CONTROL_H_ -#define ROS2COMPONENT_FIXTURES__VISIBILITY_CONTROL_H_ - -#ifdef __cplusplus -extern "C" -{ -#endif - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define ROS2COMPONENT_FIXTURES_EXPORT __attribute__ ((dllexport)) - #define ROS2COMPONENT_FIXTURES_IMPORT __attribute__ ((dllimport)) - #else - #define ROS2COMPONENT_FIXTURES_EXPORT __declspec(dllexport) - #define ROS2COMPONENT_FIXTURES_IMPORT __declspec(dllimport) - #endif - #ifdef ROS2COMPONENT_FIXTURES_BUILDING_DLL - #define ROS2COMPONENT_FIXTURES_PUBLIC ROS2COMPONENT_FIXTURES_EXPORT - #else - #define ROS2COMPONENT_FIXTURES_PUBLIC ROS2COMPONENT_FIXTURES_IMPORT - #endif - #define ROS2COMPONENT_FIXTURES_PUBLIC_TYPE ROS2COMPONENT_FIXTURES_PUBLIC - #define ROS2COMPONENT_FIXTURES_LOCAL -#else - #define ROS2COMPONENT_FIXTURES_EXPORT __attribute__ ((visibility("default"))) - #define ROS2COMPONENT_FIXTURES_IMPORT - #if __GNUC__ >= 4 - #define ROS2COMPONENT_FIXTURES_PUBLIC __attribute__ ((visibility("default"))) - #define ROS2COMPONENT_FIXTURES_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define ROS2COMPONENT_FIXTURES_PUBLIC - #define ROS2COMPONENT_FIXTURES_LOCAL - #endif - #define ROS2COMPONENT_FIXTURES_PUBLIC_TYPE -#endif - -#ifdef __cplusplus -} -#endif - -#endif // ROS2COMPONENT_FIXTURES__VISIBILITY_CONTROL_H_ diff --git a/ros2component_fixtures/CMakeLists.txt b/ros2component_test_fixtures/CMakeLists.txt similarity index 73% rename from ros2component_fixtures/CMakeLists.txt rename to ros2component_test_fixtures/CMakeLists.txt index ff5de6135..8f4d15e64 100644 --- a/ros2component_fixtures/CMakeLists.txt +++ b/ros2component_test_fixtures/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros2component_fixtures) +project(ros2component_test_fixtures) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -18,30 +18,25 @@ find_package(std_msgs REQUIRED) include_directories(include) -# create ament index resource which references the libraries in the binary dir -set(node_plugins "") - add_library(talker_component SHARED src/talker_component.cpp) target_compile_definitions(talker_component - PRIVATE "ROS2COMPONENT_FIXTURES_BUILDING_DLL") + PRIVATE "ros2component_test_fixtures_BUILDING_DLL") ament_target_dependencies(talker_component "rclcpp" "rclcpp_components" "std_msgs") -rclcpp_components_register_nodes(talker_component "ros2component_fixtures::Talker") -set(node_plugins "${node_plugins}ros2component_fixtures::Talker;$\n") +rclcpp_components_register_nodes(talker_component "ros2component_test_fixtures::Talker") add_library(listener_component SHARED src/listener_component.cpp) target_compile_definitions(listener_component - PRIVATE "ROS2COMPONENT_FIXTURES_BUILDING_DLL") + PRIVATE "ros2component_test_fixtures_BUILDING_DLL") ament_target_dependencies(listener_component "rclcpp" "rclcpp_components" "std_msgs") -rclcpp_components_register_nodes(listener_component "ros2component_fixtures::Listener") -set(node_plugins "${node_plugins}ros2component_fixtures::Listener;$\n") +rclcpp_components_register_nodes(listener_component "ros2component_test_fixtures::Listener") # since the package installs libraries without exporting them # it needs to make sure that the library path is being exported diff --git a/ros2component_fixtures/include/ros2component_fixtures/listener_component.hpp b/ros2component_test_fixtures/include/ros2component_test_fixtures/listener_component.hpp similarity index 70% rename from ros2component_fixtures/include/ros2component_fixtures/listener_component.hpp rename to ros2component_test_fixtures/include/ros2component_test_fixtures/listener_component.hpp index bd6d2b7d0..72dc01fd7 100644 --- a/ros2component_fixtures/include/ros2component_fixtures/listener_component.hpp +++ b/ros2component_test_fixtures/include/ros2component_test_fixtures/listener_component.hpp @@ -12,26 +12,26 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS2COMPONENT_FIXTURES__LISTENER_COMPONENT_HPP_ -#define ROS2COMPONENT_FIXTURES__LISTENER_COMPONENT_HPP_ +#ifndef ROS2COMPONENT_TEST_FIXTURES__LISTENER_COMPONENT_HPP_ +#define ROS2COMPONENT_TEST_FIXTURES__LISTENER_COMPONENT_HPP_ -#include "ros2component_fixtures/visibility_control.h" +#include "ros2component_test_fixtures/visibility_control.h" #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" -namespace ros2component_fixtures +namespace ros2component_test_fixtures { class Listener : public rclcpp::Node { public: - ROS2COMPONENT_FIXTURES_PUBLIC + ROS2COMPONENT_TEST_FIXTURES_PUBLIC explicit Listener(const rclcpp::NodeOptions & options); private: rclcpp::Subscription::SharedPtr sub_; }; -} // namespace ros2component_fixtures +} // namespace ros2component_test_fixtures -#endif // ROS2COMPONENT_FIXTURES__LISTENER_COMPONENT_HPP_ +#endif // ROS2COMPONENT_TEST_FIXTURES__LISTENER_COMPONENT_HPP_ diff --git a/ros2component_fixtures/include/ros2component_fixtures/talker_component.hpp b/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp similarity index 72% rename from ros2component_fixtures/include/ros2component_fixtures/talker_component.hpp rename to ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp index fdc07a45b..26f2ecc67 100644 --- a/ros2component_fixtures/include/ros2component_fixtures/talker_component.hpp +++ b/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS2COMPONENT_FIXTURES__TALKER_COMPONENT_HPP_ -#define ROS2COMPONENT_FIXTURES__TALKER_COMPONENT_HPP_ +#ifndef ROS2COMPONENT_TEST_FIXTURES__TALKER_COMPONENT_HPP_ +#define ROS2COMPONENT_TEST_FIXTURES__TALKER_COMPONENT_HPP_ -#include "ros2component_fixtures/visibility_control.h" +#include "ros2component_test_fixtures/visibility_control.h" #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" -namespace ros2component_fixtures +namespace ros2component_test_fixtures { class Talker : public rclcpp::Node { public: - ROS2COMPONENT_FIXTURES_PUBLIC + ROS2COMPONENT_TEST_FIXTURES_PUBLIC explicit Talker(const rclcpp::NodeOptions & options); protected: @@ -37,6 +37,6 @@ class Talker : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_; }; -} // namespace ros2component_fixtures +} // namespace ros2component_test_fixtures -#endif // ROS2COMPONENT_FIXTURES__TALKER_COMPONENT_HPP_ +#endif // ROS2COMPONENT_TEST_FIXTURES__TALKER_COMPONENT_HPP_ diff --git a/ros2component_test_fixtures/include/ros2component_test_fixtures/visibility_control.h b/ros2component_test_fixtures/include/ros2component_test_fixtures/visibility_control.h new file mode 100644 index 000000000..739f9c929 --- /dev/null +++ b/ros2component_test_fixtures/include/ros2component_test_fixtures/visibility_control.h @@ -0,0 +1,58 @@ +// 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. + +#ifndef ROS2COMPONENT_TEST_FIXTURES__VISIBILITY_CONTROL_H_ +#define ROS2COMPONENT_TEST_FIXTURES__VISIBILITY_CONTROL_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROS2COMPONENT_TEST_FIXTURES_EXPORT __attribute__ ((dllexport)) + #define ROS2COMPONENT_TEST_FIXTURES_IMPORT __attribute__ ((dllimport)) + #else + #define ROS2COMPONENT_TEST_FIXTURES_EXPORT __declspec(dllexport) + #define ROS2COMPONENT_TEST_FIXTURES_IMPORT __declspec(dllimport) + #endif + #ifdef ROS2COMPONENT_TEST_FIXTURES_BUILDING_DLL + #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC ROS2COMPONENT_TEST_FIXTURES_EXPORT + #else + #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC ROS2COMPONENT_TEST_FIXTURES_IMPORT + #endif + #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC_TYPE ROS2COMPONENT_TEST_FIXTURES_PUBLIC + #define ROS2COMPONENT_TEST_FIXTURES_LOCAL +#else + #define ROS2COMPONENT_TEST_FIXTURES_EXPORT __attribute__ ((visibility("default"))) + #define ROS2COMPONENT_TEST_FIXTURES_IMPORT + #if __GNUC__ >= 4 + #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC __attribute__ ((visibility("default"))) + #define ROS2COMPONENT_TEST_FIXTURES_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC + #define ROS2COMPONENT_TEST_FIXTURES_LOCAL + #endif + #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC_TYPE +#endif + +#ifdef __cplusplus +} +#endif + +#endif // ROS2COMPONENT_TEST_FIXTURES__VISIBILITY_CONTROL_H_ diff --git a/ros2component_fixtures/package.xml b/ros2component_test_fixtures/package.xml similarity index 95% rename from ros2component_fixtures/package.xml rename to ros2component_test_fixtures/package.xml index bfd16b8bf..6cacada7f 100644 --- a/ros2component_fixtures/package.xml +++ b/ros2component_test_fixtures/package.xml @@ -1,7 +1,7 @@ - ros2component_fixtures + ros2component_test_fixtures 0.1.0 Examples for ros2component cli Dirk Thomas diff --git a/ros2component_fixtures/src/listener_component.cpp b/ros2component_test_fixtures/src/listener_component.cpp similarity index 90% rename from ros2component_fixtures/src/listener_component.cpp rename to ros2component_test_fixtures/src/listener_component.cpp index 911e3bf56..3f0bf1e80 100644 --- a/ros2component_fixtures/src/listener_component.cpp +++ b/ros2component_test_fixtures/src/listener_component.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ros2component_fixtures/listener_component.hpp" +#include "ros2component_test_fixtures/listener_component.hpp" #include #include @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" -namespace ros2component_fixtures +namespace ros2component_test_fixtures { // Create a Listener "component" that subclasses the generic rclcpp::Node base class. @@ -45,11 +45,11 @@ Listener::Listener(const rclcpp::NodeOptions & options) sub_ = create_subscription("chatter", 10, callback); } -} // namespace ros2component_fixtures +} // namespace ros2component_test_fixtures #include "rclcpp_components/register_node_macro.hpp" // Register the component with class_loader. // This acts as a sort of entry point, allowing the component to be discoverable when its library // is being loaded into a running process. -RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_fixtures::Listener) +RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_test_fixtures::Listener) diff --git a/ros2component_fixtures/src/talker_component.cpp b/ros2component_test_fixtures/src/talker_component.cpp similarity index 90% rename from ros2component_fixtures/src/talker_component.cpp rename to ros2component_test_fixtures/src/talker_component.cpp index 7d08ef876..5dd893470 100644 --- a/ros2component_fixtures/src/talker_component.cpp +++ b/ros2component_test_fixtures/src/talker_component.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ros2component_fixtures/talker_component.hpp" +#include "ros2component_test_fixtures/talker_component.hpp" #include #include @@ -24,7 +24,7 @@ using namespace std::chrono_literals; -namespace ros2component_fixtures +namespace ros2component_test_fixtures { // Create a Talker "component" that subclasses the generic rclcpp::Node base class. @@ -52,11 +52,11 @@ void Talker::on_timer() pub_->publish(std::move(msg)); } -} // namespace ros2component_fixtures +} // namespace ros2component_test_fixtures #include "rclcpp_components/register_node_macro.hpp" // Register the component with class_loader. // This acts as a sort of entry point, allowing the component to be discoverable when its library // is being loaded into a running process. -RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_fixtures::Talker) +RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_test_fixtures::Talker) From 3a440c421bf4cb4da41fc4cb8e12b1210a73f6ce Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Fri, 8 Nov 2019 10:18:12 -0300 Subject: [PATCH 6/9] Modify talker Signed-off-by: Brian Ezequiel Marchi --- ros2component/test/test_cli_list.py | 18 +++++++++--------- .../talker_component.hpp | 5 ----- .../src/talker_component.cpp | 10 ++-------- 3 files changed, 11 insertions(+), 22 deletions(-) diff --git a/ros2component/test/test_cli_list.py b/ros2component/test/test_cli_list.py index be6e5f0bb..4d486b95e 100644 --- a/ros2component/test/test_cli_list.py +++ b/ros2component/test/test_cli_list.py @@ -18,6 +18,7 @@ from launch import LaunchDescription from launch.actions import ExecuteProcess from launch.actions import OpaqueFunction +from launch.actions import TimerAction from launch_ros.actions import Node @@ -84,7 +85,7 @@ def generate_test_description(rmw_implementation, ready_fn): name='daemon-start', on_exit=[ component_node, - listener_command_action, + TimerAction(period=3.0, actions=[listener_command_action]), OpaqueFunction(function=lambda context: ready_fn()) ], additional_env=additional_env @@ -130,16 +131,15 @@ def launch_component_command(self, arguments): def test_list_verb(self): with self.launch_component_command( arguments=['list']) as list_command: - assert list_command.wait_for_shutdown(timeout=10) + assert list_command.wait_for_shutdown(timeout=20) assert list_command.exit_code == launch_testing.asserts.EXIT_OK - LIST_THREE_NODES = [ - '/ComponentManager', - ' 1 /listener', - ' 2 /talker', - ' 3 /talker' - ] assert launch_testing.tools.expect_output( - expected_lines=LIST_THREE_NODES, + expected_lines=[ + '/ComponentManager', + ' 1 /listener', + ' 2 /talker', + ' 3 /talker' + ], text=list_command.output, strict=False ) diff --git a/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp b/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp index 26f2ecc67..8ca6fc880 100644 --- a/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp +++ b/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp @@ -28,13 +28,8 @@ class Talker : public rclcpp::Node ROS2COMPONENT_TEST_FIXTURES_PUBLIC explicit Talker(const rclcpp::NodeOptions & options); -protected: - void on_timer(); - private: - size_t count_; rclcpp::Publisher::SharedPtr pub_; - rclcpp::TimerBase::SharedPtr timer_; }; } // namespace ros2component_test_fixtures diff --git a/ros2component_test_fixtures/src/talker_component.cpp b/ros2component_test_fixtures/src/talker_component.cpp index 5dd893470..cbac9bd01 100644 --- a/ros2component_test_fixtures/src/talker_component.cpp +++ b/ros2component_test_fixtures/src/talker_component.cpp @@ -31,19 +31,13 @@ namespace ros2component_test_fixtures // Components get built into shared libraries and as such do not write their own main functions. // The process using the component's shared library will instantiate the class as a ROS node. Talker::Talker(const rclcpp::NodeOptions & options) -: Node("talker", options), count_(0) +: Node("talker", options) { // Create a publisher of "std_mgs/String" messages on the "chatter" topic. pub_ = create_publisher("chatter", 10); - // Use a timer to schedule periodic message publishing. - timer_ = create_wall_timer(1s, std::bind(&Talker::on_timer, this)); -} - -void Talker::on_timer() -{ auto msg = std::make_unique(); - msg->data = "Hello World: " + std::to_string(++count_); + msg->data = "Hello World"; RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str()); std::flush(std::cout); From 03f74e6ff5b718202628c67765bb55d69fd56752 Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Mon, 11 Nov 2019 14:17:42 -0300 Subject: [PATCH 7/9] Increase retries for list and improve load verb test Signed-off-by: Brian Ezequiel Marchi --- ros2component/test/test_cli_list.py | 4 ++-- ros2component/test/test_cli_load.py | 27 ++++++++++++++++++++++++--- 2 files changed, 26 insertions(+), 5 deletions(-) diff --git a/ros2component/test/test_cli_list.py b/ros2component/test/test_cli_list.py index 4d486b95e..6f0c7c02c 100644 --- a/ros2component/test/test_cli_list.py +++ b/ros2component/test/test_cli_list.py @@ -127,11 +127,11 @@ def launch_component_command(self, arguments): yield component_command cls.launch_component_command = launch_component_command - @launch_testing.markers.retry_on_failure(times=5) + @launch_testing.markers.retry_on_failure(times=10) def test_list_verb(self): with self.launch_component_command( arguments=['list']) as list_command: - assert list_command.wait_for_shutdown(timeout=20) + assert list_command.wait_for_shutdown(timeout=30) assert list_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ diff --git a/ros2component/test/test_cli_load.py b/ros2component/test/test_cli_load.py index 272da0872..ddd2c31bb 100644 --- a/ros2component/test/test_cli_load.py +++ b/ros2component/test/test_cli_load.py @@ -13,6 +13,7 @@ # limitations under the License. import contextlib +import functools import unittest from launch import LaunchDescription @@ -37,8 +38,9 @@ def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} component_node = Node( - package='rclcpp_components', node_executable='component_container', output='screen', - additional_env=additional_env) + package='rclcpp_components', node_executable='component_container', output='own_log', + output_format='{line}', additional_env=additional_env, + name='container_' + rmw_implementation) return LaunchDescription([ # Always restart daemon to isolate tests. ExecuteProcess( @@ -67,7 +69,8 @@ def setUpClass( launch_service, proc_info, proc_output, - rmw_implementation + rmw_implementation, + component_node ): @contextlib.contextmanager def launch_component_command(self, arguments): @@ -90,6 +93,14 @@ def launch_component_command(self, arguments): ) as component_command: yield component_command cls.launch_component_command = launch_component_command + cls.component_node = launch_testing.tools.ProcessProxy( + component_node, proc_info, proc_output, + output_filter=launch_testing_ros.tools.basic_output_filter( + # ignore ros2cli daemon nodes + filtered_patterns=['.*ros2cli.*'], + filtered_rmw_implementation=rmw_implementation + ) + ) @launch_testing.markers.retry_on_failure(times=2) def test_load_verb(self): @@ -99,6 +110,11 @@ def test_load_verb(self): 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker']) as load_command: assert load_command.wait_for_shutdown(timeout=20) + assert self.component_node.wait_for_output(functools.partial( + launch_testing.tools.expect_output, expected_lines=[ + "[INFO] [talker]: Publishing: 'Hello World'" + ], strict=False + ), timeout=10) assert load_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ @@ -153,6 +169,11 @@ def test_load_verb(self): 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker']) as load_command: assert load_command.wait_for_shutdown(timeout=20) + assert self.component_node.wait_for_output(functools.partial( + launch_testing.tools.expect_output, expected_lines=[ + "[INFO] [talker]: Publishing: 'Hello World'" + ] * 3, strict=False + ), timeout=10) assert load_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ From 1b0461ac6e9e4650ce63e3a6401612ea6469c473 Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Mon, 11 Nov 2019 14:26:47 -0300 Subject: [PATCH 8/9] Improve unload verb test Signed-off-by: Brian Ezequiel Marchi --- ros2component/test/test_cli_unload.py | 53 ++++++++++++++------------- 1 file changed, 28 insertions(+), 25 deletions(-) diff --git a/ros2component/test/test_cli_unload.py b/ros2component/test/test_cli_unload.py index df42a3b4e..16893286d 100644 --- a/ros2component/test/test_cli_unload.py +++ b/ros2component/test/test_cli_unload.py @@ -18,6 +18,7 @@ from launch import LaunchDescription from launch.actions import ExecuteProcess from launch.actions import OpaqueFunction +from launch.actions import TimerAction from launch_ros.actions import Node @@ -52,27 +53,31 @@ def generate_test_description(rmw_implementation, ready_fn): 'PYTHONUNBUFFERED': '1' }, name='ros2component-cli', - output='screen' - ) - talker_one_action = ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen' - ) - talker_two_action = ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen' + output='screen', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen', + on_exit=[ + ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + ] + ) + ] ) return LaunchDescription([ # Always restart daemon to isolate tests. @@ -85,9 +90,7 @@ def generate_test_description(rmw_implementation, ready_fn): name='daemon-start', on_exit=[ component_node, - listener_command_action, - talker_one_action, - talker_two_action, + TimerAction(period=3.0, actions=[listener_command_action]), OpaqueFunction(function=lambda context: ready_fn()) ], additional_env=additional_env @@ -129,7 +132,7 @@ def launch_component_command(self, arguments): yield component_command cls.launch_component_command = launch_component_command - @launch_testing.markers.retry_on_failure(times=5) + @launch_testing.markers.retry_on_failure(times=10) def test_unload_verb(self): with self.launch_component_command( arguments=[ From e0b2e920a6cd0050963f5534d3aa5fce0d1eaded Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Mon, 11 Nov 2019 15:59:45 -0300 Subject: [PATCH 9/9] Address PR comments Signed-off-by: Brian Ezequiel Marchi --- ros2component/test/test_cli_list.py | 56 ++++++++++++++------------- ros2component/test/test_cli_load.py | 30 +++++++------- ros2component/test/test_cli_types.py | 33 +++++----------- ros2component/test/test_cli_unload.py | 54 +++++++++++++------------- 4 files changed, 82 insertions(+), 91 deletions(-) diff --git a/ros2component/test/test_cli_list.py b/ros2component/test/test_cli_list.py index 6f0c7c02c..0fc6d218a 100644 --- a/ros2component/test/test_cli_list.py +++ b/ros2component/test/test_cli_list.py @@ -37,9 +37,33 @@ @launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} - component_node = Node( + container_node_action = Node( package='rclcpp_components', node_executable='component_container', output='screen', additional_env=additional_env) + + talker_two_command_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + + talker_one_command_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen', + on_exit=[talker_two_command_action] + ) + listener_command_action = ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', 'ros2component_test_fixtures', 'ros2component_test_fixtures::Listener'], @@ -49,31 +73,9 @@ def generate_test_description(rmw_implementation, ready_fn): }, name='ros2component-cli', output='screen', - on_exit=[ - ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen', - on_exit=[ - ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen' - ) - ] - ) - ] + on_exit=[talker_one_command_action] ) + return LaunchDescription([ # Always restart daemon to isolate tests. ExecuteProcess( @@ -84,7 +86,7 @@ def generate_test_description(rmw_implementation, ready_fn): cmd=['ros2', 'daemon', 'start'], name='daemon-start', on_exit=[ - component_node, + container_node_action, TimerAction(period=3.0, actions=[listener_command_action]), OpaqueFunction(function=lambda context: ready_fn()) ], @@ -131,7 +133,7 @@ def launch_component_command(self, arguments): def test_list_verb(self): with self.launch_component_command( arguments=['list']) as list_command: - assert list_command.wait_for_shutdown(timeout=30) + assert list_command.wait_for_shutdown(timeout=10) assert list_command.exit_code == launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ diff --git a/ros2component/test/test_cli_load.py b/ros2component/test/test_cli_load.py index ddd2c31bb..26e395456 100644 --- a/ros2component/test/test_cli_load.py +++ b/ros2component/test/test_cli_load.py @@ -37,7 +37,7 @@ @launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} - component_node = Node( + container_node_action = Node( package='rclcpp_components', node_executable='component_container', output='own_log', output_format='{line}', additional_env=additional_env, name='container_' + rmw_implementation) @@ -51,7 +51,7 @@ def generate_test_description(rmw_implementation, ready_fn): cmd=['ros2', 'daemon', 'start'], name='daemon-start', on_exit=[ - component_node, + container_node_action, OpaqueFunction(function=lambda context: ready_fn()) ], additional_env=additional_env @@ -70,7 +70,7 @@ def setUpClass( proc_info, proc_output, rmw_implementation, - component_node + container_node_action ): @contextlib.contextmanager def launch_component_command(self, arguments): @@ -93,8 +93,8 @@ def launch_component_command(self, arguments): ) as component_command: yield component_command cls.launch_component_command = launch_component_command - cls.component_node = launch_testing.tools.ProcessProxy( - component_node, proc_info, proc_output, + cls.container_node_action = launch_testing.tools.ProcessProxy( + container_node_action, proc_info, proc_output, output_filter=launch_testing_ros.tools.basic_output_filter( # ignore ros2cli daemon nodes filtered_patterns=['.*ros2cli.*'], @@ -110,19 +110,19 @@ def test_load_verb(self): 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker']) as load_command: assert load_command.wait_for_shutdown(timeout=20) - assert self.component_node.wait_for_output(functools.partial( + assert load_command.exit_code == launch_testing.asserts.EXIT_OK + assert launch_testing.tools.expect_output( + expected_lines=[ + "Loaded component 1 into '/ComponentManager' " + "container node as '/talker'"], + text=load_command.output, + strict=False + ) + assert self.container_node_action.wait_for_output(functools.partial( launch_testing.tools.expect_output, expected_lines=[ "[INFO] [talker]: Publishing: 'Hello World'" ], strict=False ), timeout=10) - assert load_command.exit_code == launch_testing.asserts.EXIT_OK - assert launch_testing.tools.expect_output( - expected_lines=[ - "Loaded component 1 into '/ComponentManager' " - "container node as '/talker'"], - text=load_command.output, - strict=False - ) with self.launch_component_command( arguments=[ 'load', '/ComponentManager', @@ -169,7 +169,7 @@ def test_load_verb(self): 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker']) as load_command: assert load_command.wait_for_shutdown(timeout=20) - assert self.component_node.wait_for_output(functools.partial( + assert self.container_node_action.wait_for_output(functools.partial( launch_testing.tools.expect_output, expected_lines=[ "[INFO] [talker]: Publishing: 'Hello World'" ] * 3, strict=False diff --git a/ros2component/test/test_cli_types.py b/ros2component/test/test_cli_types.py index 203d3d881..e96b8c40c 100644 --- a/ros2component/test/test_cli_types.py +++ b/ros2component/test/test_cli_types.py @@ -19,13 +19,10 @@ from launch.actions import ExecuteProcess from launch.actions import OpaqueFunction -from launch_ros.actions import Node - import launch_testing import launch_testing.asserts import launch_testing.markers import launch_testing.tools -import launch_testing_ros.tools import pytest @@ -34,11 +31,8 @@ @pytest.mark.rostest @launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) +@launch_testing.markers.keep_alive def generate_test_description(rmw_implementation, ready_fn): - additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} - component_node = Node( - package='rclcpp_components', node_executable='component_container', output='screen', - additional_env=additional_env) return LaunchDescription([ # Always restart daemon to isolate tests. ExecuteProcess( @@ -49,14 +43,13 @@ def generate_test_description(rmw_implementation, ready_fn): cmd=['ros2', 'daemon', 'start'], name='daemon-start', on_exit=[ - component_node, OpaqueFunction(function=lambda context: ready_fn()) ], - additional_env=additional_env + additional_env={'RMW_IMPLEMENTATION': rmw_implementation} ) ] - ), - ]), locals() + ) + ]) class TestROS2ComponentTypesCLI(unittest.TestCase): @@ -81,12 +74,7 @@ def launch_component_command(self, arguments): output='screen' ) with launch_testing.tools.launch_process( - launch_service, component_command_action, proc_info, proc_output, - output_filter=launch_testing_ros.tools.basic_output_filter( - # ignore ros2cli daemon nodes - filtered_patterns=['.*ros2cli.*'], - filtered_rmw_implementation=rmw_implementation - ) + launch_service, component_command_action, proc_info, proc_output ) as component_command: yield component_command cls.launch_component_command = launch_component_command @@ -98,13 +86,12 @@ def test_types_verb(self): arguments=['types']) as component_command: assert component_command.wait_for_shutdown(timeout=20) assert component_command.exit_code == launch_testing.asserts.EXIT_OK - DEMO_NODES_TYPES = [ - 'ros2component_test_fixtures', - ' ros2component_test_fixtures::Talker', - ' ros2component_test_fixtures::Listener' - ] assert launch_testing.tools.expect_output( - expected_lines=DEMO_NODES_TYPES, + expected_lines=[ + 'ros2component_test_fixtures', + ' ros2component_test_fixtures::Talker', + ' ros2component_test_fixtures::Listener' + ], text=component_command.output, strict=True ) diff --git a/ros2component/test/test_cli_unload.py b/ros2component/test/test_cli_unload.py index 16893286d..284671dc2 100644 --- a/ros2component/test/test_cli_unload.py +++ b/ros2component/test/test_cli_unload.py @@ -42,9 +42,33 @@ @launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation, ready_fn): additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} - component_node = Node( + container_node_action = Node( package='rclcpp_components', node_executable='component_container', output='screen', additional_env=additional_env) + + talker_two_command_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen' + ) + + talker_one_command_action = ExecuteProcess( + cmd=['ros2', 'component', 'load', '/ComponentManager', + 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2component-cli', + output='screen', + on_exit=[talker_two_command_action] + ) + listener_command_action = ExecuteProcess( cmd=['ros2', 'component', 'load', '/ComponentManager', 'ros2component_test_fixtures', 'ros2component_test_fixtures::Listener'], @@ -54,31 +78,9 @@ def generate_test_description(rmw_implementation, ready_fn): }, name='ros2component-cli', output='screen', - on_exit=[ - ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen', - on_exit=[ - ExecuteProcess( - cmd=['ros2', 'component', 'load', '/ComponentManager', - 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'], - additional_env={ - 'RMW_IMPLEMENTATION': rmw_implementation, - 'PYTHONUNBUFFERED': '1' - }, - name='ros2component-cli', - output='screen' - ) - ] - ) - ] + on_exit=[talker_one_command_action] ) + return LaunchDescription([ # Always restart daemon to isolate tests. ExecuteProcess( @@ -89,7 +91,7 @@ def generate_test_description(rmw_implementation, ready_fn): cmd=['ros2', 'daemon', 'start'], name='daemon-start', on_exit=[ - component_node, + container_node_action, TimerAction(period=3.0, actions=[listener_command_action]), OpaqueFunction(function=lambda context: ready_fn()) ],