Namespaces | |
| namespace | details |
Classes | |
| class | RangeException |
| class | ROSField |
| A ROSMessage will contain one or more ROSField(s). Each field is little more than a name / type pair. More... | |
| class | ROSMessage |
| class | ROSType |
| Description of a ROS type. More... | |
| struct | ROSTypeFlat |
| class | ShapeShifter |
| The ShapeShifter class is a type erased container for ROS Messages. It can be used also to create generic publishers and subscribers. More... | |
| struct | 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... | |
| class | SubstitutionRule |
| class | TypeException |
| class | VarNumber |
Typedefs | |
| typedef std::vector< std::pair < std::string, VarNumber > > | RenamedValues |
| typedef std::vector< ROSMessage > | ROSTypeList |
| typedef ssoX::basic_string< char > | SString |
| typedef details::Tree< SString > | StringTree |
| typedef details::TreeElement < SString > | StringTreeNode |
| typedef std::map< std::string, std::vector < RosIntrospection::SubstitutionRule > > | SubstitutionRuleMap |
Enumerations | |
| enum | BuiltinType { BOOL, BYTE, CHAR, UINT8, UINT16, UINT32, UINT64, INT8, INT16, INT32, INT64, FLOAT32, FLOAT64, TIME, DURATION, STRING, OTHER } |
Functions | |
| void | applyNameTransform (const std::vector< SubstitutionRule > &rules, const ROSTypeFlat &container_source, RenamedValues &renamed_destination) |
| void | 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) : | |
| void | buildRosFlatTypeImpl (const ROSTypeList &type_list, const ROSType &type, StringTreeLeaf tree_node, uint8_t **buffer_ptr, ROSTypeFlat *flat_container, const uint32_t max_array_size, bool do_store) |
| ROSTypeList | 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. | |
| bool | FindPattern (const std::vector< SString > &pattern, size_t index, const StringTreeNode *tail, const StringTreeNode **head) |
| template<typename T > | |
| BuiltinType | getType () |
| template<> | |
| BuiltinType | getType< bool > () |
| template<> | |
| BuiltinType | getType< double > () |
| template<> | |
| BuiltinType | getType< float > () |
| template<> | |
| BuiltinType | getType< int16_t > () |
| template<> | |
| BuiltinType | getType< int32_t > () |
| template<> | |
| BuiltinType | getType< int64_t > () |
| template<> | |
| BuiltinType | getType< int8_t > () |
| template<> | |
| BuiltinType | getType< ros::Duration > () |
| template<> | |
| BuiltinType | getType< ros::Time > () |
| template<> | |
| BuiltinType | getType< std::string > () |
| template<> | |
| BuiltinType | getType< uint16_t > () |
| template<> | |
| BuiltinType | getType< uint32_t > () |
| template<> | |
| BuiltinType | getType< uint64_t > () |
| template<> | |
| BuiltinType | getType< uint8_t > () |
| bool | isNumberPlaceholder (const SString &s) |
| bool | isSeparator (const std::string &line) |
| bool | isSubstitutionPlaceholder (const SString &s) |
| std::ostream & | operator<< (std::ostream &os, const BuiltinType &c) |
| std::ostream & | operator<< (std::ostream &os, const StringTreeLeaf &leaf) |
| std::ostream & | operator<< (std::ostream &s, const ROSTypeList &c) |
| template<typename T > | |
| bool | operator== (const VarNumber &var, const T &num) |
| template<typename T > | |
| bool | operator== (const T &num, const VarNumber &var) |
| int | PatternMatchAndIndexPosition (const StringTreeLeaf &leaf, const StringTreeNode *pattern_head) |
| int | print_number (char *buffer, uint16_t value) |
| template<typename T > | |
| T | ReadFromBuffer (uint8_t **buffer) |
| SString | strippedTypeName (const boost::string_ref &line) |
| const char * | toStr (const BuiltinType &c) |
Variables | |
| const int | BuiltinTypeSize [OTHER] |
| typedef std::vector< std::pair<std::string, VarNumber> > RosIntrospection::RenamedValues |
Definition at line 127 of file renamer.hpp.
| typedef std::vector<ROSMessage> RosIntrospection::ROSTypeList |
Definition at line 164 of file parser.hpp.
| typedef ssoX::basic_string<char> RosIntrospection::SString |
Definition at line 50 of file parser.hpp.
Definition at line 57 of file parser.hpp.
Definition at line 56 of file parser.hpp.
| typedef std::map< std::string, std::vector< RosIntrospection::SubstitutionRule > > RosIntrospection::SubstitutionRuleMap |
Definition at line 125 of file renamer.hpp.
| BOOL | |
| BYTE | |
| CHAR | |
| UINT8 | |
| UINT16 | |
| UINT32 | |
| UINT64 | |
| INT8 | |
| INT16 | |
| INT32 | |
| INT64 | |
| FLOAT32 | |
| FLOAT64 | |
| TIME | |
| DURATION | |
| STRING | |
| OTHER |
Definition at line 11 of file builtin_types.hpp.
| void RosIntrospection::applyNameTransform | ( | const std::vector< SubstitutionRule > & | rules, |
| const ROSTypeFlat & | container_source, | ||
| RenamedValues & | renamed_destination | ||
| ) |
Definition at line 112 of file renamer.cpp.
| 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) :
IMPORTANT: this approach is not meant to be used with use arrays such as maps, point clouds and images. It would require a ridicoulous amount of memory and, franckly, make little sense. For this reason the argument max_array_size is used.
| type_map | list of all the ROSMessage already known by the application (built using buildROSTypeMapFromDefinition) |
| type | The main type that correspond to this serialized data. |
| prefix | prefix to add to the name (actually, the root of StringTree). |
| buffer_ptr | Pointer to the first element of the serialized data. |
| flat_container_output | output. It is recommended to reuse the same object if possible to reduce the amount of memory allocation. |
| max_array_size | all the vectors that contains more elements than max_array_size will be discarted. |
Definition at line 205 of file deserializer.cpp.
| void RosIntrospection::buildRosFlatTypeImpl | ( | const ROSTypeList & | type_list, |
| const ROSType & | type, | ||
| StringTreeLeaf | tree_node, | ||
| uint8_t ** | buffer_ptr, | ||
| ROSTypeFlat * | flat_container, | ||
| const uint32_t | max_array_size, | ||
| bool | do_store | ||
| ) |
Definition at line 42 of file deserializer.cpp.
| 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.
| type_name | name to give to the main type to be extracted. |
| msg_definition | text obtained by either: |
Definition at line 218 of file parser.cpp.
| bool RosIntrospection::FindPattern | ( | const std::vector< SString > & | pattern, |
| size_t | index, | ||
| const StringTreeNode * | tail, | ||
| const StringTreeNode ** | head | ||
| ) | [inline] |
Definition at line 52 of file renamer.cpp.
| BuiltinType RosIntrospection::getType | ( | ) |
Definition at line 50 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< bool > | ( | ) | [inline] |
Definition at line 55 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< double > | ( | ) | [inline] |
Definition at line 68 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< float > | ( | ) | [inline] |
Definition at line 67 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< int16_t > | ( | ) | [inline] |
Definition at line 58 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< int32_t > | ( | ) | [inline] |
Definition at line 59 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< int64_t > | ( | ) | [inline] |
Definition at line 60 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< int8_t > | ( | ) | [inline] |
Definition at line 57 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< ros::Duration > | ( | ) | [inline] |
Definition at line 73 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< ros::Time > | ( | ) | [inline] |
Definition at line 72 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< std::string > | ( | ) | [inline] |
Definition at line 70 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< uint16_t > | ( | ) | [inline] |
Definition at line 63 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< uint32_t > | ( | ) | [inline] |
Definition at line 64 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< uint64_t > | ( | ) | [inline] |
Definition at line 65 of file builtin_types.hpp.
| BuiltinType RosIntrospection::getType< uint8_t > | ( | ) | [inline] |
Definition at line 62 of file builtin_types.hpp.
| bool RosIntrospection::isNumberPlaceholder | ( | const SString & | s | ) | [inline] |
Definition at line 42 of file renamer.cpp.
| bool RosIntrospection::isSeparator | ( | const std::string & | line | ) | [inline] |
Definition at line 51 of file parser.cpp.
| bool RosIntrospection::isSubstitutionPlaceholder | ( | const SString & | s | ) | [inline] |
Definition at line 47 of file renamer.cpp.
| std::ostream& RosIntrospection::operator<< | ( | std::ostream & | os, |
| const BuiltinType & | c | ||
| ) | [inline] |
Definition at line 35 of file builtin_types.hpp.
| std::ostream& RosIntrospection::operator<< | ( | std::ostream & | os, |
| const StringTreeLeaf & | leaf | ||
| ) | [inline] |
Definition at line 138 of file deserializer.hpp.
| std::ostream & RosIntrospection::operator<< | ( | std::ostream & | s, |
| const ROSTypeList & | c | ||
| ) |
Definition at line 252 of file parser.cpp.
| bool RosIntrospection::operator== | ( | const VarNumber & | var, |
| const T & | num | ||
| ) | [inline] |
Definition at line 39 of file variant.hpp.
| bool RosIntrospection::operator== | ( | const T & | num, |
| const VarNumber & | var | ||
| ) | [inline] |
Definition at line 45 of file variant.hpp.
| int RosIntrospection::PatternMatchAndIndexPosition | ( | const StringTreeLeaf & | leaf, |
| const StringTreeNode * | pattern_head | ||
| ) |
Definition at line 87 of file renamer.cpp.
| int RosIntrospection::print_number | ( | char * | buffer, |
| uint16_t | value | ||
| ) | [inline] |
Definition at line 149 of file deserializer.hpp.
| T RosIntrospection::ReadFromBuffer | ( | uint8_t ** | buffer | ) | [inline] |
Definition at line 125 of file parser.hpp.
| SString RosIntrospection::strippedTypeName | ( | const boost::string_ref & | line | ) | [inline] |
Definition at line 62 of file parser.cpp.
| const char* RosIntrospection::toStr | ( | const BuiltinType & | c | ) | [inline] |
Definition at line 20 of file builtin_types.hpp.
| const int RosIntrospection::BuiltinTypeSize[OTHER] |
{
1, 1, 1,
1, 2, 4, 8,
1, 2, 4, 8,
4, 8,
8, 8,
-1
}
Definition at line 41 of file builtin_types.hpp.