1
$\begingroup$

Rosanswers logo

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/304645/ros2-robot-state-publisher-publishes-empty-robot_description/

I'm using FastRTPS.

Thanks.


Originally posted by clyde on ROS Answers with karma: 1247 on 2018-10-14

Post score: 8


Original comments

Comment by clyde on 2018-10-15:
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.

Comment by ahlyder on 2019-06-04:
Did you ever get this to work? And if so, how?

Comment by clyde on 2019-06-06:
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.

$\endgroup$

2 Answers 2

1
$\begingroup$

Rosanswers logo

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.


Originally posted by jubeira with karma: 1054 on 2019-07-03

This answer was ACCEPTED on the original site

Post score: 4


Original comments

Comment by clyde on 2019-07-03:
This works! The upshot is that ros2 topic echo won't match transient local topics. Thanks!

$\endgroup$
0
$\begingroup$

Rosanswers logo

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/blob/6788c1b78fe35e1a459a9d8f184afeb79792bd71/tf2_ros/src/tf2_ros/static_transform_broadcaster.py#L55


Originally posted by lukicdarkoo with karma: 486 on 2020-04-03

This answer was NOT ACCEPTED on the original site

Post score: 6


Original comments

Comment by clyde on 2020-05-04:
Ah, very cool. IIUC this was added in Eloquent. https://github.com/ros2/ros2cli/pull/283

Good point on DurabilityPolicy.TRANSIENT_LOCAL.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.