Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adapt tests to Zenoh (backport #988) #991

Merged
merged 3 commits into from
Mar 21, 2025
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
31 changes: 28 additions & 3 deletions ros2topic/test/test_echo_pub.py
Original file line number Diff line number Diff line change
@@ -13,6 +13,7 @@
# limitations under the License.

import functools
import re
import sys
import unittest

@@ -31,6 +32,8 @@
import rclpy
from rclpy.executors import SingleThreadedExecutor
from rclpy.qos import DurabilityPolicy
from rclpy.qos import qos_check_compatible
from rclpy.qos import QoSCompatibility
from rclpy.qos import QoSProfile
from rclpy.qos import ReliabilityPolicy
from rclpy.utilities import get_rmw_implementation_identifier
@@ -126,12 +129,23 @@ def test_pub_basic(self, launch_service, proc_info, proc_output):
pub_extra_options = [
'--qos-reliability', 'best_effort',
'--qos-durability', 'volatile']
# This QoS profile matched with the extra options defined above
rostopic_qos_profile = QoSProfile(
depth=10,
reliability=ReliabilityPolicy.BEST_EFFORT,
durability=DurabilityPolicy.VOLATILE)
subscription_qos_profile = QoSProfile(
depth=10,
reliability=ReliabilityPolicy.RELIABLE,
durability=DurabilityPolicy.TRANSIENT_LOCAL)
expected_maximum_message_count = 0
expected_minimum_message_count = 0
# Skip this test if the QoS between the publisher and subscription
# are compatible according to the underlying middleware.
comp, reason = qos_check_compatible(
rostopic_qos_profile, subscription_qos_profile)
if comp == QoSCompatibility.OK:
raise unittest.SkipTest()

future = rclpy.task.Future()

@@ -329,6 +343,17 @@ def test_echo_basic(self, launch_service, proc_info, proc_output):
depth=10,
reliability=ReliabilityPolicy.BEST_EFFORT,
durability=DurabilityPolicy.VOLATILE)
# This QoS profile matched with the extra options defined above
rostopic_qos_profile = QoSProfile(
depth=10,
reliability=ReliabilityPolicy.RELIABLE,
durability=DurabilityPolicy.TRANSIENT_LOCAL)
# Skip this test if the QoS between the publisher and subscription
# are compatible according to the underlying middleware.
comp, reason = qos_check_compatible(
rostopic_qos_profile, publisher_qos_profile)
if comp == QoSCompatibility.OK or comp == QoSCompatibility.WARNING:
raise unittest.SkipTest()
if not message_lost:
echo_extra_options.append('--no-lost-messages')
publisher = self.node.create_publisher(String, topic, publisher_qos_profile)
@@ -460,9 +485,9 @@ def publish_message():
)
assert command.wait_for_output(functools.partial(
launch_testing.tools.expect_output, expected_lines=[
"b'\\x00\\x01\\x00\\x00\\x06\\x00\\x00\\x00hello\\x00\\x00\\x00'",
'---',
], strict=True
re.compile(r"^b'\\x00\\x01\\x00\\x00\\x06\\x00\\x00\\x00hello(\\x00)*'$"),
re.compile(r'^---$'),
], strict=False
), timeout=10), 'Echo CLI did not print expected message'
assert command.wait_for_shutdown(timeout=10)

3 changes: 2 additions & 1 deletion ros2topic/test/test_use_sim_time.py
Original file line number Diff line number Diff line change
@@ -264,7 +264,8 @@ def publish_message():
launch_testing.tools.expect_output, expected_lines=[
# without speed up, the average band width should be 16 B
re.compile(r'8 B/s from \d+ messages'),
re.compile(r'\s*Message size mean: 16 B min: 16 B max: 16 B')
re.compile(
r'\s*Message size mean: (14|16) B min: (14|16) B max: (14|16) B')
], strict=False
), timeout=10), 'Echo CLI did not print expected message'
assert command.wait_for_shutdown(timeout=5)