How to get a type of the message having its string type name in C++?

As an input I have a topic name. I want to get the message type of this topic.

  1. I know how to find the string type name using node->get_topic_names_and_types();. The resulting string type name is smth like rcl_interfaces/msg/ParameterEvent (just for example)
  2. Is there any ways in C++ how to get the instance of rcl_interfaces::msg::ParameterEvent or it bumps into C++ being static typed language?

In Python I found the following way of doing that:

import argparse
from ros2cli.node.strategy import NodeStrategy
import rosidl_runtime_py.utilities

with NodeStrategy(argparse.Namespace()) as node:
    for (
        topic,
        topic_type,
    ) in node.daemon_node.get_topic_names_and_types():
        if topic == requested_topic:
            requested_type_str = topic_type[0]


topic_type = rosidl_runtime_py.utilities.get_message(requested_type_str)
print(topic_type) # would print something like <class 'my_custom_package.msg._my_custom_message.MyCustomMessage'>)

for demo see msg_introspection_demo/src/subscriber.cpp at main · Barry-Xu-2018/msg_introspection_demo

for toolkit see facontidavide/rosx_introspection: Deserialize any ROS message, without compilation time information.

2 Likes

If you want to have a normal message layout, lazy copy, the ability to also create and publish messages, action, and service support, the tool you want is:

There are also multiple examples on how to use it to get you started.

Here’s a short example for subscription

using namespace ros_babel_fish; // Except Node all of the following classes are in that namespace
Node node;
BabelFish::SharedPtr fish = BabelFish::make_shared();
// Subscribe topic /pose
BabelFishSubscription::SharedPtr sub = fish->create_subscription( node, topic, 1, &callback );

/* ... */

void callback( const ros_babel_fish::CompoundMessage::SharedPtr &msg )
{
  std::cout << "Message received!" << std::endl;
  std::cout << "Datatype:" << msg->datatype() << std::endl; // geometry_msgs::msg::Pose
  std::cout << "Name:" << msg->name() << std::endl; // geometry_msgs/msg/Pose
  std::cout << "Message Content:" << std::endl;
  const CompoundMessage &compound = *msg;
  std::cout << "Position: " << compound["position"]["x"].value<double>() << ", " << compound["position"]["y"].value<double>() << ", "
            << compound["position"]["z"].value<double>() << std::endl;
  // Alternatively, you can use the new get<T> convenience method
  std::cout << "Orientation: " << compound["orientation"].get<double>("w") << ", " << compound["orientation"].get<double>("x") << ", "
            << compound["orientation"].get<double>("y") << ", " << compound["orientation"].get<double>("z") << std::endl;
};

To create messages:

// ...
BabelFishPublisher::SharedPtr pub_pose = fish->create_publisher( node, "/pose", "geometry_msgs/msg/Pose", 1 );

CompoundMessage::SharedPtr message = fish->create_message_shared( "geometry_msgs/msg/Pose" );
auto &compound = *message;
compound["position"].set<double>("z", 3.6);
pub_pose->publish( compound );
2 Likes