Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Launch testing examples : ROS focused #263

Merged
merged 13 commits into from
Sep 16, 2021
47 changes: 47 additions & 0 deletions launch_testing_ros/examples/README.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
Launch testing examples
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
=======================

.. 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 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 <https://github.com/ros2/launch/tree/master/launch_testing/test/launch_testing/examples>`__ with their explanation available `here <https://github.com/ros2/launch/tree/master/launch_testing#examples>`__
73 changes: 73 additions & 0 deletions launch_testing_ros/examples/check_msgs_launch_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
# Copyright 2021 Open Source Robotics Foundation, Inc.
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved
#
# 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()
])
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved


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)
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved
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()
65 changes: 65 additions & 0 deletions launch_testing_ros/examples/check_node_launch_test.py
Original file line number Diff line number Diff line change
@@ -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):
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved
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
72 changes: 72 additions & 0 deletions launch_testing_ros/examples/set_param_launch_test.py
Original file line number Diff line number Diff line change
@@ -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)
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved

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]