From b2934f12d742222e40284596d57eead8281ce846 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 30 Jun 2020 14:48:31 -0700 Subject: [PATCH 1/4] add --keep-alive option to 'topic pub' (#544) Signed-off-by: Dirk Thomas Signed-off-by: Shane Loretz --- ros2topic/ros2topic/verb/pub.py | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/ros2topic/ros2topic/verb/pub.py b/ros2topic/ros2topic/verb/pub.py index e546008af..03d52082e 100644 --- a/ros2topic/ros2topic/verb/pub.py +++ b/ros2topic/ros2topic/verb/pub.py @@ -83,6 +83,10 @@ def add_arguments(self, parser, cli_name): group.add_argument( '-t', '--times', type=nonnegative_int, default=0, help='Publish this number of times and then exit') + parser.add_argument( + '--keep-alive', metavar='N', type=positive_float, default=0.1, + help='Keep publishing node alive for N seconds after the last msg ' + '(default: 0.1)') parser.add_argument( '-n', '--node-name', help='Name of the created publishing node') @@ -108,7 +112,8 @@ def main(args): 1. / args.rate, args.print, times, - qos_profile) + qos_profile, + args.keep_alive) def publisher( @@ -120,6 +125,7 @@ def publisher( print_nth: int, times: int, qos_profile: QoSProfile, + keep_alive: float, ) -> Optional[str]: """Initialize a node with a single publisher and run its publish loop (maybe only once).""" msg_module = get_message(message_type) @@ -149,7 +155,7 @@ def timer_callback(): while times == 0 or count < times: rclpy.spin_once(node) - if times == 1: - time.sleep(0.1) # make sure the message reaches the wire before exiting + # give some time for the messages to reach the wire before exiting + time.sleep(keep_alive) node.destroy_timer(timer) From fbb83da41a0c7f7fc99814fab5473a333efcd3d0 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 9 Sep 2020 16:47:28 -0700 Subject: [PATCH 2/4] Give kwarg default value for backporting keep_alive is made a keyword argument with a default value of 0.1 so the pull request can be backported. Signed-off-by: Shane Loretz Signed-off-by: Shane Loretz --- ros2topic/ros2topic/verb/pub.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros2topic/ros2topic/verb/pub.py b/ros2topic/ros2topic/verb/pub.py index 03d52082e..6479570c7 100644 --- a/ros2topic/ros2topic/verb/pub.py +++ b/ros2topic/ros2topic/verb/pub.py @@ -125,7 +125,7 @@ def publisher( print_nth: int, times: int, qos_profile: QoSProfile, - keep_alive: float, + keep_alive: float = 0.1, ) -> Optional[str]: """Initialize a node with a single publisher and run its publish loop (maybe only once).""" msg_module = get_message(message_type) From 9c8a7ec889c9a264fa8120216aa83f9f267278bf Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Mon, 6 Jul 2020 10:21:17 -0700 Subject: [PATCH 3/4] use transient_local and longer keep-alive for pub tests (#546) * use transient_local and longer keep-alive for pub tests Signed-off-by: Dirk Thomas * add comment to document unit of --keep-alive Signed-off-by: Dirk Thomas Signed-off-by: Shane Loretz --- ros2topic/test/fixtures/listener_node.py | 6 ++++-- ros2topic/test/test_cli.py | 13 ++++++++++++- 2 files changed, 16 insertions(+), 3 deletions(-) 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}' From c58aa743f87963fc60cde2df51a1d04f6450012f Mon Sep 17 00:00:00 2001 From: Scott K Logan Date: Fri, 31 Jul 2020 10:15:49 -0700 Subject: [PATCH 4/4] Use reliable QoS for ros2topic tests (#555) The TestROS2TopicCLI tests perform feature testing of the ros2topic command line interface. If the system is under stress during these tests, messages may be lost (by design). If that happens, there is a fairly high likelihood that the test_topic_pub_once test will fail because there is only one opportunity for the message to be successfully transported. We're likely dropping other messages in this suite, but the other tests continuously publish until one of the messages is received (or a timeout occurs), making them significantly less likely to fail. Using the 'reliable' setting for QoS reliability seems to make the tests consistently pass, even when the system is placed under additional stress. Signed-off-by: Scott K Logan Signed-off-by: Shane Loretz --- ros2topic/test/fixtures/listener_node.py | 3 ++- ros2topic/test/test_cli.py | 3 +++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ros2topic/test/fixtures/listener_node.py b/ros2topic/test/fixtures/listener_node.py index f6355ddff..71fa79b9f 100644 --- a/ros2topic/test/fixtures/listener_node.py +++ b/ros2topic/test/fixtures/listener_node.py @@ -26,7 +26,8 @@ class ListenerNode(Node): def __init__(self): super().__init__('listener') qos_profile = qos_profile_from_short_keys( - 'system_default', durability='transient_local') + 'system_default', durability='transient_local', + reliability='reliable') self.sub = self.create_subscription( String, 'chatter', self.callback, qos_profile ) diff --git a/ros2topic/test/test_cli.py b/ros2topic/test/test_cli.py index 15e278790..0173ff91c 100644 --- a/ros2topic/test/test_cli.py +++ b/ros2topic/test/test_cli.py @@ -563,6 +563,7 @@ def test_topic_pub(self): 'pub', '--keep-alive', '3', # seconds '--qos-durability', 'transient_local', + '--qos-reliability', 'reliable', '/chit_chatter', 'std_msgs/msg/String', '{data: foo}' @@ -588,6 +589,7 @@ def test_topic_pub_once(self): 'pub', '--once', '--keep-alive', '3', # seconds '--qos-durability', 'transient_local', + '--qos-reliability', 'reliable', '/chit_chatter', 'std_msgs/msg/String', '{data: bar}' @@ -615,6 +617,7 @@ def test_topic_pub_print_every_two(self): '-p', '2', '--keep-alive', '3', # seconds '--qos-durability', 'transient_local', + '--qos-reliability', 'reliable', '/chit_chatter', 'std_msgs/msg/String', '{data: fizz}'