Skip to content

Commit

Permalink
Feedback from review.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette committed Oct 12, 2023
1 parent 1fcd31c commit 9b75267
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 7 deletions.
7 changes: 1 addition & 6 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -623,12 +623,7 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
// Deliver ROS message
case rclcpp::DeliveredMessageKind::ROS_MESSAGE:
{
// TODO(clalancette): The loaned message interface is currently not safe to use.
// If a user takes a reference to 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. Disable the entire interface for now until we sort through the issues.
if (false && subscription->can_loan_messages()) {
if (subscription->can_loan_messages()) {
// This is the case where a loaned message is taken from the middleware via
// inter-process communication, given to the user for their callback,
// and then returned.
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 9b75267

Please sign in to comment.