From a6e3412bb0a17a3032865f098452949c1400b271 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Mon, 21 Oct 2019 20:47:42 -0700 Subject: [PATCH] rename return functions for loaned messages (#896) * fix up documentation for zero copy api Signed-off-by: Karsten Knese * rename loan_message to borrow_loaned_message Signed-off-by: Karsten Knese * use return_loaned_message_from Signed-off-by: Karsten Knese --- rclcpp/include/rclcpp/loaned_message.hpp | 2 +- rclcpp/include/rclcpp/publisher.hpp | 13 +++++++------ rclcpp/include/rclcpp/subscription_base.hpp | 1 - rclcpp/src/rclcpp/executor.cpp | 4 ++-- rclcpp/test/test_loaned_message.cpp | 4 ++-- 5 files changed, 12 insertions(+), 12 deletions(-) diff --git a/rclcpp/include/rclcpp/loaned_message.hpp b/rclcpp/include/rclcpp/loaned_message.hpp index 09ad4a8..ad086cf 100644 --- a/rclcpp/include/rclcpp/loaned_message.hpp +++ b/rclcpp/include/rclcpp/loaned_message.hpp @@ -137,7 +137,7 @@ public: if (pub_.can_loan_messages()) { // return allocated memory to the middleware auto ret = - rcl_return_loaned_message(pub_.get_publisher_handle(), message_); + rcl_return_loaned_message_from_publisher(pub_.get_publisher_handle(), message_); if (ret != RCL_RET_OK) { RCLCPP_ERROR( error_logger, "rcl_deallocate_loaned_message failed: %s", rcl_get_error_string().str); diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 31de94e..b017080 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -129,7 +129,7 @@ public: virtual ~Publisher() {} - /// Loan memory for a ROS message from the middleware + /// Borrow a loaned 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. @@ -137,14 +137,15 @@ public: * * 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 */ rclcpp::LoanedMessage - loan_message() + borrow_loaned_message() { return rclcpp::LoanedMessage(this, this->get_allocator()); } @@ -201,9 +202,9 @@ public: 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 06d161c..23ecb5e 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -134,7 +134,6 @@ public: 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 diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 6953610..c8ee237 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -344,13 +344,13 @@ Executor::execute_subscription( subscription->get_topic_name(), rcl_get_error_string().str); rcl_reset_error(); } - ret = rcl_release_loaned_message( + ret = rcl_return_loaned_message_from_subscription( subscription->get_subscription_handle().get(), loaned_msg); if (RCL_RET_OK != ret) { RCUTILS_LOG_ERROR_NAMED( "rclcpp", - "release_loaned failed for subscription on topic '%s': %s", + "return_loaned_message failed for subscription on topic '%s': %s", subscription->get_topic_name(), rcl_get_error_string().str); } loaned_msg = nullptr; diff --git a/rclcpp/test/test_loaned_message.cpp b/rclcpp/test/test_loaned_message.cpp index 726209a..651b367 100644 --- a/rclcpp/test/test_loaned_message.cpp +++ b/rclcpp/test/test_loaned_message.cpp @@ -53,7 +53,7 @@ TEST_F(TestLoanedMessage, loan_from_pub) { auto node = std::make_shared("loaned_message_test_node"); auto pub = node->create_publisher("loaned_message_test_topic", 1); - auto loaned_msg = pub->loan_message(); + auto loaned_msg = pub->borrow_loaned_message(); ASSERT_TRUE(loaned_msg.is_valid()); loaned_msg.get().float64_value = 42.0f; ASSERT_EQ(42.0f, loaned_msg.get().float64_value); @@ -67,7 +67,7 @@ TEST_F(TestLoanedMessage, release) { MessageT * msg = nullptr; { - auto loaned_msg = pub->loan_message(); + auto loaned_msg = pub->borrow_loaned_message(); ASSERT_TRUE(loaned_msg.is_valid()); loaned_msg.get().float64_value = 42.0f; ASSERT_EQ(42.0f, loaned_msg.get().float64_value);