Public Member Functions | Protected Attributes | List of all members
RosIntrospection::ROSType Class Reference

ROSType. More...

#include <ros_type.hpp>

Public Member Functions

const std::string & baseName () const
 
size_t hash () const
 
bool isBuiltin () const
 True if the type is ROS builtin. More...
 
const absl::string_viewmsgName () const
 ex.: geometry_msgs/Pose -> "Pose" More...
 
bool operator!= (const ROSType &other) const
 
bool operator< (const ROSType &other) const
 
ROSTypeoperator= (const ROSType &other)
 
ROSTypeoperator= (ROSType &&other)
 
bool operator== (const ROSType &other) const
 
const absl::string_viewpkgName () const
 ex.: geometry_msgs/Pose -> "geometry_msgs" More...
 
 ROSType ()
 
 ROSType (absl::string_view name)
 
 ROSType (const ROSType &other)
 
 ROSType (ROSType &&other)
 
void setPkgName (absl::string_view new_pkg)
 
BuiltinType typeID () const
 If type is builtin, returns the id. BuiltinType::OTHER otherwise. More...
 
int typeSize () const
 If builtin, size of builtin, -1 means variable or undefined. More...
 

Protected Attributes

std::string _base_name
 
size_t _hash
 
BuiltinType _id
 
absl::string_view _msg_name
 
absl::string_view _pkg_name
 

Detailed Description

ROSType.

Definition at line 50 of file ros_type.hpp.

Constructor & Destructor Documentation

RosIntrospection::ROSType::ROSType ( )
inline

Definition at line 53 of file ros_type.hpp.

RosIntrospection::ROSType::ROSType ( absl::string_view  name)

Definition at line 42 of file ros_type.cpp.

RosIntrospection::ROSType::ROSType ( const ROSType other)
inline

Definition at line 57 of file ros_type.hpp.

RosIntrospection::ROSType::ROSType ( ROSType &&  other)
inline

Definition at line 59 of file ros_type.hpp.

Member Function Documentation

const std::string & RosIntrospection::ROSType::baseName ( ) const
inline

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

Definition at line 112 of file ros_type.hpp.

size_t RosIntrospection::ROSType::hash ( ) const
inline

Definition at line 98 of file ros_type.hpp.

bool RosIntrospection::ROSType::isBuiltin ( ) const
inline

True if the type is ROS builtin.

Definition at line 127 of file ros_type.hpp.

const absl::string_view & RosIntrospection::ROSType::msgName ( ) const
inline

ex.: geometry_msgs/Pose -> "Pose"

Definition at line 117 of file ros_type.hpp.

bool RosIntrospection::ROSType::operator!= ( const ROSType other) const
inline

Definition at line 90 of file ros_type.hpp.

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

Definition at line 94 of file ros_type.hpp.

ROSType & RosIntrospection::ROSType::operator= ( const ROSType other)

Definition at line 68 of file ros_type.cpp.

ROSType & RosIntrospection::ROSType::operator= ( ROSType &&  other)

Definition at line 80 of file ros_type.cpp.

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

Definition at line 86 of file ros_type.hpp.

const absl::string_view & RosIntrospection::ROSType::pkgName ( ) const
inline

ex.: geometry_msgs/Pose -> "geometry_msgs"

Definition at line 122 of file ros_type.hpp.

void RosIntrospection::ROSType::setPkgName ( absl::string_view  new_pkg)

Definition at line 93 of file ros_type.cpp.

BuiltinType RosIntrospection::ROSType::typeID ( ) const
inline

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

Definition at line 137 of file ros_type.hpp.

int RosIntrospection::ROSType::typeSize ( ) const
inline

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

Definition at line 132 of file ros_type.hpp.

Member Data Documentation

std::string RosIntrospection::ROSType::_base_name
protected

Definition at line 103 of file ros_type.hpp.

size_t RosIntrospection::ROSType::_hash
protected

Definition at line 106 of file ros_type.hpp.

BuiltinType RosIntrospection::ROSType::_id
protected

Definition at line 102 of file ros_type.hpp.

absl::string_view RosIntrospection::ROSType::_msg_name
protected

Definition at line 104 of file ros_type.hpp.

absl::string_view RosIntrospection::ROSType::_pkg_name
protected

Definition at line 105 of file ros_type.hpp.


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


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Thu May 16 2019 02:39:10