ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
8

ros2 latching

asked 2018-10-14 18:49:51 -0500

clyde gravatar image

updated 2018-10-14 19:01:52 -0500

I can't get message latching (transient local durability) to work in Bouncy. Here's my Python test case:

#!/usr/bin/env python

import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile, QoSDurabilityPolicy
from std_msgs.msg import String


class Latching(Node):

    def __init__(self):
        super().__init__('latching')
        latching_qos = QoSProfile(depth=1,
            durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL)
        pub = self.create_publisher(String, 'foo', qos_profile=latching_qos)
        msg = String(data='test')
        pub.publish(msg)


def main(args=None):
    rclpy.init(args=args)
    node = Latching()

    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        node.get_logger().info("Ctrl-C detected, shutting down")
    finally:
        node.destroy_node()
        rclpy.shutdown()


if __name__ == '__main__':
    main()

When I run ros2 topic echo /foo std_msgs/String first, then run my node, I see message test published on topic /foo as expected.

However, when I run my node before running ros2 topic echo /foo std_msgs/String, nothing shows up. Shouldn't I see the latched message?

I wonder if this might be related to https://answers.ros.org/question/3046...

I'm using FastRTPS.

Thanks.

edit retag flag offensive close merge delete

Comments

I just tested this w/ a Python listener with the same QoS. Still no luck: if the publisher runs first, then the subscriber gets the message. If the publisher runs second, the subscriber never gets the message.

clyde gravatar image clyde  ( 2018-10-15 13:48:22 -0500 )edit

Did you ever get this to work? And if so, how?

ahlyder gravatar image ahlyder  ( 2019-06-04 06:31:19 -0500 )edit

I did not. Workarounds: (1) for rviz, read the URDF from a file, not from a message. (2) publish static messages periodically, perhaps once every 5s.

clyde gravatar image clyde  ( 2019-06-06 13:25:01 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
4

answered 2019-07-03 12:07:10 -0500

jubeira gravatar image

updated 2019-07-03 12:11:28 -0500

I haven't tried Bouncy, but as of today's Dashing this slightly modified code taken from the question works for me:

#!/usr/bin/env python3

import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile, QoSDurabilityPolicy
from std_msgs.msg import String


class Latching(Node):

    def __init__(self):
        super().__init__('latching_sub')
        latching_qos = QoSProfile(depth=1,
            durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL)
        sub = self.create_subscription(String, 'foo', self.callback, qos_profile=latching_qos)

    def callback(self, str_msg):
        self.get_logger().info('Got message: ' + str(str_msg))


def main(args=None):
    rclpy.init(args=args)
    node = Latching()

    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        node.get_logger().info("Ctrl-C detected, shutting down")
    finally:
        node.destroy_node()
        rclpy.shutdown()

if __name__ == '__main__':
    main()

No matter the order I run the two nodes (publisher first and subscriber second or vice-versa), I always see the callback in the subscriber called. I've tested it using FastRTPS as well.

Hope it helps!

PS: for reference, this issue has a good summary of the differences between ROS1 latching and transient local settings: https://github.com/ros2/ros2/issues/464.

edit flag offensive delete link more

Comments

This works! The upshot is that ros2 topic echo won't match transient local topics. Thanks!

clyde gravatar image clyde  ( 2019-07-03 15:50:15 -0500 )edit
6

answered 2020-04-03 06:09:10 -0500

lukicdarkoo gravatar image

updated 2020-04-03 06:10:45 -0500

You can use ros2 topic echo, you just need to set correct QoS profile and durability:

ros2 topic echo --qos-profile services_default --qos-durability transient_local foo


BTW, maybe it is better to use DurabilityPolicy.TRANSIENT_LOCAL instead of QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL as it is done in static_transform_broadcaster: https://github.com/ros2/geometry2/blo...

edit flag offensive delete link more

Comments

Ah, very cool. IIUC this was added in Eloquent. https://github.com/ros2/ros2cli/pull/283

Good point on DurabilityPolicy.TRANSIENT_LOCAL.

clyde gravatar image clyde  ( 2020-05-04 13:48:52 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2018-10-14 18:49:51 -0500

Seen: 5,317 times

Last updated: Apr 03 '20