Skip to content

Commit

Permalink
Fix output mismatches and extend timeouts.
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed Oct 18, 2019
1 parent cbea51d commit 8f2f2d1
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
4 changes: 2 additions & 2 deletions ros2node/test/test_cli.py
Original file line number Diff line number Diff line change
Expand Up @@ -172,9 +172,9 @@ def test_info_node(self):
], itertools.repeat(re.compile(
r'\s*/complex_node/.*parameter.*: rcl_interfaces/srv/.*Parameter.*'
), 6), [
' Actions Servers:',
' Action Servers:',
' /fibonacci: test_msgs/action/Fibonacci',
' Actions Clients:',
' Action Clients:',
''
]),
text=node_command.output, strict=False
Expand Down
12 changes: 6 additions & 6 deletions ros2topic/test/test_cli.py
Original file line number Diff line number Diff line change
Expand Up @@ -402,7 +402,7 @@ def test_no_arr_topic_echo_on_array_message(self):
'alignment_check: 0',
'---'
], strict=False
), timeout=5), 'Output does not match: ' + topic_command.output
), timeout=10), 'Output does not match: ' + topic_command.output
assert topic_command.wait_for_shutdown(timeout=5)

@launch_testing.markers.retry_on_failure(times=5)
Expand Down Expand Up @@ -446,7 +446,7 @@ def test_no_arr_topic_echo_on_seq_message(self):
'alignment_check: 0',
'---'
], strict=True
), timeout=5)
), timeout=10)
assert topic_command.wait_for_shutdown(timeout=5)

@launch_testing.markers.retry_on_failure(times=5)
Expand Down Expand Up @@ -491,7 +491,7 @@ def test_no_arr_topic_echo_on_bounded_seq_message(self):
'alignment_check: 0',
'---'
], strict=True
), timeout=5)
), timeout=10)
assert topic_command.wait_for_shutdown(timeout=5)

@launch_testing.markers.retry_on_failure(times=5)
Expand Down Expand Up @@ -540,7 +540,7 @@ def test_topic_pub_once(self):
"publishing #1: std_msgs.msg.String(data='bar')",
''
], strict=True
), timeout=5)
), timeout=10)
assert topic_command.wait_for_shutdown(timeout=5)
self.listener_node.wait_for_output(functools.partial(
launch_testing.tools.expect_output, expected_lines=[
Expand All @@ -567,12 +567,12 @@ def test_topic_pub_print_every_two(self):
"publishing #4: std_msgs.msg.String(data='fizz')",
''
], strict=True
), timeout=6), 'Output does not match: ' + topic_command.output
), timeout=10), 'Output does not match: ' + topic_command.output
self.listener_node.wait_for_output(functools.partial(
launch_testing.tools.expect_output, expected_lines=[
'[INFO] [listener]: I heard: [fizz]'
], strict=True
), timeout=5)
), timeout=10)
assert topic_command.wait_for_shutdown(timeout=5)

@launch_testing.markers.retry_on_failure(times=5)
Expand Down

0 comments on commit 8f2f2d1

Please sign in to comment.