ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
536 stars 417 forks source link

Feature Request: Dynamic Type Handling for Generic Subscriptions #2568

Open tonynajjar opened 3 months ago

tonynajjar commented 3 months ago

Feature request

Feature description

I am developing an application where I need to subscribe to topics with unknown message types (similar to rosbag2). In the subscription callback, I need access to the deserialized message and its fields without knowing the type in advance.

There is a related example here, but it requires specifying the type (T2) beforehand. I am looking for a way to use only the topic type as a string to dynamically obtain the message class.

Using snippets here and there from rclcpp I put together this incomplete example:

node->create_generic_subscription(
  topic_name,
  topic_type,
  qos,
  [this, topic_name, topic_type](std::shared_ptr<const rclcpp::SerializedMessage> message,
  const rclcpp::MessageInfo & mi) {
    void* deserialized_msg = nullptr;
    auto ts_lib = rclcpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp");
    auto type_support = rclcpp::get_message_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib);
    rmw_deserialize(&message->get_rcl_serialized_message(), type_support, deserialized_msg);
  });

The issue is that deserialized_msg is a null pointer ('void *'), and I am unsure how to proceed from here.

If there is currently no way to achieve this, please consider this a feature request. I am open to contributing with some guidance on the implementation. Thanks!

Related:

https://answers.ros.org/question/405796/deserialize-message-with-topic-name-ros2/ https://github.com/ros2/rclcpp/issues/2260 https://github.com/ros2/ros2/issues/1374 https://github.com/facontidavide/rosx_introspection

tonynajjar commented 3 months ago

I found this simillar unanswered question: https://answers.ros.org/question/405796/deserialize-message-with-topic-name-ros2/

fujitatomoya commented 3 months ago

@Barry-Xu-2018 do you have any thoughts?

Barry-Xu-2018 commented 3 months ago

I think there are two scenarios.

In the first scenario, you should be able to easily cast the pointer to the message type.

In the second scenario, you can use type support to parse each type in the message one by one. e.g. https://github.com/ros2/rosbag2/blob/fa84cfeeb0b640d53c23d25634ec5b0177ae1efe/rosbag2_transport/src/rosbag2_transport/player_service_client.cpp#L163-L168 If you want this way, I can provide a simple example to demonstrate how to do.

tonynajjar commented 3 months ago

Thanks @Barry-Xu-2018 for your answer. Mine is the second scenario, I'd be grateful if you can provide an example. I would try it out and give feedback in a couple of hours

fujitatomoya commented 3 months ago

@Barry-Xu-2018 @tonynajjar

what about having either demos or examples for this? i believe that would be useful for ROS community?

tonynajjar commented 3 months ago

what about having either demos or examples for this? i believe that would be useful for ROS community?

It would definitely be useful to a handful of people given that it's been asked a couple of times already here and there

Also the reason why we would need a tutorial for this is because it's (imo) a reasonable thing for high-level users of ROS to want to do but the way to do it seems pretty low-level (with type support and other things I've never heard of with 5 years of experience with ROS). So I'm wondering if it would make sense to expose this functionality on a higher-level? Some function in client libraries?

tonynajjar commented 3 months ago

I stumbled upon https://github.com/facontidavide/rosx_introspection and was able to make a prototype! Here is the pseudo-code:

#include "rosx_introspection/ros_parser.hpp"
#include "rosx_introspection/ros_utils/ros2_helpers.hpp"

using namespace RosMsgParser;

ParsersCollection<ROS2_Deserializer> parser_;

void print_fields(const std::string& topic_name, const std::string& topic_type, std::shared_ptr<const rclcpp::SerializedMessage> serialized_message) {
    parser_.registerParser(topic_name, ROSType(topic_type),
                            GetMessageDefinition(topic_type));
    std::vector<uint8_t> buffer(serialized_message->get_rcl_serialized_message().buffer_length);
    memcpy(buffer.data(), serialized_message->get_rcl_serialized_message().buffer, serialized_message->get_rcl_serialized_message().buffer_length);

    const FlatMessage* flat_container = parser_.deserialize(topic_name, Span<uint8_t>(buffer));

    for (auto& it : flat_container->value)
    {
        std::cout << it.first << " >> " << it.second.convert<double>() << std::endl;
    }
    for (auto& it : flat_container->name)
    {
        std::cout << it.first << " >>>" << it.second << std::endl;
    }
}

@facontidavide thanks for that project. As there is no real guide, I got inspired from the tests mostly, am I using your library correctly? Any recommendations?

@Barry-Xu-2018 @fujitatomoya maybe this could be a good starting point to implement something similar in rclcpp?

tonynajjar commented 3 months ago

Just found https://github.com/ros2/rclcpp/issues/2260 which is also similar

Barry-Xu-2018 commented 3 months ago

@tonynajjar

I'd be grateful if you can provide an example. I would try it out and give feedback in a couple of hours

Apologies for the delayed reply. I will prepare a simple example for you.

I'll look into https://github.com/facontidavide/rosx_introspection.

Barry-Xu-2018 commented 3 months ago

@tonynajjar

This is a simple sample (The code is a bit ugly. I haven't had time to check out the implementation of rosx_introspection yet.). It tries to get items of sensor_msgs::msg::Temperature based on generic subscription.
https://github.com/Barry-Xu-2018/msg_introspection_demo

Barry-Xu-2018 commented 1 month ago

@tonynajjar

Would using rosx_introspection meet your requirements ?
Alternatively, you could write it yourself (refer to https://github.com/Barry-Xu-2018/msg_introspection_demo).

If there are no further questions, can I close this issue?

tonynajjar commented 1 month ago

Hi @Barry-Xu-2018,

I didn't go beyond an initial prototype yet using rosx_introspection but that seemed to work.

So I'm wondering if it would make sense to expose this functionality on a higher-level? Some function in client libraries?

I still think this could make sense to implement in rclcpp. If you disagree, then we can close the issue for now and I would report back if more than your example or rosx_introspection is needed. Thanks for your support

Barry-Xu-2018 commented 1 month ago

I still think this could make sense to implement in rclcpp. If you disagree, then we can close the issue for now and I would report back if more than your example or rosx_introspection is needed. Thanks for your support

Based on my thoughts, this isn't a general requirement, so it's not quite suitable to include in rclcpp. Of course, we can listen to others' opinions as well.

tonynajjar commented 2 weeks ago

Cross-linking another repo I found related to this issue: https://github.com/LOEWE-emergenCITY/ros_babel_fish

FYI @StefanFabian

StefanFabian commented 2 weeks ago

Thanks for the mention @tonynajjar I think rclcpp and rosidl_typesupport_introspection_cpp already contain all helpers necessary to handle dynamic types. I hope the examples in my repo are enough to help you understand my approach.

One noteworthy difference to rosx_introspection is that rosx_introspection manually deserializes messages from CDR, and I'm not sure how many middlewares use CDR to serialize messages. ros_babel_fish operates a layer higher. It lets rclcpp do the deserialization and uses the introspection functions to wrap the message. Hence, in theory, it should work with any middleware. Wrapping the message instead of transforming it enables my library to:

  1. Handle large messages, e.g., images, without expensive operations, such as copying the entire image data.
  2. Use lazy evaluation, which means you only pay for what you use. If you only need the header of the message, the rest of the message is not processed.

In my biased view, I think ros_babel_fish is the easiest library for tasks such as this with minimal performance overhead.