Classes | Namespaces | Functions
deserializer.hpp File Reference
#include <array>
#include <sstream>
#include "ros_type_introspection/parser.hpp"
#include "ros_type_introspection/stringtree.hpp"
#include "ros_type_introspection/variant.hpp"
Include dependency graph for deserializer.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  RosIntrospection::ROSTypeFlat
struct  RosIntrospection::StringTreeLeaf
 The StringTreeLeaf is, as the name suggests, a leaf (terminal node) of a StringTree. It provides the pointer to the node and a list of numbers that represent the index that corresponds to the placeholder "#". More...

Namespaces

namespace  RosIntrospection

Functions

void RosIntrospection::buildRosFlatType (const ROSTypeList &type_map, ROSType type, SString prefix, uint8_t *buffer_ptr, ROSTypeFlat *flat_container_output, const uint32_t max_array_size)
 buildRosFlatType is a function that read raw serialized data from a ROS message (generated by a ros bag or a topic) and stored the values of each field in a "flat" container called ROSTypeFlat. For example if you apply this to [geometry_msgs/Pose](http://docs.ros.org/kinetic/api/geometry_msgs/html/msg/Pose.html) the vector ROSTypeFlat::value will contain the following pairs (where ... is the number of that field) :
std::ostream & RosIntrospection::operator<< (std::ostream &os, const StringTreeLeaf &leaf)
int RosIntrospection::print_number (char *buffer, uint16_t value)


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Sun Oct 1 2017 02:54:53