From 53bec8ffda2a494cde8173e95cd1746242b62f4a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Sat, 20 Apr 2024 22:48:34 +0200 Subject: [PATCH 01/15] Add option for Publisher plugins to support publishing using Unique Ptr --- .../image_transport/publisher_plugin.hpp | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/image_transport/include/image_transport/publisher_plugin.hpp b/image_transport/include/image_transport/publisher_plugin.hpp index d899349e..79350dca 100644 --- a/image_transport/include/image_transport/publisher_plugin.hpp +++ b/image_transport/include/image_transport/publisher_plugin.hpp @@ -59,6 +59,14 @@ class PublisherPlugin */ virtual std::string getTransportName() const = 0; + /** + * \brief Check whether this plugin supports publishing using UniquePtr. + */ + virtual bool supportsUniquePtrPub() const + { + return false; + } + /** * \brief Advertise a topic, simple version. */ @@ -95,6 +103,18 @@ class PublisherPlugin publish(*message); } + /** + * \brief Publish an image using the transport associated with this PublisherPlugin. + * This version of the function can be used to optimize cases where the Plugin can + * avoid doing copies of the data when having the ownership to the image message. + * Plugins that can take advantage of message ownership should overwrite this method + * along with supportsUniquePtrPub(). + */ + virtual void publishUniquePtr(sensor_msgs::msg::Image::UniquePtr message) const + { + publish(*message); + } + /** * \brief Publish an image using the transport associated with this PublisherPlugin. * This version of the function can be used to optimize cases where you don't want to From 02fec9823a643770818048465dbe760c203110b9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Sat, 20 Apr 2024 22:50:00 +0200 Subject: [PATCH 02/15] Implement publishUniquePtr in simple publisher plugin --- .../simple_publisher_plugin.hpp | 35 +++++++++++++++++-- 1 file changed, 32 insertions(+), 3 deletions(-) diff --git a/image_transport/include/image_transport/simple_publisher_plugin.hpp b/image_transport/include/image_transport/simple_publisher_plugin.hpp index f088c874..f29af8d7 100644 --- a/image_transport/include/image_transport/simple_publisher_plugin.hpp +++ b/image_transport/include/image_transport/simple_publisher_plugin.hpp @@ -89,7 +89,20 @@ class SimplePublisherPlugin : public PublisherPlugin return; } - publish(message, bindInternalPublisher(simple_impl_->pub_.get())); + publish(message, simple_impl_->pub_); + } + + void publishUniquePtr(sensor_msgs::msg::Image::UniquePtr message) const override + { + if (!simple_impl_ || !simple_impl_->pub_) { + auto logger = simple_impl_ ? simple_impl_->logger_ : rclcpp::get_logger("image_transport"); + RCLCPP_ERROR( + logger, + "Call to publish() on an invalid image_transport::SimplePublisherPlugin"); + return; + } + + publish(std::move(message), simple_impl_->pub_); } void shutdown() override @@ -112,6 +125,8 @@ class SimplePublisherPlugin : public PublisherPlugin simple_impl_->pub_ = node->create_publisher(transport_topic, qos, options); } + typedef typename rclcpp::Publisher::SharedPtr PublisherT; + //! Generic function for publishing the internal message type. typedef std::function PublishFn; @@ -125,7 +140,21 @@ class SimplePublisherPlugin : public PublisherPlugin */ virtual void publish( const sensor_msgs::msg::Image & message, - const PublishFn & publish_fn) const = 0; + const PublishFn & publish_fn) const {} + + virtual void publish( + const sensor_msgs::msg::Image & message, + const PublisherT & publisher) const + { + publish(message, bindInternalPublisher(publisher.get())); + } + + virtual void publish( + sensor_msgs::msg::Image::UniquePtr message, + const PublisherT & publisher) const + { + publish(*message, bindInternalPublisher(publisher.get())); + } /** * \brief Return the communication topic name for a given base topic. @@ -148,7 +177,7 @@ class SimplePublisherPlugin : public PublisherPlugin rclcpp::Node * node_; rclcpp::Logger logger_; - typename rclcpp::Publisher::SharedPtr pub_; + PublisherT pub_; }; std::unique_ptr simple_impl_; From 5bb8381913a72f2ddb05a6b79e5f3388a1baa986 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Sat, 20 Apr 2024 22:50:34 +0200 Subject: [PATCH 03/15] Support UniquePtr publishing in raw publisher plugin --- .../include/image_transport/raw_publisher.hpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/image_transport/include/image_transport/raw_publisher.hpp b/image_transport/include/image_transport/raw_publisher.hpp index e52b26b9..eb1db760 100644 --- a/image_transport/include/image_transport/raw_publisher.hpp +++ b/image_transport/include/image_transport/raw_publisher.hpp @@ -56,12 +56,24 @@ class RawPublisher : public SimplePublisherPlugin return "raw"; } + virtual bool supportsUniquePtrPub() const + { + return true; + } + protected: virtual void publish(const sensor_msgs::msg::Image & message, const PublishFn & publish_fn) const { publish_fn(message); } + virtual void publish( + sensor_msgs::msg::Image::UniquePtr message, + const PublisherT & publisher) const + { + publisher->publish(std::move(message)); + } + virtual std::string getTopicToAdvertise(const std::string & base_topic) const { return base_topic; From 251c24be3f066523a74b009bcadf81dfb170586d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Sat, 20 Apr 2024 22:51:32 +0200 Subject: [PATCH 04/15] Implement UniquePtr publishing in image transport publishers --- .../image_transport/camera_publisher.hpp | 21 +++++++++++ .../include/image_transport/publisher.hpp | 6 +++ image_transport/src/camera_publisher.cpp | 37 +++++++++++++++++++ image_transport/src/publisher.cpp | 31 ++++++++++++++++ 4 files changed, 95 insertions(+) diff --git a/image_transport/include/image_transport/camera_publisher.hpp b/image_transport/include/image_transport/camera_publisher.hpp index 9ed81b07..ad80328c 100644 --- a/image_transport/include/image_transport/camera_publisher.hpp +++ b/image_transport/include/image_transport/camera_publisher.hpp @@ -111,6 +111,14 @@ class CameraPublisher const sensor_msgs::msg::Image::ConstSharedPtr & image, const sensor_msgs::msg::CameraInfo::ConstSharedPtr & info) const; + /*! + * \brief Publish an (image, info) pair on the topics associated with this CameraPublisher. + */ + IMAGE_TRANSPORT_PUBLIC + void publish( + sensor_msgs::msg::Image::UniquePtr image, + sensor_msgs::msg::CameraInfo::UniquePtr info) const; + /*! * \brief Publish an (image, info) pair with given timestamp on the topics associated with * this CameraPublisher. @@ -123,6 +131,19 @@ class CameraPublisher sensor_msgs::msg::Image & image, sensor_msgs::msg::CameraInfo & info, rclcpp::Time stamp) const; + /*! + * \brief Publish an (image, info) pair with given timestamp on the topics associated with + * this CameraPublisher. + * + * Convenience version, which sets the timestamps of both image and info to stamp before + * publishing. + */ + IMAGE_TRANSPORT_PUBLIC + void publish( + sensor_msgs::msg::Image::UniquePtr image, + sensor_msgs::msg::CameraInfo::UniquePtr info, + rclcpp::Time stamp) const; + /*! * \brief Shutdown the advertisements associated with this Publisher. */ diff --git a/image_transport/include/image_transport/publisher.hpp b/image_transport/include/image_transport/publisher.hpp index dc28d017..4f529121 100644 --- a/image_transport/include/image_transport/publisher.hpp +++ b/image_transport/include/image_transport/publisher.hpp @@ -103,6 +103,12 @@ class Publisher IMAGE_TRANSPORT_PUBLIC void publish(const sensor_msgs::msg::Image::ConstSharedPtr & message) const; + /*! + * \brief Publish an image on the topics associated with this Publisher. + */ + IMAGE_TRANSPORT_PUBLIC + void publish(sensor_msgs::msg::Image::UniquePtr message) const; + /*! * \brief Shutdown the advertisements associated with this Publisher. */ diff --git a/image_transport/src/camera_publisher.cpp b/image_transport/src/camera_publisher.cpp index 7c1ae450..1aa4dc2b 100644 --- a/image_transport/src/camera_publisher.cpp +++ b/image_transport/src/camera_publisher.cpp @@ -153,6 +153,23 @@ void CameraPublisher::publish( impl_->info_pub_->publish(*info); } +void CameraPublisher::publish( + sensor_msgs::msg::Image::UniquePtr image, + sensor_msgs::msg::CameraInfo::UniquePtr info) const +{ + if (!impl_ || !impl_->isValid()) { + // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged + auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); + RCLCPP_FATAL( + logger, + "Call to publish() on an invalid image_transport::CameraPublisher"); + return; + } + + impl_->image_pub_.publish(std::move(image)); + impl_->info_pub_->publish(std::move(info)); +} + void CameraPublisher::publish( sensor_msgs::msg::Image & image, sensor_msgs::msg::CameraInfo & info, rclcpp::Time stamp) const @@ -172,6 +189,26 @@ void CameraPublisher::publish( impl_->info_pub_->publish(info); } +void CameraPublisher::publish( + sensor_msgs::msg::Image::UniquePtr image, + sensor_msgs::msg::CameraInfo::UniquePtr info, + rclcpp::Time stamp) const +{ + if (!impl_ || !impl_->isValid()) { + // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged + auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); + RCLCPP_FATAL( + logger, + "Call to publish() on an invalid image_transport::CameraPublisher"); + return; + } + + image->header.stamp = stamp; + info->header.stamp = stamp; + impl_->image_pub_.publish(std::move(image)); + impl_->info_pub_->publish(std::move(info)); +} + void CameraPublisher::shutdown() { if (impl_) { diff --git a/image_transport/src/publisher.cpp b/image_transport/src/publisher.cpp index 0bed7b09..33402791 100644 --- a/image_transport/src/publisher.cpp +++ b/image_transport/src/publisher.cpp @@ -202,6 +202,37 @@ void Publisher::publish(const sensor_msgs::msg::Image::ConstSharedPtr & message) } } +void Publisher::publish(sensor_msgs::msg::Image::UniquePtr message) const +{ + if (!impl_ || !impl_->isValid()) { + // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged + auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); + RCLCPP_FATAL(logger, "Call to publish() on an invalid image_transport::Publisher"); + return; + } + + std::vector> pubs_take_reference; + std::optional> pub_takes_ownership = std::nullopt; + + for (const auto & pub : impl_->publishers_) { + if (pub->getNumSubscribers() > 0) { + if (pub->supportsUniquePtrPub() && !pub_takes_ownership.has_value()) { + pub_takes_ownership = pub; + } else { + pubs_take_reference.push_back(pub); + } + } + } + + for (const auto & pub : pubs_take_reference) { + pub->publish(*message); + } + + if (pub_takes_ownership.has_value()) { + pub_takes_ownership.value()->publishUniquePtr(std::move(message)); + } +} + void Publisher::shutdown() { if (impl_) { From 6697bb00d4320159baf3baf974c70ff7f2e44a9f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 22 Apr 2024 12:47:44 +0000 Subject: [PATCH 05/15] Reformat using ament_uncrustify --- image_transport/include/image_transport/publisher_plugin.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/image_transport/include/image_transport/publisher_plugin.hpp b/image_transport/include/image_transport/publisher_plugin.hpp index 79350dca..d80c304f 100644 --- a/image_transport/include/image_transport/publisher_plugin.hpp +++ b/image_transport/include/image_transport/publisher_plugin.hpp @@ -105,7 +105,7 @@ class PublisherPlugin /** * \brief Publish an image using the transport associated with this PublisherPlugin. - * This version of the function can be used to optimize cases where the Plugin can + * This version of the function can be used to optimize cases where the Plugin can * avoid doing copies of the data when having the ownership to the image message. * Plugins that can take advantage of message ownership should overwrite this method * along with supportsUniquePtrPub(). From 4c2ef7f7ad4e0f6abb96681f788861ea74e1ed14 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 22 Apr 2024 12:48:52 +0000 Subject: [PATCH 06/15] Fix ament_cpplint errors --- image_transport/include/image_transport/raw_publisher.hpp | 1 + .../include/image_transport/simple_publisher_plugin.hpp | 1 + 2 files changed, 2 insertions(+) diff --git a/image_transport/include/image_transport/raw_publisher.hpp b/image_transport/include/image_transport/raw_publisher.hpp index eb1db760..1cb08920 100644 --- a/image_transport/include/image_transport/raw_publisher.hpp +++ b/image_transport/include/image_transport/raw_publisher.hpp @@ -30,6 +30,7 @@ #define IMAGE_TRANSPORT__RAW_PUBLISHER_HPP_ #include +#include #include "sensor_msgs/msg/image.hpp" diff --git a/image_transport/include/image_transport/simple_publisher_plugin.hpp b/image_transport/include/image_transport/simple_publisher_plugin.hpp index f29af8d7..5ec5a348 100644 --- a/image_transport/include/image_transport/simple_publisher_plugin.hpp +++ b/image_transport/include/image_transport/simple_publisher_plugin.hpp @@ -31,6 +31,7 @@ #include #include +#include #include "rclcpp/node.hpp" #include "rclcpp/logger.hpp" From 77ad82f070a0999a1b106291f9e610101f41501a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 22 Apr 2024 13:29:51 +0000 Subject: [PATCH 07/15] Fix unused variable warnings --- .../include/image_transport/simple_publisher_plugin.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/image_transport/include/image_transport/simple_publisher_plugin.hpp b/image_transport/include/image_transport/simple_publisher_plugin.hpp index 5ec5a348..9bb978de 100644 --- a/image_transport/include/image_transport/simple_publisher_plugin.hpp +++ b/image_transport/include/image_transport/simple_publisher_plugin.hpp @@ -140,8 +140,8 @@ class SimplePublisherPlugin : public PublisherPlugin * single subscriber publishing (in subscription callbacks). */ virtual void publish( - const sensor_msgs::msg::Image & message, - const PublishFn & publish_fn) const {} + const sensor_msgs::msg::Image & /*message*/, + const PublishFn & /*publish_fn*/) const {} virtual void publish( const sensor_msgs::msg::Image & message, From 1ebb245183012c59e18a64bb94588b56c2e3167b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 22 Apr 2024 13:43:25 +0000 Subject: [PATCH 08/15] Remove redundant TODO comments --- image_transport/src/camera_publisher.cpp | 1 - image_transport/src/publisher.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/image_transport/src/camera_publisher.cpp b/image_transport/src/camera_publisher.cpp index 1aa4dc2b..ddc9050b 100644 --- a/image_transport/src/camera_publisher.cpp +++ b/image_transport/src/camera_publisher.cpp @@ -124,7 +124,6 @@ void CameraPublisher::publish( const sensor_msgs::msg::CameraInfo & info) const { if (!impl_ || !impl_->isValid()) { - // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); RCLCPP_FATAL( logger, diff --git a/image_transport/src/publisher.cpp b/image_transport/src/publisher.cpp index 33402791..4eebee16 100644 --- a/image_transport/src/publisher.cpp +++ b/image_transport/src/publisher.cpp @@ -205,7 +205,6 @@ void Publisher::publish(const sensor_msgs::msg::Image::ConstSharedPtr & message) void Publisher::publish(sensor_msgs::msg::Image::UniquePtr message) const { if (!impl_ || !impl_->isValid()) { - // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); RCLCPP_FATAL(logger, "Call to publish() on an invalid image_transport::Publisher"); return; From 134fa6fe257c70ef75010862514351855429c215 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 22 Apr 2024 13:44:32 +0000 Subject: [PATCH 09/15] Add missing include --- image_transport/src/publisher.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/image_transport/src/publisher.cpp b/image_transport/src/publisher.cpp index 4eebee16..d467e54b 100644 --- a/image_transport/src/publisher.cpp +++ b/image_transport/src/publisher.cpp @@ -29,6 +29,7 @@ #include "image_transport/publisher.hpp" #include +#include #include #include #include From 587fdab8c91d4df6ef8ce0057451c92e86b57a8a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 22 Apr 2024 13:45:14 +0000 Subject: [PATCH 10/15] Use new API in raw publisher --- image_transport/include/image_transport/raw_publisher.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/image_transport/include/image_transport/raw_publisher.hpp b/image_transport/include/image_transport/raw_publisher.hpp index 1cb08920..c3391fa0 100644 --- a/image_transport/include/image_transport/raw_publisher.hpp +++ b/image_transport/include/image_transport/raw_publisher.hpp @@ -63,9 +63,9 @@ class RawPublisher : public SimplePublisherPlugin } protected: - virtual void publish(const sensor_msgs::msg::Image & message, const PublishFn & publish_fn) const + virtual void publish(const sensor_msgs::msg::Image & message, const PublisherT & publisher) const { - publish_fn(message); + publisher->publish(message); } virtual void publish( From 2606433b5102aef34e9bbf71402219b1655e7c27 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Fri, 26 Apr 2024 16:25:19 +0200 Subject: [PATCH 11/15] Restore old raw_publisher publish method, add deprecated attribute --- image_transport/include/image_transport/raw_publisher.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/image_transport/include/image_transport/raw_publisher.hpp b/image_transport/include/image_transport/raw_publisher.hpp index c3391fa0..65fed4a7 100644 --- a/image_transport/include/image_transport/raw_publisher.hpp +++ b/image_transport/include/image_transport/raw_publisher.hpp @@ -63,6 +63,12 @@ class RawPublisher : public SimplePublisherPlugin } protected: + [[deprecated("Use publish(const sensor_msgs::msg::Image&, const PublisherT&) instead.")]] + virtual void publish(const sensor_msgs::msg::Image & message, const PublishFn & publish_fn) const + { + publish_fn(message); + } + virtual void publish(const sensor_msgs::msg::Image & message, const PublisherT & publisher) const { publisher->publish(message); From e3bc5b262853599635f027d67addafb101160923 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 29 Apr 2024 02:00:16 +0000 Subject: [PATCH 12/15] Throw exceptions instead of empty/faulty default implementations --- .../include/image_transport/publisher_plugin.hpp | 5 +++-- .../image_transport/simple_publisher_plugin.hpp | 14 ++++++++++---- 2 files changed, 13 insertions(+), 6 deletions(-) diff --git a/image_transport/include/image_transport/publisher_plugin.hpp b/image_transport/include/image_transport/publisher_plugin.hpp index d80c304f..c545b4ca 100644 --- a/image_transport/include/image_transport/publisher_plugin.hpp +++ b/image_transport/include/image_transport/publisher_plugin.hpp @@ -29,6 +29,7 @@ #ifndef IMAGE_TRANSPORT__PUBLISHER_PLUGIN_HPP_ #define IMAGE_TRANSPORT__PUBLISHER_PLUGIN_HPP_ +#include #include #include @@ -110,9 +111,9 @@ class PublisherPlugin * Plugins that can take advantage of message ownership should overwrite this method * along with supportsUniquePtrPub(). */ - virtual void publishUniquePtr(sensor_msgs::msg::Image::UniquePtr message) const + virtual void publishUniquePtr(sensor_msgs::msg::Image::UniquePtr /*message*/) const { - publish(*message); + throw std::logic_error("publishUniquePtr() is not implemented."); } /** diff --git a/image_transport/include/image_transport/simple_publisher_plugin.hpp b/image_transport/include/image_transport/simple_publisher_plugin.hpp index 9bb978de..b3c177c3 100644 --- a/image_transport/include/image_transport/simple_publisher_plugin.hpp +++ b/image_transport/include/image_transport/simple_publisher_plugin.hpp @@ -30,6 +30,7 @@ #define IMAGE_TRANSPORT__SIMPLE_PUBLISHER_PLUGIN_HPP_ #include +#include #include #include @@ -141,7 +142,11 @@ class SimplePublisherPlugin : public PublisherPlugin */ virtual void publish( const sensor_msgs::msg::Image & /*message*/, - const PublishFn & /*publish_fn*/) const {} + const PublishFn & /*publish_fn*/) const + { + throw std::logic_error( + "publish(const sensor_msgs::msg::Image&, const PublishFn&) is not implemented."); + } virtual void publish( const sensor_msgs::msg::Image & message, @@ -151,10 +156,11 @@ class SimplePublisherPlugin : public PublisherPlugin } virtual void publish( - sensor_msgs::msg::Image::UniquePtr message, - const PublisherT & publisher) const + sensor_msgs::msg::Image::UniquePtr /*message*/, + const PublisherT & /*publisher*/) const { - publish(*message, bindInternalPublisher(publisher.get())); + throw std::logic_error( + "publish(sensor_msgs::msg::Image::UniquePtr, const PublisherT&) is not implemented."); } /** From 70f40d1c7ae73988e6fffa979143be28648fe36f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 29 Apr 2024 02:01:21 +0000 Subject: [PATCH 13/15] Add more comments --- .../image_transport/simple_publisher_plugin.hpp | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/image_transport/include/image_transport/simple_publisher_plugin.hpp b/image_transport/include/image_transport/simple_publisher_plugin.hpp index b3c177c3..4ca77524 100644 --- a/image_transport/include/image_transport/simple_publisher_plugin.hpp +++ b/image_transport/include/image_transport/simple_publisher_plugin.hpp @@ -133,8 +133,9 @@ class SimplePublisherPlugin : public PublisherPlugin typedef std::function PublishFn; /** - * \brief Publish an image using the specified publish function. Must be implemented by - * the subclass. + * \brief Publish an image using the specified publish function. + * + * \deprecated Use publish(const sensor_msgs::msg::Image&, const PublisherT&) instead. * * The PublishFn publishes the transport-specific message type. This indirection allows * SimpleSubscriberPlugin to use this function for both normal broadcast publishing and @@ -148,13 +149,25 @@ class SimplePublisherPlugin : public PublisherPlugin "publish(const sensor_msgs::msg::Image&, const PublishFn&) is not implemented."); } + /** + * \brief Publish an image using the specified publisher. + */ virtual void publish( const sensor_msgs::msg::Image & message, const PublisherT & publisher) const { + // Fallback to old, deprecated method publish(message, bindInternalPublisher(publisher.get())); } + /** + * \brief Publish an image using the specified publisher. + * + * This version of the function can be used to optimize cases where the Plugin can + * avoid doing copies of the data when having the ownership to the image message. + * Plugins that can take advantage of message ownership should overwrite this method + * along with supportsUniquePtrPub(). + */ virtual void publish( sensor_msgs::msg::Image::UniquePtr /*message*/, const PublisherT & /*publisher*/) const From 9beb1343fe780bef43134b852df226dd3dfd88aa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 6 May 2024 20:54:52 +0200 Subject: [PATCH 14/15] Remove more redundant TODO comments --- image_transport/src/camera_publisher.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/image_transport/src/camera_publisher.cpp b/image_transport/src/camera_publisher.cpp index ddc9050b..ced0a63c 100644 --- a/image_transport/src/camera_publisher.cpp +++ b/image_transport/src/camera_publisher.cpp @@ -140,7 +140,6 @@ void CameraPublisher::publish( const sensor_msgs::msg::CameraInfo::ConstSharedPtr & info) const { if (!impl_ || !impl_->isValid()) { - // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); RCLCPP_FATAL( logger, @@ -157,7 +156,6 @@ void CameraPublisher::publish( sensor_msgs::msg::CameraInfo::UniquePtr info) const { if (!impl_ || !impl_->isValid()) { - // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); RCLCPP_FATAL( logger, @@ -174,7 +172,6 @@ void CameraPublisher::publish( rclcpp::Time stamp) const { if (!impl_ || !impl_->isValid()) { - // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); RCLCPP_FATAL( logger, @@ -194,7 +191,6 @@ void CameraPublisher::publish( rclcpp::Time stamp) const { if (!impl_ || !impl_->isValid()) { - // TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged auto logger = impl_ ? impl_->logger_ : rclcpp::get_logger("image_transport"); RCLCPP_FATAL( logger, From 85f3da1a11409c74d73feae8f46ee5193d66a6ac Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Wed, 15 May 2024 11:21:41 +0000 Subject: [PATCH 15/15] Add missing utility include --- image_transport/src/camera_publisher.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/image_transport/src/camera_publisher.cpp b/image_transport/src/camera_publisher.cpp index ced0a63c..66c7d7f1 100644 --- a/image_transport/src/camera_publisher.cpp +++ b/image_transport/src/camera_publisher.cpp @@ -30,6 +30,7 @@ #include #include +#include #include "rclcpp/expand_topic_or_service_name.hpp" #include "rclcpp/logging.hpp"