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

use transient_local and longer keep-alive for pub tests #546

Merged
merged 2 commits into from
Jul 6, 2020
Merged
Show file tree
Hide file tree
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
6 changes: 4 additions & 2 deletions ros2topic/test/fixtures/listener_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand All @@ -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):
Expand Down
13 changes: 12 additions & 1 deletion ros2topic/test/test_cli.py
Original file line number Diff line number Diff line change
Expand Up @@ -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=[
Expand All @@ -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}'
Expand All @@ -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}'
Expand Down