Skip to content

Commit f294488

Browse files
authored
Disable the loaned messages inside the executor. (#2335)
* 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 <[email protected]>
1 parent 8a02e39 commit f294488

File tree

2 files changed

+19
-1
lines changed

2 files changed

+19
-1
lines changed

rclcpp/src/rclcpp/executor.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -669,6 +669,11 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
669669
subscription->get_topic_name(),
670670
[&]() {return subscription->take_type_erased(message.get(), message_info);},
671671
[&]() {subscription->handle_message(message, message_info);});
672+
// TODO(clalancette): In the case that the user is using the MessageMemoryPool,
673+
// and they take a shared_ptr reference to the message in the callback, this can
674+
// inadvertently return the message to the pool when the user is still using it.
675+
// This is a bug that needs to be fixed in the pool, and we should probably have
676+
// a custom deleter for the message that actually does the return_message().
672677
subscription->return_message(message);
673678
}
674679
break;

rclcpp/src/rclcpp/subscription_base.cpp

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -298,7 +298,20 @@ SubscriptionBase::setup_intra_process(
298298
bool
299299
SubscriptionBase::can_loan_messages() const
300300
{
301-
return rcl_subscription_can_loan_messages(subscription_handle_.get());
301+
bool retval = rcl_subscription_can_loan_messages(subscription_handle_.get());
302+
if (retval) {
303+
// TODO(clalancette): The loaned message interface is currently not safe to use with
304+
// shared_ptr callbacks. If a user takes a copy of the shared_ptr, it can get freed from
305+
// underneath them via rcl_return_loaned_message_from_subscription(). The correct solution is
306+
// to return the loaned message in a custom deleter, but that needs to be carefully handled
307+
// with locking. Warn the user about this until we fix it.
308+
RCLCPP_WARN_ONCE(
309+
this->node_logger_,
310+
"Loaned messages are only safe with const ref subscription callbacks. "
311+
"If you are using any other kind of subscriptions, "
312+
"set the ROS_DISABLE_LOANED_MESSAGES environment variable to 1 (the default).");
313+
}
314+
return retval;
302315
}
303316

304317
rclcpp::Waitable::SharedPtr

0 commit comments

Comments
 (0)