Skip to content

Commit 745fc5f

Browse files
committed
Revamp the test.
Make it use the new test infrastructure. Signed-off-by: Chris Lalancette <[email protected]>
1 parent c8d1b49 commit 745fc5f

File tree

5 files changed

+105
-102
lines changed

5 files changed

+105
-102
lines changed

image_tools_py/package.xml

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -13,15 +13,11 @@
1313
<exec_depend>std_msgs</exec_depend>
1414
<exec_depend>sensor_msgs</exec_depend>
1515

16-
<!-- These test dependencies are optional
17-
Their purpose is to make sure that the code passes the linters -->
1816
<test_depend>ament_copyright</test_depend>
1917
<test_depend>ament_flake8</test_depend>
2018
<test_depend>ament_pep257</test_depend>
21-
<test_depend>ament_pep8</test_depend>
22-
<test_depend>ament_pyflakes</test_depend>
2319
<test_depend>launch</test_depend>
24-
<test_depend>launch_testing</test_depend>
20+
<test_depend>python3-pytest</test_depend>
2521

2622
<export>
2723
<build_type>ament_python</build_type>

image_tools_py/setup.py

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -26,11 +26,9 @@ def run(self):
2626

2727
for rmw_impl in rmw_implementations:
2828
substs = {
29-
'@rmw_implementation@': rmw_impl,
30-
'@showimage_py_exe@': os.path.join(self.install_dir, 'showimage_py'),
31-
'@showimage_py_outfile@': os.path.realpath(os.path.join('test', 'showimage_py')),
32-
'@cam2image_py_exe@': os.path.join(self.install_dir, 'cam2image_py'),
33-
'@cam2image_py_outfile@': os.path.realpath(os.path.join('test', 'cam2image_py')),
29+
'@RMW_IMPLEMENTATION@': rmw_impl,
30+
'@RCLPY_DEMO_SHOWIMAGE_EXE@': os.path.join(self.install_dir, 'showimage_py'),
31+
'@RCLPY_DEMO_CAM2IMAGE_EXE@': os.path.join(self.install_dir, 'cam2image_py'),
3432
}
3533

3634
infile = os.path.join('test', 'test_showimage_cam2image.py.in')
@@ -39,7 +37,7 @@ def run(self):
3937
with open(outfile, 'w') as outfp:
4038
for line in infp:
4139
for subst in substs:
42-
line = line.replace(subst, "r'%s' # noqa" % (substs[subst]))
40+
line = line.replace(subst, substs[subst])
4341
outfp.write(line)
4442

4543
install_scripts.run(self)

image_tools_py/test/cam2image_py.txt

Lines changed: 0 additions & 2 deletions
This file was deleted.

image_tools_py/test/showimage_py.regex

Lines changed: 0 additions & 1 deletion
This file was deleted.
Lines changed: 100 additions & 88 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
# Copyright 2016 Open Source Robotics Foundation, Inc.
1+
# Copyright 2019 Open Source Robotics Foundation, Inc.
22
#
33
# Licensed under the Apache License, Version 2.0 (the "License");
44
# you may not use this file except in compliance with the License.
@@ -13,90 +13,102 @@
1313
# limitations under the License.
1414

