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

Revision history [back]

click to hide/show revision 1
initial version

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. Also using FastRTPS.

Hope it helps!

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. Also using FastRTPS.

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.

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. Also I've tested it using FastRTPS.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.