ros2 / rclcpp

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

Dynamic Message Deserialization #2260

Open wew84 opened 1 year ago

wew84 commented 1 year ago

Hi,

I'm relatively new to the rclcpp client after several years of using rclpy and both ROS1 clients. I'm trying to deserialize a message dynamically at runtime. I have the following callback for a generic subscriber:

[this, topic_name, topic_type](const std::shared_ptr<rclcpp::SerializedMessage> &message) {
    std::shared_ptr<rcpputils::SharedLibrary> library = rclcpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp");
    const rosidl_message_type_support_t * message_type_support = rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *library);
    auto members = static_cast<const rosidl_typesupport_introspection_cpp::MessageMembers *>(message_type_support->data);
    rcutils_allocator_t allocator = rcutils_get_default_allocator();
    auto data = allocator.allocate(members->size_of_, allocator.state);
    if (nullptr == data) {
        RCLCPP_ERROR(this->get_logger(), "Could not allocate message memory %zu", members->size_of_);
        return;
    }
    rclcpp::SerializationBase ser(message_type_support);
    ser.deserialize_message(message.get(), data);
...

When I run this, I get a members->sizeof of 140737332973024, so I assume the casting to message members is incorrect. I also tried the init_function() in members.

I may be misunderstanding the mechanism for introspection or the serialization API. Any help would be great. Thanks.

wew84 commented 1 year ago

After some further investigation, it looks like the cast to members always returns junk.

Steps to reproduce issue

I wrote this code sample.

#include "rclcpp/rclcpp.hpp"
#include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"

int main(int argc, char * argv[])
{
    std::string topic_type = "std_msgs/msg/String";
    std::shared_ptr<rcpputils::SharedLibrary> library = rclcpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp");
    const rosidl_message_type_support_t * message_type_support = rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *library);
    auto members = static_cast<const rosidl_typesupport_introspection_cpp::MessageMembers *>(message_type_support->data);
}

When I bring up a debugger, I get the following output: image

(I also tested with can_msgs/msg/Frame): image

It seems that the cast should be valid if I correctly understand the IDL generators here.

If this is more relevant in the IDL repo, I'd be happy to move it there.

clalancette commented 1 year ago

So I don't know about the exact code you are using above. But we do have examples of using serialized messages and successfully decoding. One such example is in https://github.com/ros2/demos/blob/rolling/demo_nodes_cpp/src/topics/listener_serialized_message.cpp .

More specifically, rosbag2 implements exactly the kind of message-agnostic thing you are trying to do here. So it may be worthwhile to look at how that is implemented, maybe starting with https://github.com/ros2/rosbag2/blob/rolling/rosbag2_cpp/src/rosbag2_cpp/types/introspection_message.cpp .

Let me know if that helps at all.

doruktiktiklar commented 5 months ago

Hi, I also have a similar problem. I want to write a collector application that output a JSON object periodically. That json object will include a list of items. Each item will include 3 things: the name of the topic, the type of the topic and the deserialized last message in that topic.

This is close to what I want to do, but it does not provide a parse method https://github.com/RobotWebTools/rosbridge_suite/blob/ros2/rosapi/src/rosapi/objectutils.py

Rosbag2 seem to just put the serialized message inside their own serialized message https://github.com/ros2/rosbag2/blob/rolling/rosbag2_cpp/src/rosbag2_cpp/writer.cpp#L202

I guess dynamic deserialization is what I need, but it is not implemented https://github.com/ros2/ros2/issues/1374 https://github.com/eProsima/Fast-DDS/issues/3296 https://github.com/ros2/rclcpp/blob/rolling/rclcpp/src/rclcpp/dynamic_typesupport/dynamic_serialization_support.cpp

Is it possible to do what I want? I would prefer using C++ or python. It probably is possible with C but I am not sure about which way to go.

Barry-Xu-2018 commented 4 months ago

@doruktiktiklar

Your ideas are similar to the current service event. Please refer to https://github.com/ros-infrastructure/rep/blob/336d3b66135ca71a82d5e903de1e865e4ceddd2d/rep-2012.rst#service-event-definition. request and response part are deserialized data.
About parse method, you can refer to the implementation of player_service_client.cpp. e.g. https://github.com/ros2/rosbag2/blob/0b6a8dacef1a7de0117a48502c987209830f5e96/rosbag2_transport/src/rosbag2_transport/player_service_client.cpp#L32-L97