Classes | Namespaces | Typedefs | Functions
parser.hpp File Reference
#include <vector>
#include <map>
#include <boost/function.hpp>
#include <boost/utility/string_ref.hpp>
#include "ros_type_introspection/stringtree.hpp"
#include "ros_type_introspection/variant.hpp"
Include dependency graph for parser.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  RosIntrospection::ROSField
 A ROSMessage will contain one or more ROSField(s). Each field is little more than a name / type pair. More...
class  RosIntrospection::ROSMessage
class  RosIntrospection::ROSType
 Description of a ROS type. More...

Namespaces

namespace  RosIntrospection

Typedefs

typedef std::vector< ROSMessage > RosIntrospection::ROSTypeList
typedef ssoX::basic_string< char > RosIntrospection::SString
typedef details::Tree< SString > RosIntrospection::StringTree
typedef details::TreeElement
< SString > 
RosIntrospection::StringTreeNode

Functions

ROSTypeList RosIntrospection::buildROSTypeMapFromDefinition (const std::string &type_name, const std::string &msg_definition)
 A single message definition will (most probably) generate myltiple ROSMessage(s). In fact the "child" ROSTypes are parsed as well in a recursive and hierarchical way. To make an example, given as input the [geometry_msgs/Pose](http://docs.ros.org/kinetic/api/geometry_msgs/html/msg/Pose.html) the result will be a ROSTypeList containing Pose, Point and Quaternion.
std::ostream & RosIntrospection::operator<< (std::ostream &s, const ROSTypeList &c)
template<typename T >
RosIntrospection::ReadFromBuffer (uint8_t **buffer)


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