ros2 / design

Design documentation for ROS 2.0 effort
http://design.ros2.org/
Apache License 2.0
223 stars 194 forks source link

Design Document for Zero-Copy via Loaned Messages #256

Closed mjcarroll closed 4 years ago

mjcarroll commented 5 years ago

Design document for using loaned messages to provide support for zero-copy middleware implementations.

This is from notes that @Karsten1987 and @wjwwood composed, reformatted and expanded.

Karsten1987 commented 5 years ago

fyi @michael-poehnl

Karsten1987 commented 5 years ago

I think we talked about this, but I think we didn't come to an conclusion.

When we talk about taking sequences for messages which can be loaned, this implies that there has to be some sort of adjustment/enhancement on for a rmw_take_loaned_message_sequence function. Right now I envision something like:

rmw_ret_t
rmw_take_loaned_message_sequence(rmw_message_sequence_t * message_sequence, size_t n);

Where n is the amount of messages being fetched and stored in the message sequence.

If I bring this all the way up to a possible implementation in the rclcpp::Executor::execute_subscription function, this would like as such:

void
Executor::execute_subscription(
  rclcpp::SubscriptionBase::SharedPtr subscription)
{
  rmw_message_info_t message_info;
  message_info.from_intra_process = false;

  // handle serialized messages
  if (subscription->is_serialized()) {
    auto serialized_msg = subscription->create_serialized_message();
    auto ret = rcl_take_serialized_message(
      subscription->get_subscription_handle().get(),
      serialized_msg.get(), &message_info, nullptr);
    if (RCL_RET_OK == ret) {
      auto void_serialized_msg = std::static_pointer_cast<void>(serialized_msg);
      subscription->handle_message(void_serialized_msg, message_info);
    } else if (RCL_RET_SUBSCRIPTION_TAKE_FAILED != ret) {
      RCUTILS_LOG_ERROR_NAMED(
        "rclcpp",
        "take_serialized failed for subscription on topic '%s': %s",
        subscription->get_topic_name(), rcl_get_error_string().str);
      rcl_reset_error();
    }
    subscription->return_serialized_message(serialized_msg);
    return;
  }

  // if a middleware can provide loaned messages, we always take them as such
  if (subscription->can_loan_messages()) {
    size_t n = 1;  // how many messages are we fetch at a time
    // Could be part of the subscription API in case of polling
    // Maybe take a parameter n for reserving space in the loaned message sequence
    auto LoanedMessageSequence lms = subscription->create_loaned_sequence(n);
    auto ret = rcl_take_loaned_message_sequence(lms.get_sequence_handle(), n);
    if (RCL_RET_OK == ret) {
      subscription->handle_message(lms.msg_at(0), lms.msg_info_at(0));
    } else if (RCL_RET_TAKE_FAILED != ret) {
      RCUTILS_LOG_ERROR_NAMED(
        "rclcpp",
        "could not take loaned message sequence on topic '%s': %s",
        subscription->get_topic_name(), rcl_get_error_string().str);
      rcl_reset_error();
    }
    subscription->return_loaned_sequence(lms);
    return;
  }

  // if the middleware can't loan message, we create our own instances and take them
  std::shared_ptr<void> message = subscription->create_message();
  auto ret = rcl_take(
    subscription->get_subscription_handle().get(),
    message.get(), &message_info, nullptr);
  if (RCL_RET_OK == ret) {
    subscription->handle_message(message, message_info);
  } else if (RCL_RET_SUBSCRIPTION_TAKE_FAILED != ret) {
    RCUTILS_LOG_ERROR_NAMED(
      "rclcpp",
      "could not deserialize serialized message on topic '%s': %s",
      subscription->get_topic_name(), rcl_get_error_string().str);
    rcl_reset_error();
  }
  subscription->return_message(message);
}

Looking at the scribble above, you can see an inconsistency between serialized/non-loaned messages and loaned messages. The first two types are always fetch one-by-one, whereas loaned messages are always fetched in a sequence - main reason for this being a strong requirements for RTI Connext Micro in order to enable zero-copy.

The question which arises now is whether any rmw_take_* should be modified in a way that it always takes n instances or if we restrict that to loaned messages exclusively. If we did change rmw_take to always take multiple, then we have to push this consequently to rmw_serialized_messages as well as ROS messages allocated by the rclcpp::MessageMemoryStrategy and implement C-based container structures for it.

My thinking here is that in a context of an executor, we probably would get around implementing the message sequences for serialized and non-loaned messages as we handle one callback at a time. But thinking this further and having the ability to use the API outside of the scope of an executor (by polling the waitset or having different implementations of an executor), I personally believe it would be the right thing to do and extend the sequencing also to these types. As the rmw_take_multiple functions can be implemented next to the existing rmw_take, we can still use the latter inside the executor.

Opinions?

Karsten1987 commented 5 years ago

connected to https://github.com/ros2/ros2/issues/785

jacobperron commented 4 years ago

The question which arises now is whether any rmwtake* should be modified in a way that it always takes n instances or if we restrict that to loaned messages exclusively.

It makes sense to me to also extend the "take N" functionality to non-loaned messages, but we probably don't need to include this detail/discussion in this document since it is not exactly related to loaned messages. Probably worth discussing as part of the implementation ticket or a new issue.

mjcarroll commented 4 years ago

Probably worth discussing as part of the implementation ticket or a new issue.

Agreed.

ros-discourse commented 3 years ago

This pull request has been mentioned on ROS Discourse. There might be relevant details there:

https://discourse.ros.org/t/ros-2-galactic-default-middleware-announced/18064/1