From 87cd9714666f47aed6e819ea3371c9db7f678855 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Fri, 18 Oct 2019 16:59:35 -0700 Subject: [PATCH] fix up documentation for zero copy api Signed-off-by: Karsten Knese --- rclcpp/include/rclcpp/publisher.hpp | 11 ++++++----- rclcpp/include/rclcpp/subscription_base.hpp | 1 - 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 9bde46e3df..32b78a07b0 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -136,7 +136,7 @@ class Publisher : public PublisherBase >::make_shared(size, this->get_allocator()); } - /// Loan memory for a ROS message from the middleware + /// Loan memory for a ROS message from the middleware. /** * If the middleware is capable of loaning memory for a ROS message instance, * the loaned message will be directly allocated in the middleware. @@ -144,8 +144,9 @@ class Publisher : public PublisherBase * * With a call to \sa `publish` the LoanedMessage instance is being returned to the middleware * or free'd accordingly to the allocator. - * If the message is not being published but processed differently, the message has to be - * returned by calling \sa `return_loaned_message`. + * If the message is not being published but processed differently, the destructor of this + * class will either return the message to the middleware or deallocate it via the internal + * allocator. * \sa rclcpp::LoanedMessage for details of the LoanedMessage class. * * \return LoanedMessage containing memory for a ROS message of type MessageT @@ -215,9 +216,9 @@ class Publisher : public PublisherBase return this->do_serialized_publish(&serialized_msg); } - /// Publish an instance of a LoanedMessage + /// Publish an instance of a LoanedMessage. /** - * When publishing a loaned message, the memory for this ROS instance will be deallocated + * When publishing a loaned message, the memory for this ROS message will be deallocated * after being published. * The instance of the loaned message is no longer valid after this call. * diff --git a/rclcpp/include/rclcpp/subscription_base.hpp b/rclcpp/include/rclcpp/subscription_base.hpp index f3df9974b3..8a6190ac17 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -138,7 +138,6 @@ class SubscriptionBase : public std::enable_shared_from_this void handle_message(std::shared_ptr & message, const rmw_message_info_t & message_info) = 0; - // TODO(karsten1987): Does it make sense to pass in a weak_ptr? RCLCPP_PUBLIC virtual void