Git Product home page Git Product logo

Comments (10)

tonynajjar avatar tonynajjar commented on June 28, 2024 2

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?

from rclcpp.

Barry-Xu-2018 avatar Barry-Xu-2018 commented on June 28, 2024 1

@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

from rclcpp.

tonynajjar avatar tonynajjar commented on June 28, 2024

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

from rclcpp.

fujitatomoya avatar fujitatomoya commented on June 28, 2024

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

from rclcpp.

Barry-Xu-2018 avatar Barry-Xu-2018 commented on June 28, 2024

I think there are two scenarios.

  • The message type is one of a few known types
  • The message type is completely unknown (many types).

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.

from rclcpp.

tonynajjar avatar tonynajjar commented on June 28, 2024

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

from rclcpp.

fujitatomoya avatar fujitatomoya commented on June 28, 2024

@Barry-Xu-2018 @tonynajjar

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

from rclcpp.

tonynajjar avatar tonynajjar commented on June 28, 2024

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?

from rclcpp.

tonynajjar avatar tonynajjar commented on June 28, 2024

Just found #2260 which is also similar

from rclcpp.

Barry-Xu-2018 avatar Barry-Xu-2018 commented on June 28, 2024

@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.

from rclcpp.

Related Issues (20)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.