1515
import os
16-
17-
from launch.legacy import LaunchDescriptor
18-
from launch.legacy.exit_handler import ignore_exit_handler
19-
from launch.legacy.exit_handler import primary_ignore_returncode_exit_handler
20-
from launch.legacy.launcher import DefaultLauncher
21-
from launch.legacy.output_handler import ConsoleOutput
22-
from launch_testing import create_handler
23-
24-
25-
def setup():
26-
os.environ['OSPL_VERBOSITY'] = '8' # 8 = OS_NONE
27-
# bare minimum formatting for console output matching
28-
os.environ['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '{message}'
29-
30-
31-
def test_reliable_qos():
32-
pub_executable_args = ['-r', '1', '-s', '0', '-b', '-f', '5']
33-
sub_executable_args = ['-r', '1', '-s', '0']
34-
_test_executables(pub_executable_args, sub_executable_args)
35-
36-
37-
def _test_executables(publisher_executable_args, subscriber_executable_args):
38-
output_handlers = []
39-
launch_descriptor = LaunchDescriptor()
40-
41-
rmw_implementation = @rmw_implementation@
42-
env = dict(os.environ)
43-
env['RMW_IMPLEMENTATION'] = rmw_implementation
44-
env['PYTHONUNBUFFERED'] = '1'
45-
46-
# Launch the process that will receive the images.
47-
# This is the process that gets to decide when to tear the launcher down.
48-
# It will exit when the regex for receiving images is matched.
49-
showimage_executable = @showimage_py_exe@
50-
showimage_output_file = @showimage_py_outfile@
51-
showimage_name = 'test_showimage_py'
52-
showimage_handler = create_handler(
53-
showimage_name, launch_descriptor, showimage_output_file, exit_on_match=True,
54-
filtered_rmw_implementation=rmw_implementation)
55-
assert showimage_handler, 'Cannot find appropriate handler for %s' % showimage_output_file
56-
output_handlers.append(showimage_handler)
57-
58-
command = [showimage_executable]
59-
command.extend(subscriber_executable_args)
60-
launch_descriptor.add_process(
61-
cmd=command,
62-
name=showimage_name,
63-
exit_handler=primary_ignore_returncode_exit_handler,
64-
output_handlers=[showimage_handler, ConsoleOutput()],
65-
env=env,
66-
)
67-
68-
# Launch the process that will publish the images.
69-
# This process will be exited when the launcher is torn down.
70-
cam2image_executable = @cam2image_py_exe@
71-
cam2image_output_file = @cam2image_py_outfile@
72-
cam2image_name = 'test_cam2image_py'
73-
cam2image_handler = create_handler(
74-
cam2image_name, launch_descriptor, cam2image_output_file, exit_on_match=False,
75-
filtered_rmw_implementation=rmw_implementation)
76-
assert cam2image_handler, 'Cannot find appropriate handler for %s' % cam2image_output_file
77-
output_handlers.append(cam2image_handler)
78-
79-
command = [cam2image_executable]
80-
command.extend(publisher_executable_args)
81-
launch_descriptor.add_process(
82-
cmd=command,
83-
name=cam2image_name,
84-
exit_handler=ignore_exit_handler,
85-
output_handlers=[cam2image_handler, ConsoleOutput()],
86-
env=env,
87-
)
88-
89-
launcher = DefaultLauncher()
90-
launcher.add_launch_descriptor(launch_descriptor)
91-
rc = launcher.launch()
92-
93-
assert rc == 0, \
94-
"The launch file failed with exit code '" + str(rc) + "'. "
95-
96-
# Check that the output received by the handlers is what was expected.
97-
for handler in output_handlers:
98-
handler.check()
99-
100-
101-
if __name__ == '__main__':
102-
test_reliable_qos()
16+
import time
17+
import unittest
18+
19+
from launch import LaunchDescription
20+
from launch import LaunchService
21+
from launch.actions import EmitEvent
22+
from launch.actions import ExecuteProcess
23+
from launch.actions import RegisterEventHandler
24+
from launch.event_handlers import OnProcessIO
25+
from launch.events import Shutdown
26+
27+
28+
# TODO(clalancette): we can't currently use launch_testing since there is
29+
# currently no integration with pure python setup.py. Once we have a solution
30+
# for https://github.com/ros2/launch/issues/237, we should revisit this.
31+
class TestExecutablesDemo(unittest.TestCase):
32+
33+
def __init__(self, name):
34+
super().__init__(name)
35+
self._start_time = time.time()
36+
self._ls = LaunchService()
37+
self._ls.include_launch_description(self.generate_launch_description())
38+
self._saw_cam2image_output = False
39+
self._saw_showimage_output = False
40+
41+
def generate_launch_description(self):
42+
launch_description = LaunchDescription()
43+
publisher_executable_args = ['-r', '1', '-s', '0', '-b', '-f', '5']
44+
subscriber_executable_args = ['-r', '1', '-s', '0']
45+
46+
env = dict(os.environ)
47+
env['PYTHONUNBUFFERED'] = '1'
48+
env['OSPL_VERBOSITY'] = '8' # 8 = OS_NONE
49+
# bare minimum formatting for console output matching
50+
env['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '{message}'
51+
env['RMW_IMPLEMENTATION'] = r'@RMW_IMPLEMENTATION@'
52+
53+
# Launch the process that will receive the images.
54+
# This is the process that gets to decide when to tear the launcher down.
55+
# It will exit when the regex for receiving images is matched.
56+
showimage_executable = r'@RCLPY_DEMO_SHOWIMAGE_EXE@' # noqa: E501
57+
showimage_name = 'test_showimage_py'
58+
59+
command = [showimage_executable]
60+
command.extend(subscriber_executable_args)
61+
showimage_process = ExecuteProcess(
62+
cmd=command,
63+
name=showimage_name,
64+
env=env,
65+
output='screen'
66+
)
67+
launch_description.add_action(showimage_process)
68+
69+
# Launch the process that will publish the images.
70+
# This process will be exited when the launcher is torn down.
71+
cam2image_executable = r'@RCLPY_DEMO_CAM2IMAGE_EXE@' # noqa: E501
72+
cam2image_name = 'test_cam2image_py'
73+
74+
command = [cam2image_executable]
75+
command.extend(publisher_executable_args)
76+
cam2image_process = ExecuteProcess(
77+
cmd=command,
78+
name=cam2image_name,
79+
env=env,
80+
output='screen'
81+
)
82+
launch_description.add_action(cam2image_process)
83+
84+
launch_description.add_action(
85+
RegisterEventHandler(
86+
OnProcessIO(
87+
on_stdout=self.append,
88+
on_stderr=self.append,
89+
)
90+
)
91+
)
92+
93+
return launch_description
94+
95+
def append(self, process_io):
96+
if 'cam2image' in process_io.process_name:
97+
if 'Publishing image #' in process_io.text.decode():
98+
self._saw_cam2image_output = True
99+
elif 'showimage' in process_io.process_name:
100+
if 'Received image #' in process_io.text.decode():
101+
self._saw_showimage_output = True
102+
103+
if self._saw_cam2image_output and self._saw_showimage_output:
104+
# We've seen all required arguments from the test, quit
105+
return EmitEvent(event=Shutdown(reason='finished', due_to_sigint=False))
106+
107+
if time.time() - self._start_time > 10.0:
108+
# We've waited more than 10 seconds with no output; raise an error
109+
return EmitEvent(event=Shutdown(reason='timeout', due_to_sigint=False))
110+
111+
def test_reliable_qos(self):
112+
self._ls.run()
113+
self._ls.shutdown()
114+
self.assertTrue(self._saw_cam2image_output and self._saw_showimage_output)

0 commit comments

Comments
 (0)