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

Add timeout for ReadyToTest action #622

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 8 additions & 1 deletion launch_testing/launch_testing/launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,12 @@ def add_arguments(parser):
'--junit-xml', action='store', dest='xmlpath', default=None,
help='Do write xUnit reports to specified path.'
)
parser.add_argument(
'--timeout', type=float, default=15.0,
help='Maximum duration for which the ReadyToTest action waits for the processes'
'to start up, if processes take more time than the one specified by timeout'
'an error is thrown. By default timeout is 15 seconds.'
)


def parse_arguments():
Expand Down Expand Up @@ -92,7 +98,8 @@ def run(parser, args, test_runner_cls=LaunchTestRunner):
runner = test_runner_cls(
test_runs=test_runs,
launch_file_arguments=args.launch_arguments,
debug=args.verbose
debug=args.verbose,
timeout=args.timeout
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit (in this way, the diff will not show one deleted line next time):

Suggested change
timeout=args.timeout
timeout=args.timeout,

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks!

)

_logger_.debug('Validating test configuration')
Expand Down
13 changes: 9 additions & 4 deletions launch_testing/launch_testing/test_runner.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,15 @@ def __init__(self,
test_run,
test_run_preamble,
launch_file_arguments=[],
debug=False):
debug=False,
timeout=15.0):
self._test_run = test_run
self._test_run_preamble = test_run_preamble
self._launch_service = LaunchService(debug=debug)
self._processes_launched = threading.Event() # To signal when all processes started
self._tests_completed = threading.Event() # To signal when all the tests have finished
self._launch_file_arguments = launch_file_arguments
self._timeout = timeout # timeout for ReadyToTest Action

# Can't run LaunchService.run on another thread :-(
# See https://github.com/ros2/launch/issues/126
Expand Down Expand Up @@ -181,7 +183,7 @@ def _run_test(self):
# Waits for the DUT processes to start (signaled by the _processes_launched
# event) and then runs the tests

if not self._processes_launched.wait(timeout=15):
if not self._processes_launched.wait(self._timeout):
# Timed out waiting for the processes to start
print('Timed out waiting for processes to start up')
self._launch_service.shutdown()
Expand Down Expand Up @@ -217,7 +219,8 @@ class LaunchTestRunner(object):
def __init__(self,
test_runs,
launch_file_arguments=[],
debug=False):
debug=False,
timeout=15.0):
"""
Create an LaunchTestRunner object.

Expand All @@ -229,6 +232,7 @@ def __init__(self,
self._test_runs = test_runs
self._launch_file_arguments = launch_file_arguments
self._debug = debug
self._timeout = timeout # timeout for ReadyToTest Action

def generate_preamble(self):
"""Generate a launch description preamble for a test to be run with."""
Expand All @@ -252,7 +256,8 @@ def run(self):
run,
self.generate_preamble(),
self._launch_file_arguments,
self._debug)
self._debug,
self._timeout)
results[run] = worker.run()
except unittest.case.SkipTest as skip_exception:
# If a 'skip' decorator was placed on the generate_test_description function,
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# Copyright 2022 Apex.AI, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import launch
import launch_testing
from launch.actions import TimerAction
from launch_testing.actions import ReadyToTest

import pytest


@pytest.mark.launch_test
def generate_test_description():
# takes 5 sec for the TimerAction process to start
return launch.LaunchDescription([
launch_testing.util.KeepAliveProc(),
TimerAction(period=5.0, actions=[ReadyToTest()]),
])
70 changes: 70 additions & 0 deletions launch_testing/test/launch_testing/test_ready_action_timeout.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
# Copyright 2022 Apex.AI, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os
import subprocess

import ament_index_python


def test_ready_action_within_timeout_duration():
testpath = os.path.join(
ament_index_python.get_package_share_directory('launch_testing'),
'examples',
'ready_action_timeout_launch_test.py',
)

# the process takes 5sec to start which is within the
# timeout duration of 20sec specified by ReadyToTest action.
completed_process = subprocess.run(
args=[
'launch_test',
'--timeout',
'20.0',
testpath
],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
)

# success
assert 0 == completed_process.returncode


# the process takes longer time to startup than the one
# specified by ReadyToTest action timeout duration.
def test_ready_action_exceed_timeout_duration():
testpath = os.path.join(
ament_index_python.get_package_share_directory('launch_testing'),
'examples',
'ready_action_timeout_launch_test.py',
)

# the process takes around 5 sec to start which exceeds the
# 2 sec timeout duration specified by ReadyToTest action.
completed_process = subprocess.run(
args=[
'launch_test',
'--timeout',
'2.0',
testpath
],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
)

# fail
assert 1 == completed_process.returncode
assert 'Timed out waiting for processes to start up' in \
completed_process.stdout.decode()