From f988fc94833a03b8bf2b5a9e6c5ea658559b4213 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 31 Aug 2021 16:50:38 -0700 Subject: [PATCH 01/13] added helloworld examples, README Signed-off-by: Aditya Pande --- launch_testing_ros/examples/README.rst | 20 ++++++ .../examples/check_msgs_launch_test.py | 58 +++++++++++++++++ .../examples/check_node_launch_test.py | 51 +++++++++++++++ .../examples/hello_world_launch_test.py | 29 +++++++++ .../examples/set_param_launch_test.py | 63 +++++++++++++++++++ 5 files changed, 221 insertions(+) create mode 100644 launch_testing_ros/examples/README.rst create mode 100644 launch_testing_ros/examples/check_msgs_launch_test.py create mode 100644 launch_testing_ros/examples/check_node_launch_test.py create mode 100644 launch_testing_ros/examples/hello_world_launch_test.py create mode 100644 launch_testing_ros/examples/set_param_launch_test.py diff --git a/launch_testing_ros/examples/README.rst b/launch_testing_ros/examples/README.rst new file mode 100644 index 00000000..f92b0081 --- /dev/null +++ b/launch_testing_ros/examples/README.rst @@ -0,0 +1,20 @@ +Launch testing examples +======================= + +Overview +-------- + +This directory contains examples to help the user get an idea of how to use ``launch_testing`` to write their own test cases. It contains the following examples : + +* ``hello_world_launch_test.py`` : Demonstrates basic usage and code flow +* ``check_node_launch_test.py`` : There might be situations where nodes, once launched, take some time to actually start and we need to wait for the node to start to perform some action. We can simulate this using ``launch.actions.TimerAction``. This example shows one way to detect when a node has been launched. We delay the launch by 5 seconds, and wait for the node to start with a timeout of 8 seconds. +* ``check_msgs_launch_test.py`` : Consider a problem statement where you need to launch a node and check if messages are published on a particular topic. This example demonstrates how to do that, using the talker node from ``demo_nodes_cpp`` package. It uses the ``Event`` object to end the test as soon as the first message is received on the chatter topic, with a timeout of 5 seconds. It is recommended to keep the tests as short as possible. +* ``set_param_launch_test.py`` : Launch a node, set a parameter in it and check if that was successful. + +More ``launch_testing`` examples which are not RS specific are available `here `_. +* ``good_proc_launch_test.py`` : TODO : Add description +* ``parameters_launch_test.py`` : TODO : Add desscription +* ``ready_action_test.py``: TODO : Add description +* ``terminating_proc_launch_test.py``: TODO : Add description +* ``args_launch_test.py``: TODO : Add description +* ``context_launch_test.py``: TODO : Add description diff --git a/launch_testing_ros/examples/check_msgs_launch_test.py b/launch_testing_ros/examples/check_msgs_launch_test.py new file mode 100644 index 00000000..e848a96b --- /dev/null +++ b/launch_testing_ros/examples/check_msgs_launch_test.py @@ -0,0 +1,58 @@ +from threading import Event, Thread +import unittest + +import launch +import launch.actions +import launch_ros.actions +import launch_testing.actions +import pytest +import rclpy +from rclpy.node import Node +from std_msgs.msg import String + + +@pytest.mark.launch_test +def generate_test_description(): + return launch.LaunchDescription([ + launch_ros.actions.Node( + package='demo_nodes_cpp', + executable='talker', + name='demo_node_1', + ), + + launch_testing.actions.ReadyToTest() + ]) + + +class TestFixture(unittest.TestCase): + + def test_check_if_msgs_published(self, proc_output): + rclpy.init() + node = MakeTestNode('test_node') + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=5.0) + assert msgs_received_flag, 'Did not receive msgs !' + rclpy.shutdown() + + +class MakeTestNode(Node): + + def __init__(self, name='test_node'): + super().__init__(name) + self.msg_event_object = Event() + + def start_subscriber(self): + # Create a subscriber + self.subscription = self.create_subscription( + String, + 'chatter', + self.subscriber_callback, + 10 + ) + + # Add a spin thread + self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def subscriber_callback(self, data): + self.msg_event_object.set() diff --git a/launch_testing_ros/examples/check_node_launch_test.py b/launch_testing_ros/examples/check_node_launch_test.py new file mode 100644 index 00000000..51fe7bd2 --- /dev/null +++ b/launch_testing_ros/examples/check_node_launch_test.py @@ -0,0 +1,51 @@ +import time +import unittest + +import launch +import launch.actions +import launch_ros.actions +import launch_testing.actions +import pytest +import rclpy +from rclpy.node import Node + + +@pytest.mark.launch_test +def generate_test_description(): + return launch.LaunchDescription([ + launch.actions.TimerAction( + period=5.0, + actions=[ + launch_ros.actions.Node( + package='demo_nodes_cpp', + executable='talker', + name='demo_node_1', + ) + ]), + launch_testing.actions.ReadyToTest() + ]) + + +class TestFixture(unittest.TestCase): + + def test_node_start(self, proc_output): + rclpy.init() + node = MakeTestNode('test_node') + assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !' + rclpy.shutdown() + + +class MakeTestNode(Node): + + def __init__(self, name='test_node'): + super().__init__(name) + + def wait_for_node(self, node_name, timeout=8.0): + start = time.time() + flag = False + print('Waiting for node...') + while time.time() - start < timeout and not flag: + flag = node_name in self.get_node_names() + time.sleep(0.1) + + return flag diff --git a/launch_testing_ros/examples/hello_world_launch_test.py b/launch_testing_ros/examples/hello_world_launch_test.py new file mode 100644 index 00000000..3cd68d77 --- /dev/null +++ b/launch_testing_ros/examples/hello_world_launch_test.py @@ -0,0 +1,29 @@ +import unittest + +import launch +import launch.actions +import launch_testing.actions +import pytest + + +@pytest.mark.launch_test +def generate_test_description(): + return launch.LaunchDescription([ + launch.actions.ExecuteProcess( + cmd=['echo', 'hello_world'] + ), + launch_testing.actions.ReadyToTest() + ]) + + +class TestHelloWorldProcess(unittest.TestCase): + + def test_read_stdout(self, proc_output): + proc_output.assertWaitFor('hello_world', timeout=10, stream='stdout') + + +@launch_testing.post_shutdown_test() +class TestHelloWorldShutdown(unittest.TestCase): + + def test_exit_codes(self, proc_info): + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/launch_testing_ros/examples/set_param_launch_test.py b/launch_testing_ros/examples/set_param_launch_test.py new file mode 100644 index 00000000..a7f07112 --- /dev/null +++ b/launch_testing_ros/examples/set_param_launch_test.py @@ -0,0 +1,63 @@ +import unittest + +import launch +import launch.actions +import launch_ros.actions +import launch_testing.actions +import pytest +from rcl_interfaces.msg import Parameter, ParameterType +from rcl_interfaces.srv import SetParameters +import rclpy +from rclpy.node import Node + + +@pytest.mark.launch_test +def generate_test_description(): + return launch.LaunchDescription([ + launch_ros.actions.Node( + package='demo_nodes_cpp', + executable='parameter_blackboard', + name='demo_node_1', + ), + launch_testing.actions.ReadyToTest() + ]) + + +class TestFixture(unittest.TestCase): + + def test_set_parameter(self, proc_output): + rclpy.init() + node = MakeTestNode('test_node') + response = node.set_parameter(state=True) + assert response.successful, 'Could not set parameter!' + rclpy.shutdown() + + +class MakeTestNode(Node): + + def __init__(self, name='test_node'): + super().__init__(name) + + def set_parameter(self, state=True, timeout=5.0): + parameter = Parameter() + parameter.name = 'demo_parameter_1' + parameter.value.bool_value = state + parameter.value.type = ParameterType.PARAMETER_BOOL + parameters = [parameter] + + client = self.create_client(SetParameters, 'demo_node_1/set_parameters') + ready = client.wait_for_service(timeout_sec=5.0) + if not ready: + raise RuntimeError('Wait for service timed out') + + request = SetParameters.Request() + request.parameters = parameters + future = client.call_async(request) + rclpy.spin_until_future_complete(self, future) + + response = future.result() + if response is None: + e = future.exception() + raise RuntimeError( + f"Exception while calling service of node 'demo_node_1': {e}") + return response.results[0] From e5b99d4707bbd01d40d2e891ff2892b4364751ac Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 31 Aug 2021 16:56:11 -0700 Subject: [PATCH 02/13] README fix Signed-off-by: Aditya Pande --- launch_testing_ros/examples/README.rst | 1 + 1 file changed, 1 insertion(+) diff --git a/launch_testing_ros/examples/README.rst b/launch_testing_ros/examples/README.rst index f92b0081..b8cb8c23 100644 --- a/launch_testing_ros/examples/README.rst +++ b/launch_testing_ros/examples/README.rst @@ -12,6 +12,7 @@ This directory contains examples to help the user get an idea of how to use ``la * ``set_param_launch_test.py`` : Launch a node, set a parameter in it and check if that was successful. More ``launch_testing`` examples which are not RS specific are available `here `_. + * ``good_proc_launch_test.py`` : TODO : Add description * ``parameters_launch_test.py`` : TODO : Add desscription * ``ready_action_test.py``: TODO : Add description From 65802d21bf783ac914c0e101915aecfe7a18b31c Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 31 Aug 2021 17:20:36 -0700 Subject: [PATCH 03/13] Copyright header added Signed-off-by: Aditya Pande --- .../examples/check_msgs_launch_test.py | 14 ++++++++++++++ .../examples/check_node_launch_test.py | 14 ++++++++++++++ .../examples/hello_world_launch_test.py | 14 ++++++++++++++ .../examples/set_param_launch_test.py | 14 ++++++++++++++ 4 files changed, 56 insertions(+) diff --git a/launch_testing_ros/examples/check_msgs_launch_test.py b/launch_testing_ros/examples/check_msgs_launch_test.py index e848a96b..36e9782f 100644 --- a/launch_testing_ros/examples/check_msgs_launch_test.py +++ b/launch_testing_ros/examples/check_msgs_launch_test.py @@ -1,3 +1,17 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from threading import Event, Thread import unittest diff --git a/launch_testing_ros/examples/check_node_launch_test.py b/launch_testing_ros/examples/check_node_launch_test.py index 51fe7bd2..a4b22ff5 100644 --- a/launch_testing_ros/examples/check_node_launch_test.py +++ b/launch_testing_ros/examples/check_node_launch_test.py @@ -1,3 +1,17 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import time import unittest diff --git a/launch_testing_ros/examples/hello_world_launch_test.py b/launch_testing_ros/examples/hello_world_launch_test.py index 3cd68d77..00058b99 100644 --- a/launch_testing_ros/examples/hello_world_launch_test.py +++ b/launch_testing_ros/examples/hello_world_launch_test.py @@ -1,3 +1,17 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import unittest import launch diff --git a/launch_testing_ros/examples/set_param_launch_test.py b/launch_testing_ros/examples/set_param_launch_test.py index a7f07112..c3c92eae 100644 --- a/launch_testing_ros/examples/set_param_launch_test.py +++ b/launch_testing_ros/examples/set_param_launch_test.py @@ -1,3 +1,17 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import unittest import launch From 0643d43d70b5f1124dec168d2046adfda39f75f2 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Wed, 1 Sep 2021 11:29:42 -0700 Subject: [PATCH 04/13] Added section : How to run the tests Signed-off-by: Aditya Pande --- launch_testing_ros/examples/README.rst | 38 +++++++++++++++++++++++++- 1 file changed, 37 insertions(+), 1 deletion(-) diff --git a/launch_testing_ros/examples/README.rst b/launch_testing_ros/examples/README.rst index b8cb8c23..193e7757 100644 --- a/launch_testing_ros/examples/README.rst +++ b/launch_testing_ros/examples/README.rst @@ -1,17 +1,53 @@ Launch testing examples ======================= +.. contents:: Contents + :depth: 2 + :local: + Overview -------- This directory contains examples to help the user get an idea of how to use ``launch_testing`` to write their own test cases. It contains the following examples : * ``hello_world_launch_test.py`` : Demonstrates basic usage and code flow + This test attempts to execute the ``echo hello_world`` command as a separate process, checks that the text ``hello_world`` was detected in the stdout of the launched process (in test_read_stdout function), shuts down the original ``echo hello_world`` process if it is still running. + Finally it checks if the shutdown was successful with exit code 0, in the function test_exit_codes. * ``check_node_launch_test.py`` : There might be situations where nodes, once launched, take some time to actually start and we need to wait for the node to start to perform some action. We can simulate this using ``launch.actions.TimerAction``. This example shows one way to detect when a node has been launched. We delay the launch by 5 seconds, and wait for the node to start with a timeout of 8 seconds. * ``check_msgs_launch_test.py`` : Consider a problem statement where you need to launch a node and check if messages are published on a particular topic. This example demonstrates how to do that, using the talker node from ``demo_nodes_cpp`` package. It uses the ``Event`` object to end the test as soon as the first message is received on the chatter topic, with a timeout of 5 seconds. It is recommended to keep the tests as short as possible. * ``set_param_launch_test.py`` : Launch a node, set a parameter in it and check if that was successful. -More ``launch_testing`` examples which are not RS specific are available `here `_. +Running the tests +----------------- +Make sure you have your ROS workspace sourced and then run: + +``launch_test hello_world_launch_test.py`` + +The output should be similar to: +:: + [INFO] [launch]: All log files can be found below /home/aditya/.ros/log/2021-08-23-09-47-06-613035-aditya-desktop-1376669 + [INFO] [launch]: Default logging verbosity is set to INFO + test_read_stdout (hello_world.TestHelloWorldProcess) ... [INFO] [echo-1]: process started with pid [1376672] + ok + + [INFO] [echo-1]: process has finished cleanly [pid 1376672] + ---------------------------------------------------------------------- + Ran 1 test in 0.008s + + OK + test_exit_codes (hello_world.TestHelloWorldShutdown) ... ok + + ---------------------------------------------------------------------- + Ran 1 test in 0.000s + + OK + +Similarly, the other tests can be run after making sure the corresponding dependencies are installed. + +Generic examples +---------------- + +More ``launch_testing`` examples which are not ROS specific are available `here `_. * ``good_proc_launch_test.py`` : TODO : Add description * ``parameters_launch_test.py`` : TODO : Add desscription From dabed4242aeba98ae4d2ce307e1ab6912ca1943c Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 7 Sep 2021 13:51:59 -0700 Subject: [PATCH 05/13] Changed Parameter style, README link to examples, import order Signed-off-by: Aditya Pande --- launch_testing_ros/examples/README.rst | 9 +-------- launch_testing_ros/examples/check_msgs_launch_test.py | 3 ++- launch_testing_ros/examples/set_param_launch_test.py | 7 +------ 3 files changed, 4 insertions(+), 15 deletions(-) diff --git a/launch_testing_ros/examples/README.rst b/launch_testing_ros/examples/README.rst index 193e7757..284efa54 100644 --- a/launch_testing_ros/examples/README.rst +++ b/launch_testing_ros/examples/README.rst @@ -47,11 +47,4 @@ Similarly, the other tests can be run after making sure the corresponding depend Generic examples ---------------- -More ``launch_testing`` examples which are not ROS specific are available `here `_. - -* ``good_proc_launch_test.py`` : TODO : Add description -* ``parameters_launch_test.py`` : TODO : Add desscription -* ``ready_action_test.py``: TODO : Add description -* ``terminating_proc_launch_test.py``: TODO : Add description -* ``args_launch_test.py``: TODO : Add description -* ``context_launch_test.py``: TODO : Add description +More ``launch_testing`` examples which are not ROS specific are available `here `__ with their explanation available `here `__ diff --git a/launch_testing_ros/examples/check_msgs_launch_test.py b/launch_testing_ros/examples/check_msgs_launch_test.py index 36e9782f..715e2f09 100644 --- a/launch_testing_ros/examples/check_msgs_launch_test.py +++ b/launch_testing_ros/examples/check_msgs_launch_test.py @@ -12,7 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. -from threading import Event, Thread +from threading import Event +from threading import Thread import unittest import launch diff --git a/launch_testing_ros/examples/set_param_launch_test.py b/launch_testing_ros/examples/set_param_launch_test.py index c3c92eae..94f1688d 100644 --- a/launch_testing_ros/examples/set_param_launch_test.py +++ b/launch_testing_ros/examples/set_param_launch_test.py @@ -19,7 +19,6 @@ import launch_ros.actions import launch_testing.actions import pytest -from rcl_interfaces.msg import Parameter, ParameterType from rcl_interfaces.srv import SetParameters import rclpy from rclpy.node import Node @@ -53,11 +52,7 @@ def __init__(self, name='test_node'): super().__init__(name) def set_parameter(self, state=True, timeout=5.0): - parameter = Parameter() - parameter.name = 'demo_parameter_1' - parameter.value.bool_value = state - parameter.value.type = ParameterType.PARAMETER_BOOL - parameters = [parameter] + parameters = [rclpy.Parameter('demo_parameter_1', value=state).to_parameter_msg()] client = self.create_client(SetParameters, 'demo_node_1/set_parameters') ready = client.wait_for_service(timeout_sec=5.0) From 5b535710403cc74bee5d33b086562f39c4e0f298 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Mon, 13 Sep 2021 14:27:16 -0700 Subject: [PATCH 06/13] Moved hello world example to ros2/launch Signed-off-by: Aditya Pande --- launch_testing_ros/examples/README.rst | 3 -- .../examples/hello_world_launch_test.py | 43 ------------------- 2 files changed, 46 deletions(-) delete mode 100644 launch_testing_ros/examples/hello_world_launch_test.py diff --git a/launch_testing_ros/examples/README.rst b/launch_testing_ros/examples/README.rst index 284efa54..ce1c4b52 100644 --- a/launch_testing_ros/examples/README.rst +++ b/launch_testing_ros/examples/README.rst @@ -10,9 +10,6 @@ Overview This directory contains examples to help the user get an idea of how to use ``launch_testing`` to write their own test cases. It contains the following examples : -* ``hello_world_launch_test.py`` : Demonstrates basic usage and code flow - This test attempts to execute the ``echo hello_world`` command as a separate process, checks that the text ``hello_world`` was detected in the stdout of the launched process (in test_read_stdout function), shuts down the original ``echo hello_world`` process if it is still running. - Finally it checks if the shutdown was successful with exit code 0, in the function test_exit_codes. * ``check_node_launch_test.py`` : There might be situations where nodes, once launched, take some time to actually start and we need to wait for the node to start to perform some action. We can simulate this using ``launch.actions.TimerAction``. This example shows one way to detect when a node has been launched. We delay the launch by 5 seconds, and wait for the node to start with a timeout of 8 seconds. * ``check_msgs_launch_test.py`` : Consider a problem statement where you need to launch a node and check if messages are published on a particular topic. This example demonstrates how to do that, using the talker node from ``demo_nodes_cpp`` package. It uses the ``Event`` object to end the test as soon as the first message is received on the chatter topic, with a timeout of 5 seconds. It is recommended to keep the tests as short as possible. * ``set_param_launch_test.py`` : Launch a node, set a parameter in it and check if that was successful. diff --git a/launch_testing_ros/examples/hello_world_launch_test.py b/launch_testing_ros/examples/hello_world_launch_test.py deleted file mode 100644 index 00058b99..00000000 --- a/launch_testing_ros/examples/hello_world_launch_test.py +++ /dev/null @@ -1,43 +0,0 @@ -# Copyright 2021 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import unittest - -import launch -import launch.actions -import launch_testing.actions -import pytest - - -@pytest.mark.launch_test -def generate_test_description(): - return launch.LaunchDescription([ - launch.actions.ExecuteProcess( - cmd=['echo', 'hello_world'] - ), - launch_testing.actions.ReadyToTest() - ]) - - -class TestHelloWorldProcess(unittest.TestCase): - - def test_read_stdout(self, proc_output): - proc_output.assertWaitFor('hello_world', timeout=10, stream='stdout') - - -@launch_testing.post_shutdown_test() -class TestHelloWorldShutdown(unittest.TestCase): - - def test_exit_codes(self, proc_info): - launch_testing.asserts.assertExitCodes(proc_info) From b5118ae063c2074b716343a4621e415070626104 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 14 Sep 2021 11:16:44 -0700 Subject: [PATCH 07/13] Updated README Signed-off-by: Aditya Pande --- launch_testing_ros/examples/README.rst | 40 ++++++++++++++------------ 1 file changed, 21 insertions(+), 19 deletions(-) diff --git a/launch_testing_ros/examples/README.rst b/launch_testing_ros/examples/README.rst index ce1c4b52..ac56e055 100644 --- a/launch_testing_ros/examples/README.rst +++ b/launch_testing_ros/examples/README.rst @@ -18,28 +18,30 @@ Running the tests ----------------- Make sure you have your ROS workspace sourced and then run: -``launch_test hello_world_launch_test.py`` +``launch_test check_msgs_launch_test.py`` The output should be similar to: :: - [INFO] [launch]: All log files can be found below /home/aditya/.ros/log/2021-08-23-09-47-06-613035-aditya-desktop-1376669 - [INFO] [launch]: Default logging verbosity is set to INFO - test_read_stdout (hello_world.TestHelloWorldProcess) ... [INFO] [echo-1]: process started with pid [1376672] - ok - - [INFO] [echo-1]: process has finished cleanly [pid 1376672] - ---------------------------------------------------------------------- - Ran 1 test in 0.008s - - OK - test_exit_codes (hello_world.TestHelloWorldShutdown) ... ok - - ---------------------------------------------------------------------- - Ran 1 test in 0.000s - - OK - -Similarly, the other tests can be run after making sure the corresponding dependencies are installed. + [INFO] [launch]: All log files can be found below /home/aditya/.ros/log/2021-09-14-11-12-10-734588-aditya-desktop-2020689 + [INFO] [launch]: Default logging verbosity is set to INFO + test_check_if_msgs_published (check_msgs_launch_test.TestFixture) ... 1631643130.800377 [0] launch_tes: using network interface enp0s25 (udp/172.23.2.248) selected arbitrarily from: enp0s25, virbr0 + [INFO] [talker-1]: process started with pid [2020700] + [talker-1] 1631643130.834719 [0] talker: using network interface enp0s25 (udp/172.23.2.248) selected arbitrarily from: enp0s25, virbr0 + [talker-1] [INFO] [1631643131.848249515] [demo_node_1]: Publishing: 'Hello World: 1' + ok + + ---------------------------------------------------------------------- + Ran 1 test in 1.062s + + OK + [INFO] [talker-1]: sending signal 'SIGINT' to process[talker-1] + [talker-1] [INFO] [1631643131.855748369] [rclcpp]: signal_handler(signal_value=2) + [INFO] [talker-1]: process has finished cleanly [pid 2020700] + + ---------------------------------------------------------------------- + Ran 0 tests in 0.000s + + OK Generic examples ---------------- From ec7f9e029ee1bf621aaa783a5cf6a549ca0d0332 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 14 Sep 2021 13:27:55 -0700 Subject: [PATCH 08/13] Moved files for CI Signed-off-by: Aditya Pande --- .../test/examples/check_msgs_launch_test.py | 73 +++++++++++++++++++ .../test/examples/check_node_launch_test.py | 65 +++++++++++++++++ .../test/examples/set_param_launch_test.py | 72 ++++++++++++++++++ 3 files changed, 210 insertions(+) create mode 100644 launch_testing_ros/test/examples/check_msgs_launch_test.py create mode 100644 launch_testing_ros/test/examples/check_node_launch_test.py create mode 100644 launch_testing_ros/test/examples/set_param_launch_test.py diff --git a/launch_testing_ros/test/examples/check_msgs_launch_test.py b/launch_testing_ros/test/examples/check_msgs_launch_test.py new file mode 100644 index 00000000..715e2f09 --- /dev/null +++ b/launch_testing_ros/test/examples/check_msgs_launch_test.py @@ -0,0 +1,73 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from threading import Event +from threading import Thread +import unittest + +import launch +import launch.actions +import launch_ros.actions +import launch_testing.actions +import pytest +import rclpy +from rclpy.node import Node +from std_msgs.msg import String + + +@pytest.mark.launch_test +def generate_test_description(): + return launch.LaunchDescription([ + launch_ros.actions.Node( + package='demo_nodes_cpp', + executable='talker', + name='demo_node_1', + ), + + launch_testing.actions.ReadyToTest() + ]) + + +class TestFixture(unittest.TestCase): + + def test_check_if_msgs_published(self, proc_output): + rclpy.init() + node = MakeTestNode('test_node') + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=5.0) + assert msgs_received_flag, 'Did not receive msgs !' + rclpy.shutdown() + + +class MakeTestNode(Node): + + def __init__(self, name='test_node'): + super().__init__(name) + self.msg_event_object = Event() + + def start_subscriber(self): + # Create a subscriber + self.subscription = self.create_subscription( + String, + 'chatter', + self.subscriber_callback, + 10 + ) + + # Add a spin thread + self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def subscriber_callback(self, data): + self.msg_event_object.set() diff --git a/launch_testing_ros/test/examples/check_node_launch_test.py b/launch_testing_ros/test/examples/check_node_launch_test.py new file mode 100644 index 00000000..a4b22ff5 --- /dev/null +++ b/launch_testing_ros/test/examples/check_node_launch_test.py @@ -0,0 +1,65 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import time +import unittest + +import launch +import launch.actions +import launch_ros.actions +import launch_testing.actions +import pytest +import rclpy +from rclpy.node import Node + + +@pytest.mark.launch_test +def generate_test_description(): + return launch.LaunchDescription([ + launch.actions.TimerAction( + period=5.0, + actions=[ + launch_ros.actions.Node( + package='demo_nodes_cpp', + executable='talker', + name='demo_node_1', + ) + ]), + launch_testing.actions.ReadyToTest() + ]) + + +class TestFixture(unittest.TestCase): + + def test_node_start(self, proc_output): + rclpy.init() + node = MakeTestNode('test_node') + assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !' + rclpy.shutdown() + + +class MakeTestNode(Node): + + def __init__(self, name='test_node'): + super().__init__(name) + + def wait_for_node(self, node_name, timeout=8.0): + start = time.time() + flag = False + print('Waiting for node...') + while time.time() - start < timeout and not flag: + flag = node_name in self.get_node_names() + time.sleep(0.1) + + return flag diff --git a/launch_testing_ros/test/examples/set_param_launch_test.py b/launch_testing_ros/test/examples/set_param_launch_test.py new file mode 100644 index 00000000..94f1688d --- /dev/null +++ b/launch_testing_ros/test/examples/set_param_launch_test.py @@ -0,0 +1,72 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import unittest + +import launch +import launch.actions +import launch_ros.actions +import launch_testing.actions +import pytest +from rcl_interfaces.srv import SetParameters +import rclpy +from rclpy.node import Node + + +@pytest.mark.launch_test +def generate_test_description(): + return launch.LaunchDescription([ + launch_ros.actions.Node( + package='demo_nodes_cpp', + executable='parameter_blackboard', + name='demo_node_1', + ), + launch_testing.actions.ReadyToTest() + ]) + + +class TestFixture(unittest.TestCase): + + def test_set_parameter(self, proc_output): + rclpy.init() + node = MakeTestNode('test_node') + response = node.set_parameter(state=True) + assert response.successful, 'Could not set parameter!' + rclpy.shutdown() + + +class MakeTestNode(Node): + + def __init__(self, name='test_node'): + super().__init__(name) + + def set_parameter(self, state=True, timeout=5.0): + parameters = [rclpy.Parameter('demo_parameter_1', value=state).to_parameter_msg()] + + client = self.create_client(SetParameters, 'demo_node_1/set_parameters') + ready = client.wait_for_service(timeout_sec=5.0) + if not ready: + raise RuntimeError('Wait for service timed out') + + request = SetParameters.Request() + request.parameters = parameters + future = client.call_async(request) + rclpy.spin_until_future_complete(self, future) + + response = future.result() + if response is None: + e = future.exception() + raise RuntimeError( + f"Exception while calling service of node 'demo_node_1': {e}") + return response.results[0] From f206b4f68addcd90a172e5974499c326dbabe250 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 14 Sep 2021 13:51:59 -0700 Subject: [PATCH 09/13] CI fix Signed-off-by: Aditya Pande --- .../examples/check_msgs_launch_test.py | 73 ------------------- .../examples/check_node_launch_test.py | 65 ----------------- .../examples/set_param_launch_test.py | 72 ------------------ .../{ => test}/examples/README.rst | 0 .../test/examples/check_msgs_launch_test.py | 2 + .../test/examples/check_node_launch_test.py | 2 + .../test/examples/set_param_launch_test.py | 2 + 7 files changed, 6 insertions(+), 210 deletions(-) delete mode 100644 launch_testing_ros/examples/check_msgs_launch_test.py delete mode 100644 launch_testing_ros/examples/check_node_launch_test.py delete mode 100644 launch_testing_ros/examples/set_param_launch_test.py rename launch_testing_ros/{ => test}/examples/README.rst (100%) diff --git a/launch_testing_ros/examples/check_msgs_launch_test.py b/launch_testing_ros/examples/check_msgs_launch_test.py deleted file mode 100644 index 715e2f09..00000000 --- a/launch_testing_ros/examples/check_msgs_launch_test.py +++ /dev/null @@ -1,73 +0,0 @@ -# Copyright 2021 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from threading import Event -from threading import Thread -import unittest - -import launch -import launch.actions -import launch_ros.actions -import launch_testing.actions -import pytest -import rclpy -from rclpy.node import Node -from std_msgs.msg import String - - -@pytest.mark.launch_test -def generate_test_description(): - return launch.LaunchDescription([ - launch_ros.actions.Node( - package='demo_nodes_cpp', - executable='talker', - name='demo_node_1', - ), - - launch_testing.actions.ReadyToTest() - ]) - - -class TestFixture(unittest.TestCase): - - def test_check_if_msgs_published(self, proc_output): - rclpy.init() - node = MakeTestNode('test_node') - node.start_subscriber() - msgs_received_flag = node.msg_event_object.wait(timeout=5.0) - assert msgs_received_flag, 'Did not receive msgs !' - rclpy.shutdown() - - -class MakeTestNode(Node): - - def __init__(self, name='test_node'): - super().__init__(name) - self.msg_event_object = Event() - - def start_subscriber(self): - # Create a subscriber - self.subscription = self.create_subscription( - String, - 'chatter', - self.subscriber_callback, - 10 - ) - - # Add a spin thread - self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) - self.ros_spin_thread.start() - - def subscriber_callback(self, data): - self.msg_event_object.set() diff --git a/launch_testing_ros/examples/check_node_launch_test.py b/launch_testing_ros/examples/check_node_launch_test.py deleted file mode 100644 index a4b22ff5..00000000 --- a/launch_testing_ros/examples/check_node_launch_test.py +++ /dev/null @@ -1,65 +0,0 @@ -# Copyright 2021 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import time -import unittest - -import launch -import launch.actions -import launch_ros.actions -import launch_testing.actions -import pytest -import rclpy -from rclpy.node import Node - - -@pytest.mark.launch_test -def generate_test_description(): - return launch.LaunchDescription([ - launch.actions.TimerAction( - period=5.0, - actions=[ - launch_ros.actions.Node( - package='demo_nodes_cpp', - executable='talker', - name='demo_node_1', - ) - ]), - launch_testing.actions.ReadyToTest() - ]) - - -class TestFixture(unittest.TestCase): - - def test_node_start(self, proc_output): - rclpy.init() - node = MakeTestNode('test_node') - assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !' - rclpy.shutdown() - - -class MakeTestNode(Node): - - def __init__(self, name='test_node'): - super().__init__(name) - - def wait_for_node(self, node_name, timeout=8.0): - start = time.time() - flag = False - print('Waiting for node...') - while time.time() - start < timeout and not flag: - flag = node_name in self.get_node_names() - time.sleep(0.1) - - return flag diff --git a/launch_testing_ros/examples/set_param_launch_test.py b/launch_testing_ros/examples/set_param_launch_test.py deleted file mode 100644 index 94f1688d..00000000 --- a/launch_testing_ros/examples/set_param_launch_test.py +++ /dev/null @@ -1,72 +0,0 @@ -# Copyright 2021 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import unittest - -import launch -import launch.actions -import launch_ros.actions -import launch_testing.actions -import pytest -from rcl_interfaces.srv import SetParameters -import rclpy -from rclpy.node import Node - - -@pytest.mark.launch_test -def generate_test_description(): - return launch.LaunchDescription([ - launch_ros.actions.Node( - package='demo_nodes_cpp', - executable='parameter_blackboard', - name='demo_node_1', - ), - launch_testing.actions.ReadyToTest() - ]) - - -class TestFixture(unittest.TestCase): - - def test_set_parameter(self, proc_output): - rclpy.init() - node = MakeTestNode('test_node') - response = node.set_parameter(state=True) - assert response.successful, 'Could not set parameter!' - rclpy.shutdown() - - -class MakeTestNode(Node): - - def __init__(self, name='test_node'): - super().__init__(name) - - def set_parameter(self, state=True, timeout=5.0): - parameters = [rclpy.Parameter('demo_parameter_1', value=state).to_parameter_msg()] - - client = self.create_client(SetParameters, 'demo_node_1/set_parameters') - ready = client.wait_for_service(timeout_sec=5.0) - if not ready: - raise RuntimeError('Wait for service timed out') - - request = SetParameters.Request() - request.parameters = parameters - future = client.call_async(request) - rclpy.spin_until_future_complete(self, future) - - response = future.result() - if response is None: - e = future.exception() - raise RuntimeError( - f"Exception while calling service of node 'demo_node_1': {e}") - return response.results[0] diff --git a/launch_testing_ros/examples/README.rst b/launch_testing_ros/test/examples/README.rst similarity index 100% rename from launch_testing_ros/examples/README.rst rename to launch_testing_ros/test/examples/README.rst diff --git a/launch_testing_ros/test/examples/check_msgs_launch_test.py b/launch_testing_ros/test/examples/check_msgs_launch_test.py index 715e2f09..f5df3cb2 100644 --- a/launch_testing_ros/test/examples/check_msgs_launch_test.py +++ b/launch_testing_ros/test/examples/check_msgs_launch_test.py @@ -20,6 +20,7 @@ import launch.actions import launch_ros.actions import launch_testing.actions +import launch_testing.markers import pytest import rclpy from rclpy.node import Node @@ -27,6 +28,7 @@ @pytest.mark.launch_test +@launch_testing.markers.keep_alive def generate_test_description(): return launch.LaunchDescription([ launch_ros.actions.Node( diff --git a/launch_testing_ros/test/examples/check_node_launch_test.py b/launch_testing_ros/test/examples/check_node_launch_test.py index a4b22ff5..caeba648 100644 --- a/launch_testing_ros/test/examples/check_node_launch_test.py +++ b/launch_testing_ros/test/examples/check_node_launch_test.py @@ -19,12 +19,14 @@ import launch.actions import launch_ros.actions import launch_testing.actions +import launch_testing.markers import pytest import rclpy from rclpy.node import Node @pytest.mark.launch_test +@launch_testing.markers.keep_alive def generate_test_description(): return launch.LaunchDescription([ launch.actions.TimerAction( diff --git a/launch_testing_ros/test/examples/set_param_launch_test.py b/launch_testing_ros/test/examples/set_param_launch_test.py index 94f1688d..dee51e36 100644 --- a/launch_testing_ros/test/examples/set_param_launch_test.py +++ b/launch_testing_ros/test/examples/set_param_launch_test.py @@ -18,6 +18,7 @@ import launch.actions import launch_ros.actions import launch_testing.actions +import launch_testing.markers import pytest from rcl_interfaces.srv import SetParameters import rclpy @@ -25,6 +26,7 @@ @pytest.mark.launch_test +@launch_testing.markers.keep_alive def generate_test_description(): return launch.LaunchDescription([ launch_ros.actions.Node( From 294a304d8fc4765e60240dd97e299f89c2fcfc85 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Tue, 14 Sep 2021 14:31:26 -0700 Subject: [PATCH 10/13] Added test dependency to package.xml Signed-off-by: Aditya Pande --- launch_testing_ros/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/launch_testing_ros/package.xml b/launch_testing_ros/package.xml index 4671c032..d5fdb515 100644 --- a/launch_testing_ros/package.xml +++ b/launch_testing_ros/package.xml @@ -18,6 +18,7 @@ ament_pep257 python3-pytest std_msgs + demo_nodes_cpp ament_python From a0e6070a9e03df104613326a7cef5098a6c4ef10 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Wed, 15 Sep 2021 16:25:46 -0700 Subject: [PATCH 11/13] Removed dependency on demo_nodes_cpp Signed-off-by: Aditya Pande --- launch_testing_ros/package.xml | 1 - .../test/examples/check_msgs_launch_test.py | 10 ++++- .../test/examples/check_node_launch_test.py | 9 +++- .../test/examples/parameter_blackboard.py | 41 +++++++++++++++++++ .../test/examples/set_param_launch_test.py | 9 +++- 5 files changed, 63 insertions(+), 7 deletions(-) create mode 100644 launch_testing_ros/test/examples/parameter_blackboard.py diff --git a/launch_testing_ros/package.xml b/launch_testing_ros/package.xml index d5fdb515..4671c032 100644 --- a/launch_testing_ros/package.xml +++ b/launch_testing_ros/package.xml @@ -18,7 +18,6 @@ ament_pep257 python3-pytest std_msgs - demo_nodes_cpp ament_python diff --git a/launch_testing_ros/test/examples/check_msgs_launch_test.py b/launch_testing_ros/test/examples/check_msgs_launch_test.py index f5df3cb2..35dd474e 100644 --- a/launch_testing_ros/test/examples/check_msgs_launch_test.py +++ b/launch_testing_ros/test/examples/check_msgs_launch_test.py @@ -12,6 +12,9 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import sys + from threading import Event from threading import Thread import unittest @@ -30,10 +33,13 @@ @pytest.mark.launch_test @launch_testing.markers.keep_alive def generate_test_description(): + path_to_test = os.path.dirname(__file__) + return launch.LaunchDescription([ launch_ros.actions.Node( - package='demo_nodes_cpp', - executable='talker', + executable=sys.executable, + arguments=[os.path.join(path_to_test, 'talker.py')], + additional_env={'PYTHONUNBUFFERED': '1'}, name='demo_node_1', ), diff --git a/launch_testing_ros/test/examples/check_node_launch_test.py b/launch_testing_ros/test/examples/check_node_launch_test.py index caeba648..ef9903b7 100644 --- a/launch_testing_ros/test/examples/check_node_launch_test.py +++ b/launch_testing_ros/test/examples/check_node_launch_test.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import sys import time import unittest @@ -28,13 +30,16 @@ @pytest.mark.launch_test @launch_testing.markers.keep_alive def generate_test_description(): + path_to_test = os.path.dirname(__file__) + return launch.LaunchDescription([ launch.actions.TimerAction( period=5.0, actions=[ launch_ros.actions.Node( - package='demo_nodes_cpp', - executable='talker', + executable=sys.executable, + arguments=[os.path.join(path_to_test, 'talker.py')], + additional_env={'PYTHONUNBUFFERED': '1'}, name='demo_node_1', ) ]), diff --git a/launch_testing_ros/test/examples/parameter_blackboard.py b/launch_testing_ros/test/examples/parameter_blackboard.py new file mode 100644 index 00000000..e3354c7a --- /dev/null +++ b/launch_testing_ros/test/examples/parameter_blackboard.py @@ -0,0 +1,41 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import rclpy +from rclpy.node import Node + + +class TestNode(Node): + + def __init__(self): + super().__init__('parameter_blackboard') + self.declare_parameter('demo_parameter_1', False) + + +def main(args=None): + rclpy.init(args=args) + + node = TestNode() + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/launch_testing_ros/test/examples/set_param_launch_test.py b/launch_testing_ros/test/examples/set_param_launch_test.py index dee51e36..feeb0c61 100644 --- a/launch_testing_ros/test/examples/set_param_launch_test.py +++ b/launch_testing_ros/test/examples/set_param_launch_test.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import sys import unittest import launch @@ -28,10 +30,13 @@ @pytest.mark.launch_test @launch_testing.markers.keep_alive def generate_test_description(): + path_to_test = os.path.dirname(__file__) + return launch.LaunchDescription([ launch_ros.actions.Node( - package='demo_nodes_cpp', - executable='parameter_blackboard', + executable=sys.executable, + arguments=[os.path.join(path_to_test, 'parameter_blackboard.py')], + additional_env={'PYTHONUNBUFFERED': '1'}, name='demo_node_1', ), launch_testing.actions.ReadyToTest() From 8ace476e5eb488d037b5edb56c999cf9b20902d0 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Thu, 16 Sep 2021 10:23:02 -0700 Subject: [PATCH 12/13] Merged README Signed-off-by: Aditya Pande --- launch_testing_ros/README.md | 34 ++++++++++++++ launch_testing_ros/test/examples/README.rst | 49 --------------------- 2 files changed, 34 insertions(+), 49 deletions(-) delete mode 100644 launch_testing_ros/test/examples/README.rst diff --git a/launch_testing_ros/README.md b/launch_testing_ros/README.md index 0cc28bd5..68089cd7 100644 --- a/launch_testing_ros/README.md +++ b/launch_testing_ros/README.md @@ -14,6 +14,40 @@ This test launches the talker and listener example nodes from demo\_nodes\_py an with them via their ROS interfaces. Remapping rules are used so that one of the tests can sit in between the talker and the listener and change the data on the fly. +### `check_node_launch_test.py` + +Usage: + +```sh +launch_test test/examples/check_node_launch_test.py +``` + +There might be situations where nodes, once launched, take some time to actually start and we need to wait for the node to start to perform some action. +We can simulate this using ``launch.actions.TimerAction``. This example shows one way to detect when a node has been launched. +We delay the launch by 5 seconds, and wait for the node to start with a timeout of 8 seconds. + +### `check_msgs_launch_test.py` + +Usage: + +```sh +launch_test test/examples/check_msgs_launch_test.py +``` + +Consider a problem statement where you need to launch a node and check if messages are published on a particular topic. +This example demonstrates how to do that, using the talker node from ``demo_nodes_cpp`` package. +It uses the ``Event`` object to end the test as soon as the first message is received on the chatter topic, with a timeout of 5 seconds. + +### `set_param_launch_test.py` + +Usage: + +```sh +launch_test test/examples/set_param_launch_test.py +``` + +This example demonstrates how to launch a node, set a parameter in it and check if that was successful. + #### test\_fuzzy\_data This test gives an example of what a test that fuzzes data might look like. A ROS subscriber and publisher pair encapsulated in a `DataRepublisher` object changes the string "Hello World" to diff --git a/launch_testing_ros/test/examples/README.rst b/launch_testing_ros/test/examples/README.rst deleted file mode 100644 index ac56e055..00000000 --- a/launch_testing_ros/test/examples/README.rst +++ /dev/null @@ -1,49 +0,0 @@ -Launch testing examples -======================= - -.. contents:: Contents - :depth: 2 - :local: - -Overview --------- - -This directory contains examples to help the user get an idea of how to use ``launch_testing`` to write their own test cases. It contains the following examples : - -* ``check_node_launch_test.py`` : There might be situations where nodes, once launched, take some time to actually start and we need to wait for the node to start to perform some action. We can simulate this using ``launch.actions.TimerAction``. This example shows one way to detect when a node has been launched. We delay the launch by 5 seconds, and wait for the node to start with a timeout of 8 seconds. -* ``check_msgs_launch_test.py`` : Consider a problem statement where you need to launch a node and check if messages are published on a particular topic. This example demonstrates how to do that, using the talker node from ``demo_nodes_cpp`` package. It uses the ``Event`` object to end the test as soon as the first message is received on the chatter topic, with a timeout of 5 seconds. It is recommended to keep the tests as short as possible. -* ``set_param_launch_test.py`` : Launch a node, set a parameter in it and check if that was successful. - -Running the tests ------------------ -Make sure you have your ROS workspace sourced and then run: - -``launch_test check_msgs_launch_test.py`` - -The output should be similar to: -:: - [INFO] [launch]: All log files can be found below /home/aditya/.ros/log/2021-09-14-11-12-10-734588-aditya-desktop-2020689 - [INFO] [launch]: Default logging verbosity is set to INFO - test_check_if_msgs_published (check_msgs_launch_test.TestFixture) ... 1631643130.800377 [0] launch_tes: using network interface enp0s25 (udp/172.23.2.248) selected arbitrarily from: enp0s25, virbr0 - [INFO] [talker-1]: process started with pid [2020700] - [talker-1] 1631643130.834719 [0] talker: using network interface enp0s25 (udp/172.23.2.248) selected arbitrarily from: enp0s25, virbr0 - [talker-1] [INFO] [1631643131.848249515] [demo_node_1]: Publishing: 'Hello World: 1' - ok - - ---------------------------------------------------------------------- - Ran 1 test in 1.062s - - OK - [INFO] [talker-1]: sending signal 'SIGINT' to process[talker-1] - [talker-1] [INFO] [1631643131.855748369] [rclcpp]: signal_handler(signal_value=2) - [INFO] [talker-1]: process has finished cleanly [pid 2020700] - - ---------------------------------------------------------------------- - Ran 0 tests in 0.000s - - OK - -Generic examples ----------------- - -More ``launch_testing`` examples which are not ROS specific are available `here `__ with their explanation available `here `__ From 2d08d0610c39b5df0dd952643a95bfca5e513698 Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Thu, 16 Sep 2021 10:34:58 -0700 Subject: [PATCH 13/13] README edit Signed-off-by: Aditya Pande --- launch_testing_ros/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch_testing_ros/README.md b/launch_testing_ros/README.md index 68089cd7..d7abba09 100644 --- a/launch_testing_ros/README.md +++ b/launch_testing_ros/README.md @@ -35,7 +35,7 @@ launch_test test/examples/check_msgs_launch_test.py ``` Consider a problem statement where you need to launch a node and check if messages are published on a particular topic. -This example demonstrates how to do that, using the talker node from ``demo_nodes_cpp`` package. +This example demonstrates how to do that, using a talker node. It uses the ``Event`` object to end the test as soon as the first message is received on the chatter topic, with a timeout of 5 seconds. ### `set_param_launch_test.py`