Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Disable the loaned messages inside the executor. (backport #2335) #2365

Merged
merged 1 commit into from
Nov 9, 2023
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
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