!

(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Introduction to the ROS Introspection API

Description: A simple example that shows the basic usage of ros_type_introspection.

Keywords: introspection

Tutorial Level: BEGINNER

Next Tutorial: Using ros_type_introspection to read data from a generic rosbag. Reading data from a generic Rosbags

In this first example we will use the information provided by gencpp to parse and deserialize a message. Note that in practice this approach make little sense, unless you are writing a unit test of ros_type_introspection itself. We will include the header file containing the ROS message definition, despite the fact that the purpose of this library is to avoid such inclusion!

The example is provided just as a concise presentation of the API.

   1 // You are not supposed to be able to include this header file
   2 // Otherwise you would not need ros_type_introspection at all
   3 // This is just an example
   4 #include <geometry_msgs/Pose.h>
   5 #include <ros_type_introspection/ros_introspection.hpp>
   6 
   7 // This function works only if type Message is known at
   8 // compilation time. This is not true in most of the use cases
   9 // we care about.
  10 template<typename Message>
  11 void ParseAndDeserialize(const Message& sample, const std::string& topic_name)
  12 {
  13   using namespace RosIntrospection;
  14   using namespace ros::message_traits;
  15 
  16   RosIntrospection::Parser parser;
  17 
  18    // add this type to the parser.
  19   parser.registerMessageDefinition(
  20         topic_name,
  21         ROSType(DataType<Message>::value()),
  22         Definition<Message>::value());
  23 
  24   //Serialize the "raw" message into a buffer
  25   size_t msg_length = ros::serialization::serializationLength(sample);
  26   std::vector<uint8_t> buffer(msg_length);
  27   ros::serialization::OStream stream(buffer.data(), buffer.size());
  28   ros::serialization::serialize(stream, sample);
  29 
  30   // A data structure that contains the deserialized information.
  31   // It is not meant to be human readable, but it is easy to process...
  32   FlatMessage flat_container;
  33   parser.deserializeIntoFlatContainer( topic_name,
  34                                        absl::Span<uint8_t>(buffer),
  35                                        &flat_container, 100 );
  36 
  37   // RenamedValues are key/value pairs where the key is a human
  38   // readable identifier.
  39   // It will contains only the values in flat_container.value
  40   RenamedValues renamed_numerical_values;
  41   parser.applyNameTransform( topic_name,
  42                              flat_container,
  43                              &renamed_numerical_values );
  44 
  45   // Print the data.
  46   // The type StringTreeLeaf can be converted to human readble
  47   // string with the method toStdString(),
  48   // Instead Variant can be casted using the method convert<>()
  49   for(auto& it: flat_container.value) {
  50       std::cout << it.first.toStdString() << " >> "
  51                 << it.second.convert<double>() << std::endl;
  52   }
  53   for(auto& it: flat_container.name) {
  54       std::cout << it.first.toStdString() << " >> "
  55                 << it.second << std::endl;
  56   }
  57 }
  58 
  59 int main(int argc, char **argv)
  60 {
  61   geometry_msgs::Pose pose_sample;
  62 
  63   pose_sample.position.x = 1;
  64   pose_sample.position.y = 2;
  65   pose_sample.position.z = 3;
  66 
  67   pose_sample.orientation.x = 4;
  68   pose_sample.orientation.y = 5;
  69   pose_sample.orientation.z = 6;
  70   pose_sample.orientation.w = 7;
  71 
  72   ParseAndDeserialize( pose_sample, "pose");
  73 
  74   return 0;
  75 }
  76 /* Expected output
  77 
  78 pose/position/x >> 1
  79 pose/position/y >> 2
  80 pose/position/z >> 3
  81 pose/orientation/x >> 4
  82 pose/orientation/y >> 5
  83 pose/orientation/z >> 6
  84 pose/orientation/w >> 7
  85 
  86 */

As you can notice, we were able to deserialize the raw message in buffer into individual fields containing either numbers or strings.

In the next tutorial we will explore a more practical example that does not require compile time information, just the message definition.

Wiki: ros_type_introspection/Tutorials/IntrospectionAPI (last edited 2019-01-19 15:23:47 by DavideFaconti)