Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/loaned_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ class LoanedMessage
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);
Expand Down
13 changes: 7 additions & 6 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,22 +129,23 @@ class Publisher : public PublisherBase
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.
* If not, the message allocator of this rclcpp::Publisher instance is being used.
*
* 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<MessageT, AllocatorT>
loan_message()
borrow_loaned_message()
{
return rclcpp::LoanedMessage<MessageT, AllocatorT>(this, this->get_allocator());
}
Expand Down Expand Up @@ -201,9 +202,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.
*
Expand Down
1 change: 0 additions & 1 deletion rclcpp/include/rclcpp/subscription_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,6 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
void
handle_message(std::shared_ptr<void> & 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
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/test_loaned_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ TEST_F(TestLoanedMessage, loan_from_pub) {
auto node = std::make_shared<rclcpp::Node>("loaned_message_test_node");
auto pub = node->create_publisher<MessageT>("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);
Expand All @@ -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);
Expand Down