Skip to content

Commit a6e3412

Browse files
Karsten1987mjcarroll
authored andcommitted
rename return functions for loaned messages (#896)
* fix up documentation for zero copy api Signed-off-by: Karsten Knese <[email protected]> * rename loan_message to borrow_loaned_message Signed-off-by: Karsten Knese <[email protected]> * use return_loaned_message_from Signed-off-by: Karsten Knese <[email protected]>
1 parent 3de5337 commit a6e3412

File tree

5 files changed

+12
-12
lines changed

5 files changed

+12
-12
lines changed

rclcpp/include/rclcpp/loaned_message.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ class LoanedMessage
137137
if (pub_.can_loan_messages()) {
138138
// return allocated memory to the middleware
139139
auto ret =
140-
rcl_return_loaned_message(pub_.get_publisher_handle(), message_);
140+
rcl_return_loaned_message_from_publisher(pub_.get_publisher_handle(), message_);
141141
if (ret != RCL_RET_OK) {
142142
RCLCPP_ERROR(
143143
error_logger, "rcl_deallocate_loaned_message failed: %s", rcl_get_error_string().str);

rclcpp/include/rclcpp/publisher.hpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -129,22 +129,23 @@ class Publisher : public PublisherBase
129129
virtual ~Publisher()
130130
{}
131131

132-
/// Loan memory for a ROS message from the middleware
132+
/// Borrow a loaned ROS message from the middleware.
133133
/**
134134
* If the middleware is capable of loaning memory for a ROS message instance,
135135
* the loaned message will be directly allocated in the middleware.
136136
* If not, the message allocator of this rclcpp::Publisher instance is being used.
137137
*
138138
* With a call to \sa `publish` the LoanedMessage instance is being returned to the middleware
139139
* or free'd accordingly to the allocator.
140-
* If the message is not being published but processed differently, the message has to be
141-
* returned by calling \sa `return_loaned_message`.
140+
* If the message is not being published but processed differently, the destructor of this
141+
* class will either return the message to the middleware or deallocate it via the internal
142+
* allocator.
142143
* \sa rclcpp::LoanedMessage for details of the LoanedMessage class.
143144
*
144145
* \return LoanedMessage containing memory for a ROS message of type MessageT
145146
*/
146147
rclcpp::LoanedMessage<MessageT, AllocatorT>
147-
loan_message()
148+
borrow_loaned_message()
148149
{
149150
return rclcpp::LoanedMessage<MessageT, AllocatorT>(this, this->get_allocator());
150151
}
@@ -201,9 +202,9 @@ class Publisher : public PublisherBase
201202
return this->do_serialized_publish(&serialized_msg);
202203
}
203204

204-
/// Publish an instance of a LoanedMessage
205+
/// Publish an instance of a LoanedMessage.
205206
/**
206-
* When publishing a loaned message, the memory for this ROS instance will be deallocated
207+
* When publishing a loaned message, the memory for this ROS message will be deallocated
207208
* after being published.
208209
* The instance of the loaned message is no longer valid after this call.
209210
*

rclcpp/include/rclcpp/subscription_base.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,6 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
134134
void
135135
handle_message(std::shared_ptr<void> & message, const rmw_message_info_t & message_info) = 0;
136136

137-
// TODO(karsten1987): Does it make sense to pass in a weak_ptr?
138137
RCLCPP_PUBLIC
139138
virtual
140139
void

rclcpp/src/rclcpp/executor.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -344,13 +344,13 @@ Executor::execute_subscription(
344344
subscription->get_topic_name(), rcl_get_error_string().str);
345345
rcl_reset_error();
346346
}
347-
ret = rcl_release_loaned_message(
347+
ret = rcl_return_loaned_message_from_subscription(
348348
subscription->get_subscription_handle().get(),
349349
loaned_msg);
350350
if (RCL_RET_OK != ret) {
351351
RCUTILS_LOG_ERROR_NAMED(
352352
"rclcpp",
353-
"release_loaned failed for subscription on topic '%s': %s",
353+
"return_loaned_message failed for subscription on topic '%s': %s",
354354
subscription->get_topic_name(), rcl_get_error_string().str);
355355
}
356356
loaned_msg = nullptr;

rclcpp/test/test_loaned_message.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ TEST_F(TestLoanedMessage, loan_from_pub) {
5353
auto node = std::make_shared<rclcpp::Node>("loaned_message_test_node");
5454
auto pub = node->create_publisher<MessageT>("loaned_message_test_topic", 1);
5555

56-
auto loaned_msg = pub->loan_message();
56+
auto loaned_msg = pub->borrow_loaned_message();
5757
ASSERT_TRUE(loaned_msg.is_valid());
5858
loaned_msg.get().float64_value = 42.0f;
5959
ASSERT_EQ(42.0f, loaned_msg.get().float64_value);
@@ -67,7 +67,7 @@ TEST_F(TestLoanedMessage, release) {
6767

6868
MessageT * msg = nullptr;
6969
{
70-
auto loaned_msg = pub->loan_message();
70+
auto loaned_msg = pub->borrow_loaned_message();
7171
ASSERT_TRUE(loaned_msg.is_valid());
7272
loaned_msg.get().float64_value = 42.0f;
7373
ASSERT_EQ(42.0f, loaned_msg.get().float64_value);

0 commit comments

Comments
 (0)