Skip to content

Commit 92400b4

Browse files
authored
* [launch_pytest] Fix issue when colcon --retest-until-fail flag is used (#552)
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
1 parent edcca09 commit 92400b4

File tree

7 files changed

+54
-21
lines changed

7 files changed

+54
-21
lines changed

launch_pytest/test/launch_pytest/examples/check_node_msgs.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,11 +39,12 @@ def generate_test_description():
3939
arguments=[str(path_to_test / 'executables' / 'talker.py')],
4040
additional_env={'PYTHONUNBUFFERED': '1'},
4141
name='demo_node_1',
42+
output='screen',
4243
),
4344
])
4445

4546

46-
@pytest.mark.launch
47+
@pytest.mark.launch(fixture=generate_test_description)
4748
def test_check_if_msgs_published():
4849
rclpy.init()
4950
try:

launch_pytest/test/launch_pytest/examples/executables/listener.py renamed to launch_pytest/test/launch_pytest/examples/executables/talker.py

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -18,22 +18,26 @@
1818
from std_msgs.msg import String
1919

2020

21-
class Listener(Node):
21+
class Talker(Node):
2222

2323
def __init__(self):
24-
super().__init__('listener')
25-
self.subscription = self.create_subscription(
26-
String, 'chatter', self.callback, 10
27-
)
24+
super().__init__('talker')
25+
self.count = 0
26+
self.publisher = self.create_publisher(String, 'chatter', 10)
27+
self.timer = self.create_timer(1.0, self.callback)
2828

29-
def callback(self, msg):
30-
self.get_logger().info('I heard: [%s]' % msg.data)
29+
def callback(self):
30+
data = 'Hello World: {0}'.format(self.count)
31+
self.get_logger().info('Publishing: "{0}"'.format(data))
32+
self.publisher.publish(String(data=data))
33+
self.count += 1
3134

3235

3336
def main(args=None):
3437
rclpy.init(args=args)
3538

36-
node = Listener()
39+
node = Talker()
40+
3741
try:
3842
rclpy.spin(node)
3943
except KeyboardInterrupt:

launch_pytest/test/launch_pytest/examples/pytest_hello_world.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,8 @@ def test_read_stdout(hello_world_proc, launch_context):
4949
def validate_output(output):
5050
# this function can use assertions to validate the output or return a boolean.
5151
# pytest generates easier to understand failures when assertions are used.
52-
assert output == 'hello_world\n', 'process never printed hello_world'
52+
assert output.splitlines() == ['hello_world'], 'process never printed hello_world'
53+
return True
5354
assert process_tools.wait_for_output_sync(
5455
launch_context, hello_world_proc, validate_output, timeout=5)
5556

launch_pytest/test/launch_pytest/test_plugin.py

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,9 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
from pathlib import Path
16+
import shutil
17+
1518

1619
def test_launch_fixture_is_not_a_launch_description(testdir):
1720
testdir.makepyfile("""\
@@ -313,3 +316,17 @@ async def test_case():
313316
result = testdir.runpytest()
314317

315318
result.assert_outcomes(failed=1, skipped=1)
319+
320+
321+
def test_examples(testdir):
322+
examples_dir = Path(__file__).parent / 'examples'
323+
for example in examples_dir.iterdir():
324+
# Ignoring `check_node_msgs.py` because we cannot depend on launch_ros here
325+
# as it creates a circular dependency between repositories.
326+
# We need to move that example elsewhere.
327+
if example.is_file() and example.name != 'check_node_msgs.py':
328+
copied_example = Path(testdir.copy_example(example))
329+
copied_example.rename(copied_example.parent / f'test_{copied_example.name}')
330+
shutil.copytree(examples_dir / 'executables', Path(str(testdir.tmpdir)) / 'executables')
331+
result = testdir.runpytest()
332+
result.assert_outcomes(passed=22)

launch_pytest/test/launch_pytest/tools/test_process.py

Lines changed: 21 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -48,25 +48,35 @@ def launch_description(dut):
4848

4949
@pytest.mark.launch(fixture=launch_description)
5050
async def test_async_process_tools(dut, launch_context):
51-
await tools.wait_for_start(launch_context, dut, timeout=10)
52-
def check_output(output): assert output.splitlines() == ['hello']
53-
await tools.wait_for_output(
51+
assert await tools.wait_for_start(launch_context, dut, timeout=10)
52+
53+
def check_output(output):
54+
assert output.splitlines() == ['hello']
55+
return True
56+
assert await tools.wait_for_output(
5457
launch_context, dut, check_output, timeout=10)
5558

56-
def check_stderr(err): assert err.splitlines() == ['world']
57-
await tools.wait_for_stderr(
59+
def check_stderr(err):
60+
assert err.splitlines() == ['world']
61+
return True
62+
assert await tools.wait_for_stderr(
5863
launch_context, dut, check_stderr, timeout=10)
59-
await tools.wait_for_exit(launch_context, dut, timeout=10)
64+
assert await tools.wait_for_exit(launch_context, dut, timeout=10)
6065

6166

6267
@pytest.mark.launch(fixture=launch_description)
6368
def test_sync_process_tools(dut, launch_context):
6469
tools.wait_for_start_sync(launch_context, dut, timeout=10)
65-
def check_output(output): assert output.splitlines() == ['hello']
66-
tools.wait_for_output_sync(
70+
71+
def check_output(output):
72+
assert output.splitlines() == ['hello']
73+
return True
74+
assert tools.wait_for_output_sync(
6775
launch_context, dut, check_output, timeout=10)
6876

69-
def check_stderr(err): assert err.splitlines() == ['world']
70-
tools.wait_for_stderr_sync(
77+
def check_stderr(err):
78+
assert err.splitlines() == ['world']
79+
return True
80+
assert tools.wait_for_stderr_sync(
7181
launch_context, dut, check_stderr, timeout=10)
72-
tools.wait_for_exit_sync(launch_context, dut, timeout=10)
82+
assert tools.wait_for_exit_sync(launch_context, dut, timeout=10)

0 commit comments

Comments
 (0)