Skip to content

Commit 31d814d

Browse files
authored
Adapt tests to Zenoh (#988)
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
1 parent c24c7b5 commit 31d814d

File tree

3 files changed

+44
-4
lines changed

3 files changed

+44
-4
lines changed

ros2topic/test/test_bw_delay_hz.py

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@
3333
import rclpy
3434
from rclpy.executors import SingleThreadedExecutor
3535
from rclpy.qos import DurabilityPolicy
36+
from rclpy.qos import qos_check_compatible
37+
from rclpy.qos import QoSCompatibility
3638
from rclpy.qos import QoSProfile
3739
from rclpy.qos import ReliabilityPolicy
3840
from rclpy.utilities import get_rmw_implementation_identifier
@@ -115,10 +117,22 @@ def helper_verb_basic(self, launch_service, proc_info, proc_output, verb, succes
115117
verb_extra_options = [
116118
'--qos-reliability', 'reliable',
117119
'--qos-durability', 'transient_local']
120+
# This QoS profile matched with the extra options defined above
121+
rostopic_qos_profile = QoSProfile(
122+
depth=10,
123+
reliability=ReliabilityPolicy.RELIABLE,
124+
durability=DurabilityPolicy.TRANSIENT_LOCAL)
118125
publisher_qos_profile = QoSProfile(
119126
depth=10,
120127
reliability=ReliabilityPolicy.BEST_EFFORT,
121128
durability=DurabilityPolicy.VOLATILE)
129+
# Skip this test if the QoS between the publisher and subscription
130+
# are compatible according to the underlying middleware.
131+
comp, reason = qos_check_compatible(
132+
rostopic_qos_profile, publisher_qos_profile)
133+
if comp == QoSCompatibility.OK or comp == QoSCompatibility.WARNING:
134+
raise unittest.SkipTest()
135+
122136
publisher = self.node.create_publisher(PointStamped, topic, publisher_qos_profile)
123137
assert publisher
124138

ros2topic/test/test_echo_pub.py

Lines changed: 28 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
import functools
1616
import pathlib
17+
import re
1718
import sys
1819
import unittest
1920

@@ -32,6 +33,8 @@
3233
import rclpy
3334
from rclpy.executors import SingleThreadedExecutor
3435
from rclpy.qos import DurabilityPolicy
36+
from rclpy.qos import qos_check_compatible
37+
from rclpy.qos import QoSCompatibility
3538
from rclpy.qos import QoSProfile
3639
from rclpy.qos import ReliabilityPolicy
3740
from rclpy.utilities import get_rmw_implementation_identifier
@@ -124,12 +127,23 @@ def test_pub_basic(self, launch_service, proc_info, proc_output):
124127
pub_extra_options = [
125128
'--qos-reliability', 'best_effort',
126129
'--qos-durability', 'volatile']
130+
# This QoS profile matched with the extra options defined above
131+
rostopic_qos_profile = QoSProfile(
132+
depth=10,
133+
reliability=ReliabilityPolicy.BEST_EFFORT,
134+
durability=DurabilityPolicy.VOLATILE)
127135
subscription_qos_profile = QoSProfile(
128136
depth=10,
129137
reliability=ReliabilityPolicy.RELIABLE,
130138
durability=DurabilityPolicy.TRANSIENT_LOCAL)
131139
expected_maximum_message_count = 0
132140
expected_minimum_message_count = 0
141+
# Skip this test if the QoS between the publisher and subscription
142+
# are compatible according to the underlying middleware.
143+
comp, reason = qos_check_compatible(
144+
rostopic_qos_profile, subscription_qos_profile)
145+
if comp == QoSCompatibility.OK:
146+
raise unittest.SkipTest()
133147

134148
future = rclpy.task.Future()
135149

@@ -363,6 +377,17 @@ def test_echo_basic(self, launch_service, proc_info, proc_output):
363377
depth=10,
364378
reliability=ReliabilityPolicy.BEST_EFFORT,
365379
durability=DurabilityPolicy.VOLATILE)
380+
# This QoS profile matched with the extra options defined above
381+
rostopic_qos_profile = QoSProfile(
382+
depth=10,
383+
reliability=ReliabilityPolicy.RELIABLE,
384+
durability=DurabilityPolicy.TRANSIENT_LOCAL)
385+
# Skip this test if the QoS between the publisher and subscription
386+
# are compatible according to the underlying middleware.
387+
comp, reason = qos_check_compatible(
388+
rostopic_qos_profile, publisher_qos_profile)
389+
if comp == QoSCompatibility.OK or comp == QoSCompatibility.WARNING:
390+
raise unittest.SkipTest()
366391
if not message_lost:
367392
echo_extra_options.append('--no-lost-messages')
368393
publisher = self.node.create_publisher(String, topic, publisher_qos_profile)
@@ -494,9 +519,9 @@ def publish_message():
494519
)
495520
assert command.wait_for_output(functools.partial(
496521
launch_testing.tools.expect_output, expected_lines=[
497-
"b'\\x00\\x01\\x00\\x00\\x06\\x00\\x00\\x00hello\\x00\\x00\\x00'",
498-
'---',
499-
], strict=True
522+
re.compile(r"^b'\\x00\\x01\\x00\\x00\\x06\\x00\\x00\\x00hello(\\x00)*'$"),
523+
re.compile(r'^---$'),
524+
], strict=False
500525
), timeout=10), 'Echo CLI did not print expected message'
501526
assert command.wait_for_shutdown(timeout=10)
502527

ros2topic/test/test_use_sim_time.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -264,7 +264,8 @@ def publish_message():
264264
launch_testing.tools.expect_output, expected_lines=[
265265
# without speed up, the average band width should be 16 B
266266
re.compile(r'8 B/s from \d+ messages'),
267-
re.compile(r'\s*Message size mean: 16 B min: 16 B max: 16 B')
267+
re.compile(
268+
r'\s*Message size mean: (14|16) B min: (14|16) B max: (14|16) B')
268269
], strict=False
269270
), timeout=10), 'Echo CLI did not print expected message'
270271
assert command.wait_for_shutdown(timeout=5)

0 commit comments

Comments
 (0)