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

Add non transform capabilities for intra-process #1849

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
140 changes: 104 additions & 36 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -476,6 +476,22 @@ class AnySubscriptionCallback
}
}

std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
convert_custom_type_to_ros_message_unique_ptr(const SubscribedType & msg)
{
if constexpr (rclcpp::TypeAdapter<MessageT>::is_specialized::value) {
auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr);
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(msg, *ptr);
return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
} else {
static_assert(
clalancette marked this conversation as resolved.
Show resolved Hide resolved
!sizeof(MessageT *),
"convert_custom_type_to_ros_message_unique_ptr() "
"unexpectedly called without specialized TypeAdapter");
}
}

// Dispatch when input is a ros message and the output could be anything.
void
dispatch(
Expand Down Expand Up @@ -658,7 +674,7 @@ class AnySubscriptionCallback

void
dispatch_intra_process(
std::shared_ptr<const ROSMessageType> message,
std::shared_ptr<const SubscribedType> message,
const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, static_cast<const void *>(this), true);
Expand All @@ -677,65 +693,89 @@ class AnySubscriptionCallback

// conditions for custom type
if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
callback(*local_message);
callback(*message);
} else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
callback(*local_message, message_info);
callback(*message, message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrCallback>||
std::is_same_v<T, SharedPtrCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message));
callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message));
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrWithInfoCallback>||
std::is_same_v<T, SharedPtrWithInfoCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message), message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrCallback>||
std::is_same_v<T, ConstRefSharedConstPtrCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message));
callback(message);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
callback(message, message_info);
}
// conditions for ros message type
else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT
callback(*message);
} else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) {
callback(*message, message_info);
else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT[readability/braces]
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this case cannot happen, right?

Now for intraprocess communication, the intraprocess buffer always stores instances of SubscribedType, and that will match the type specified in the callback.
We don't need a special code path for this case AFAIS.

I also don't think the possible types should have two specializations for ROS messages and type adapters, the possible callbacks are the same in both cases and the argument is always a kind of reference/pointer to SubscribedType.

In the only case we need to aware of the "ROS message type" is in interprocess dispatch.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Even if the buffer is of SubscribedType, the callback may require a ROSMessage.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Even if the buffer is of SubscribedType, the callback may require a ROSMessage.

How?
We're creating a buffer type based on the callback type.

i.e. if your callback is a smart_ptr<ROSMessage> or a ROSMessage & the buffer will also be a smart pointer to a ROSMessage.

Thus, all those code paths seem unnecessary, and we do have a lot of code paths!

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i.e. if your callback is a smart_ptr or a ROSMessage & the buffer will also be a smart pointer to a ROSMessage.

I don't think this is the case (though there is a lot going on here, so I could be wrong).

There can be a difference between the type that the subscription was created with, and the type that the callback is. Consider the following (modified from one of the tests):

// Assume we defined the TypeAdapter already
using StringTypeAdapter = rclcpp::TypeAdapter<std::string, rclcpp::msg::String>;
auto callback =
  [message_data, &is_received](
  const rclcpp::msg::String & msg) -> void
  {
    // do something
  }
auto sub = node->create_subscription<StringTypeAdapter>(topic_name, 1, callback);

When we create the subscription, through many layers we end up creating the buffer as a std::string (since that is the SubscribedType here). But our callback is a ROSMessage type, so we need these conversion routines to do the conversion right before we deliver to the callback.

Copy link
Member

@ivanpauno ivanpauno Jan 5, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

(edit) Read next comment, this one can be ignored.


I don't think that example makes sense, specifying StringTypeAdapter is not really useful if the callback is expecting a msg::String.
i.e. what's the benefit of doing that instead of just using create_subscription<msg::String>?
If there's no benefit, we shouldn't support it.
It adds complexity because you need to keep track of more combinations in the implementation.

I also think we cannot really allow that kind of code if we want the compiler to be able to infer the correct Subscription type from the callback type in Node::create_subscription().

i.e. being able to write

auto sub = node->create_subscription(topic_name, 1, callback);  // subscription type inferred from callback type

I think there's no way to infer it if both a Subscription<msg::String> and a Subscription<StringTypeAdapter> accept a msg::String callback. Though I might be wrong, c++ templates and specialization rules are complex and I cannot really remember them.
I have also not kept track of what's currently possible, I have a few questions:

  • is it possible to mix callback and subscription type as the example above?
  • is automatic template parameter inference still working for create_subscription()? IIUC, that used to work (*).

If the answer to both those question is yes, my only reason to not support that is that I don't see the benefit and it adds complexity.
I guess we can ignore that, but if we later want to not support that to reduce complexity it will be an API breaking change.

(*) If we currently support code as the example above, I guess it will only break if no type is passed and a type adapter is available, though it will still work if there's no type adapter for that message type.
I can also imagine a long and impossible to understand compiler error, which is also something to check and consider.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is automatic template parameter inference still working for create_subscription()? IIUC, that used to work (*).

Sorry, my memory is bad, I think we never supported this.
My concern about breaking template parameter inference can be ignored.

The only part I think that it's still valid from my last comment is that supporting that example seems unnecessary, but considering that we already do support it, I think we can move forward.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The only part I think that it's still valid from my last comment is that supporting that example seems unnecessary, but considering that we already do support it, I think we can move forward.

I talked to @audrow and @wjwwood a little bit about this, and part of the idea was so that you could potentially have multiple TypeAdapters for the same types together. Passing the correct TypeAdapter type to the subscription would let the compiler know which of them to choose. That said, I'll let @wjwwood comment here, as he has the best long-term vision for this.

Regardless, I think I'm going to move forward here and address the (minor) points raised by @audrow , and then run CI on the lot again.

Copy link
Member

@ivanpauno ivanpauno Jan 7, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Regardless, I think I'm going to move forward here and address the (minor) points raised by @audrow , and then run CI on the lot again.

Moving forward sounds good.

Passing the correct TypeAdapter type to the subscription would let the compiler know which of them to choose

That's fine.
My comment is about the need to support Subscription<TypeAdapterT>(..., CallbackUsingRosMessageT callback, ...), i.e. allowing to pass a callback that takes some smart pointer or referece to a ROS message type while asking for a TypeAdapterT subscription.
In practice, if the user replace TypeAdapterT with RosMessageT the implementation will do behind the scenes the exact same thing.
Allowing that adds a lot of code paths in the dispatching logic, but it doesn't seem to add any value.

Putting it another way, you always want the intraprocess buffer to match the type expected by the callback (as in that way it's possible to avoid the most copies).
I assumed that the type expected by the callback was always the Subscription<...> template parameter type, but that doesn't seem to actually be the case.
The intraprocess buffer type can currently be different to the callback type, as it's chosen basen on the subscription type, which is suboptimal.
As commented in the previous paragrah, there doesn't seem to be a real reason to allow mixing a RosMessageT callback type with a TypeAdapterT subscription.

// this two subscriptions will dispatch intraprocess and interprocess messages in the exact same way
// their type is different for the cpp type system, but that doesn't seem to have any usefulness.
// my proposal is to not support creating sub2, only sub1
// (edit) actually, the second alternative sub2 currently dispatches intraprocess messages more inefficiently.
//   But they should be doing the same thing really, so I think we should support one to reduce complexity.
auto callback = [] (msg::MyMsg::SharedPtr msg) {...};
rclcpp::Subscription<msg::MyMsg> sub1 = node->create_subscription<msg::MyMsg>(..., callback);
rclcpp::Subscription<MyTypeAdaptedToMsg> sub2 = node->create_subscription<MyTypeAdaptedToMsg>(..., callback);

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've opened up #1860 to track this (and one other issue) for the future.

if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local);
} else {
callback(*message);
}
} else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) { // NOLINT[readability/braces]
if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local, message_info);
} else {
callback(*message, message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrROSMessageCallback>||
std::is_same_v<T, SharedPtrROSMessageCallback>)
{
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message));
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message));
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
{
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info);
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>)
{
callback(message);
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(message);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>)
{
callback(message, message_info);
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(message, message_info);
}
}
// condition to catch SerializedMessage types
else if constexpr ( // NOLINT[readability/braces]
Expand Down Expand Up @@ -764,7 +804,7 @@ class AnySubscriptionCallback

void
dispatch_intra_process(
std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> message,
std::unique_ptr<SubscribedType, SubscribedTypeDeleter> message,
const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, static_cast<const void *>(this), true);
Expand All @@ -778,70 +818,98 @@ class AnySubscriptionCallback
// Dispatch.
std::visit(
[&message, &message_info, this](auto && callback) {
// clang complains that 'this' lambda capture is unused, which is true
// in *some* specializations of this template, but not others. Just
// quiet it down.
(void)this;

using T = std::decay_t<decltype(callback)>;
static constexpr bool is_ta = rclcpp::TypeAdapter<MessageT>::is_specialized::value;

// conditions for custom type
if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
callback(*local_message);
callback(*message);
} else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
callback(*local_message, message_info);
callback(*message, message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrCallback>||
std::is_same_v<T, SharedPtrCallback>
))
std::is_same_v<T, SharedPtrCallback>))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message));
callback(std::move(message));
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrWithInfoCallback>||
std::is_same_v<T, SharedPtrWithInfoCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
callback(std::move(message), message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrCallback>||
std::is_same_v<T, ConstRefSharedConstPtrCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message));
callback(std::move(message));
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
callback(std::move(message), message_info);
}
// conditions for ros message type
else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT
callback(*message);
} else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) {
callback(*message, message_info);
else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT[readability/braces]
if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local);
} else {
callback(*message);
}
} else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) { // NOLINT[readability/braces]
if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local, message_info);
} else {
callback(*message, message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrROSMessageCallback>||
std::is_same_v<T, SharedPtrROSMessageCallback>)
{
callback(std::move(message));
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(std::move(message));
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
{
callback(std::move(message), message_info);
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(std::move(message), message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>)
{
callback(std::move(message));
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(std::move(message));
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>)
{
callback(std::move(message), message_info);
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(std::move(message), message_info);
}
}
// condition to catch SerializedMessage types
else if constexpr ( // NOLINT[readability/braces]
Expand Down
Loading