Public Member Functions | Protected Attributes
RosIntrospection::ROSType Class Reference

Description of a ROS type. More...

#include <parser.hpp>

List of all members.

Public Member Functions

int arraySize () const
const SStringbaseName () const
VarNumber deserializeFromBuffer (uint8_t **buffer) const
bool isArray () const
 True if the type is an array.
bool isBuiltin () const
 True if the type is ROS builtin.
const SStringmsgName () const
 ex.: geometry_msgs/Pose[40] -> "Pose"
bool operator< (const ROSType &other) const
bool operator== (const ROSType &other) const
const SStringpkgName () const
 ex.: geometry_msgs/Pose[40] -> "geometry_msgs"
 ROSType ()
 ROSType (const std::string &name)
void setPkgName (const SString &new_pkg)
BuiltinType typeID () const
 If type is builtin, returns the id. BuiltinType::OTHER otherwise.
int typeSize () const
 If builtin, size of builtin, -1 means variable or undefined.

Protected Attributes

int _array_size
SString _base_name
boost::function< VarNumber(uint8_t
**buffer) 
_deserialize_impl )
BuiltinType _id
SString _msg_name
SString _pkg_name

Detailed Description

Description of a ROS type.

Definition at line 62 of file parser.hpp.


Constructor & Destructor Documentation

Definition at line 65 of file parser.hpp.

RosIntrospection::ROSType::ROSType ( const std::string &  name)

Definition at line 74 of file parser.cpp.


Member Function Documentation

1 if !is_array, -1 if is_array and array is variable length, otherwise length in name

Definition at line 300 of file parser.cpp.

Concatenation of msg_name and pkg_name. ex.: geometry_msgs/Pose[40]"

Definition at line 268 of file parser.cpp.

VarNumber RosIntrospection::ROSType::deserializeFromBuffer ( uint8_t **  buffer) const [inline]

Definition at line 105 of file parser.hpp.

True if the type is an array.

Definition at line 290 of file parser.cpp.

True if the type is ROS builtin.

Definition at line 295 of file parser.cpp.

ex.: geometry_msgs/Pose[40] -> "Pose"

Definition at line 273 of file parser.cpp.

bool RosIntrospection::ROSType::operator< ( const ROSType other) const [inline]

Definition at line 101 of file parser.hpp.

bool RosIntrospection::ROSType::operator== ( const ROSType other) const [inline]

Definition at line 97 of file parser.hpp.

ex.: geometry_msgs/Pose[40] -> "geometry_msgs"

Definition at line 278 of file parser.cpp.

Definition at line 283 of file parser.cpp.

If type is builtin, returns the id. BuiltinType::OTHER otherwise.

Definition at line 316 of file parser.cpp.

If builtin, size of builtin, -1 means variable or undefined.

Definition at line 305 of file parser.cpp.


Member Data Documentation

Definition at line 116 of file parser.hpp.

Definition at line 117 of file parser.hpp.

boost::function<VarNumber(uint8_t** buffer) RosIntrospection::ROSType::_deserialize_impl) [protected]

Definition at line 120 of file parser.hpp.

Definition at line 115 of file parser.hpp.

Definition at line 118 of file parser.hpp.

Definition at line 119 of file parser.hpp.


The documentation for this class was generated from the following files:


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