diff --git a/ros2topic/test/fixtures/listener_node.py b/ros2topic/test/fixtures/listener_node.py index 8ee4fddfa..f6355ddff 100644 --- a/ros2topic/test/fixtures/listener_node.py +++ b/ros2topic/test/fixtures/listener_node.py @@ -16,7 +16,7 @@ import rclpy from rclpy.node import Node -from rclpy.qos import qos_profile_system_default +from ros2topic.api import qos_profile_from_short_keys from std_msgs.msg import String @@ -25,8 +25,10 @@ class ListenerNode(Node): def __init__(self): super().__init__('listener') + qos_profile = qos_profile_from_short_keys( + 'system_default', durability='transient_local') self.sub = self.create_subscription( - String, 'chatter', self.callback, qos_profile_system_default + String, 'chatter', self.callback, qos_profile ) def callback(self, msg): diff --git a/ros2topic/test/test_cli.py b/ros2topic/test/test_cli.py index 565c4935c..15e278790 100644 --- a/ros2topic/test/test_cli.py +++ b/ros2topic/test/test_cli.py @@ -559,7 +559,14 @@ def test_topic_echo_no_publisher(self): def test_topic_pub(self): with self.launch_topic_command( - arguments=['pub', '/chit_chatter', 'std_msgs/msg/String', '{data: foo}'], + arguments=[ + 'pub', + '--keep-alive', '3', # seconds + '--qos-durability', 'transient_local', + '/chit_chatter', + 'std_msgs/msg/String', + '{data: foo}' + ], ) as topic_command: assert topic_command.wait_for_output(functools.partial( launch_testing.tools.expect_output, expected_lines=[ @@ -579,6 +586,8 @@ def test_topic_pub_once(self): with self.launch_topic_command( arguments=[ 'pub', '--once', + '--keep-alive', '3', # seconds + '--qos-durability', 'transient_local', '/chit_chatter', 'std_msgs/msg/String', '{data: bar}' @@ -604,6 +613,8 @@ def test_topic_pub_print_every_two(self): arguments=[ 'pub', '-p', '2', + '--keep-alive', '3', # seconds + '--qos-durability', 'transient_local', '/chit_chatter', 'std_msgs/msg/String', '{data: fizz}'