Skip to content

Commit

Permalink
Disable the loaned messages inside the executor. (#2335) (#2365)
Browse files Browse the repository at this point in the history
* Disable the loaned messages inside the executor.

They are currently unsafe to use; see the comment in the
commit for more information.

Signed-off-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit f294488)

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
mergify[bot] and clalancette authored Nov 9, 2023
1 parent 613bcc5 commit abcdcc4
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 1 deletion.
5 changes: 5 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -653,6 +653,11 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
subscription->get_topic_name(),
[&]() {return subscription->take_type_erased(message.get(), message_info);},
[&]() {subscription->handle_message(message, message_info);});
// TODO(clalancette): In the case that the user is using the MessageMemoryPool,
// and they take a shared_ptr reference to the message in the callback, this can
// inadvertently return the message to the pool when the user is still using it.
// This is a bug that needs to be fixed in the pool, and we should probably have
// a custom deleter for the message that actually does the return_message().
subscription->return_message(message);
}
break;
Expand Down
15 changes: 14 additions & 1 deletion rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,7 +298,20 @@ SubscriptionBase::setup_intra_process(
bool
SubscriptionBase::can_loan_messages() const
{
return rcl_subscription_can_loan_messages(subscription_handle_.get());
bool retval = rcl_subscription_can_loan_messages(subscription_handle_.get());
if (retval) {
// TODO(clalancette): The loaned message interface is currently not safe to use with
// shared_ptr callbacks. If a user takes a copy of the shared_ptr, it can get freed from
// underneath them via rcl_return_loaned_message_from_subscription(). The correct solution is
// to return the loaned message in a custom deleter, but that needs to be carefully handled
// with locking. Warn the user about this until we fix it.
RCLCPP_WARN_ONCE(
this->node_logger_,
"Loaned messages are only safe with const ref subscription callbacks. "
"If you are using any other kind of subscriptions, "
"set the ROS_DISABLE_LOANED_MESSAGES environment variable to 1 (the default).");
}
return retval;
}

rclcpp::Waitable::SharedPtr
Expand Down

0 comments on commit abcdcc4

Please sign in to comment.