Skip to content

Commit bbde938

Browse files
committed
Add in a test for showimage_py and cam2image_py.
Signed-off-by: Chris Lalancette <[email protected]>
1 parent 6372f18 commit bbde938

File tree

7 files changed

+181
-4
lines changed

7 files changed

+181
-4
lines changed

image_tools_py/cam2image_py.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,9 @@ def main(args=None):
8989
parser.add_argument(
9090
'-s', '--show', dest='show_camera', action='store', default=0, type=int, choices=[0, 1],
9191
help='Show the camera stream')
92+
parser.add_argument(
93+
'-t', '--topic', dest='topic', action='store', default='image', type=str,
94+
help='Topic to publish on')
9295
parser.add_argument(
9396
'-x', '--width', dest='width', action='store', default=320, type=int,
9497
help='Image width')
@@ -119,6 +122,8 @@ def main(args=None):
119122
# parameter.
120123
custom_camera_qos_profile.history = args.history_policy
121124

125+
print("Publishing data on topic '%s'" % (args.topic))
126+
122127
# Create the image publisher with our custom QoS profile.
123128
pub = node.create_publisher(
124129
sensor_msgs.msg.Image, 'image',

image_tools_py/package.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,9 @@
44
<name>image_tools_py</name>
55
<version>0.0.0</version>
66
<description>Python tools to capture/play back images to/from DDS subscriptions/publications.</description>
7-
<maintainer email="clalancette@osrfoundation.org">Chris Lalancette</maintainer>
7+
<maintainer email="clalancette@openrobotics.org">Chris Lalancette</maintainer>
88
<license>Apache License 2.0</license>
9-
<author email="clalancette@osrfoundation.org">Chris Lalancette</author>
9+
<author email="clalancette@openrobotics.org">Chris Lalancette</author>
1010

1111
<exec_depend>python3-opencv</exec_depend>
1212
<exec_depend>rclpy</exec_depend>

image_tools_py/setup.py

Lines changed: 46 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,50 @@
1+
import os
2+
13
from setuptools import setup
4+
from setuptools.command.install_scripts import install_scripts
25

36
package_name = 'image_tools_py'
47

8+
9+
# This configuration deserves some explanation. The goal is to generate a
10+
# test file called something like 'test_showimage_cam2image__rmw_fastrtps_.py'
11+
# that contains the test from test_showimage_cam2image.py.in, customized
12+
# for the rmw_implementation we want to test and for absolute paths of this
13+
# installation. To do that, we override the 'install_scripts' stage of
14+
# setuptools, since that is the stage that knows the paths to the 'cam2image_py'
15+
# and 'showimage_py' executables.
16+
#
17+
# TODO(clalancette): One downside to what is being done below is that the output
18+
# file is being left in the source directory. That's currently necessary
19+
# because the pytest invocation only looks there for test scripts. It would
20+
# be nicer to generate the output file in the 'build' directory and then point
21+
# pytest at it, but I don't know how to do that.
22+
class custom_install_scripts(install_scripts):
23+
24+
def run(self):
25+
rmw_implementations = ['rmw_fastrtps_cpp']
26+
27+
for rmw_impl in rmw_implementations:
28+
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')),
34+
}
35+
36+
infile = os.path.join('test', 'test_showimage_cam2image.py.in')
37+
outfile = os.path.join('test', 'test_showimage_cam2image__%s_.py' % (rmw_impl))
38+
with open(infile, 'r') as infp:
39+
with open(outfile, 'w') as outfp:
40+
for line in infp:
41+
for subst in substs:
42+
line = line.replace(subst, "'%s' # noqa" % (substs[subst]))
43+
outfp.write(line)
44+
45+
install_scripts.run(self)
46+
47+
548
setup(
649
name=package_name,
750
version='0.0.0',
@@ -19,9 +62,9 @@
1962
install_requires=['setuptools'],
2063
zip_safe=True,
2164
author='Chris Lalancette',
22-
author_email='clalancette@osrfoundation.org',
65+
author_email='clalancette@openrobotics.org',
2366
maintainer='Chris Lalancette',
24-
maintainer_email='clalancette@osrfoundation.org',
67+
maintainer_email='clalancette@openrobotics.org',
2568
keywords=['ROS'],
2669
classifiers=[
2770
'Intended Audience :: Developers',
@@ -38,4 +81,5 @@
3881
'showimage_py = showimage_py:main',
3982
],
4083
},
84+
cmdclass={'install_scripts': custom_install_scripts},
4185
)
Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
Publishing data on topic 'image'
2+
Publishing image #1
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
Received image #\d+

image_tools_py/test/test_flake8.py

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
# Copyright 2017 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_flake8.main import main
16+
import pytest
17+
18+
19+
@pytest.mark.flake8
20+
@pytest.mark.linter
21+
def test_flake8():
22+
rc = main(argv=[])
23+
assert rc == 0, 'Found errors'
Lines changed: 102 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,102 @@
1+
# Copyright 2016 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
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()

0 commit comments

Comments
 (0)