From c2acb1921a6467c1846b7f6cab4a76f89b98bda3 Mon Sep 17 00:00:00 2001 From: mauropasse Date: Wed, 21 Aug 2024 10:36:00 +0100 Subject: [PATCH] Always publish inter-process on TRANSIENT_LOCAL publishers (#152) Co-authored-by: Mauro Passerino --- rclcpp/include/rclcpp/publisher.hpp | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 654b1e210a..19df759334 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -275,7 +275,11 @@ class Publisher : public PublisherBase bool inter_process_publish_needed = get_subscription_count() > get_intra_process_subscription_count(); - if (inter_process_publish_needed) { + // If the publisher is configured with transient local durability, we must publish + // inter-process. This ensures that the RMW stores the messages for late joiner subscriptions. + // This has the consequence of subscriptions experiencing the double-delivery issue + // mentioned in https://github.com/ros2/rclcpp/issues/1750 + if (inter_process_publish_needed || buffer_) { auto shared_msg = this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg)); if (buffer_) { @@ -283,13 +287,7 @@ class Publisher : public PublisherBase } this->do_inter_process_publish(*shared_msg); } else { - if (buffer_) { - auto shared_msg = - this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg)); - buffer_->add_shared(shared_msg); - } else { - this->do_intra_process_ros_message_publish(std::move(msg)); - } + this->do_intra_process_ros_message_publish(std::move(msg)); } }