ros2 latching
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.
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.
Did you ever get this to work? And if so, how?
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.