Public Types | Public Member Functions | Static Public Attributes | Private Attributes
RosIntrospection::ShapeShifter Class Reference

The ShapeShifter class is a type erased container for ROS Messages. It can be used also to create generic publishers and subscribers. More...

#include <shape_shifter.hpp>

List of all members.

Public Types

typedef boost::shared_ptr
< ShapeShifter const > 
ConstPtr
typedef boost::shared_ptr
< ShapeShifter
Ptr

Public Member Functions

ros::Publisher advertise (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback()) const
template<typename Message >
void direct_read (const Message &msg, bool morph)
 ! Directly serialize the contentof a message into this ShapeShifter.
std::string const & getDataType () const
std::string const & getMD5Sum () const
std::string const & getMessageDefinition () const
template<class M >
void instantiate (M &destination) const
 Call to try instantiating as a particular type.
void morph (const std::string &md5sum, const std::string &datatype_, const std::string &msg_def_)
const uint8_t * raw_data () const
template<typename Stream >
void read (Stream &stream)
 ShapeShifter ()
uint32_t size () const
 Return the size of the serialized message.
template<typename Stream >
void write (Stream &stream) const
 Write serialized message contents out to a stream.
virtual ~ShapeShifter ()

Static Public Attributes

static bool uses_old_API_

Private Attributes

boost::flyweight< std::string > datatype_
boost::flyweight< std::string > md5_
boost::flyweight< std::string > msg_def_
std::vector< uint8_t > msgBuf_
bool typed_

Detailed Description

The ShapeShifter class is a type erased container for ROS Messages. It can be used also to create generic publishers and subscribers.

Definition at line 54 of file shape_shifter.hpp.


Member Typedef Documentation

typedef boost::shared_ptr<ShapeShifter const> RosIntrospection::ShapeShifter::ConstPtr

Definition at line 58 of file shape_shifter.hpp.

Definition at line 57 of file shape_shifter.hpp.


Constructor & Destructor Documentation

Definition at line 254 of file shape_shifter.hpp.

Definition at line 261 of file shape_shifter.hpp.


Member Function Documentation

ros::Publisher RosIntrospection::ShapeShifter::advertise ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queue_size,
bool  latch = false,
const ros::SubscriberStatusCallback connect_cb = ros::SubscriberStatusCallback() 
) const [inline]

Definition at line 285 of file shape_shifter.hpp.

template<typename Message >
void RosIntrospection::ShapeShifter::direct_read ( const Message &  msg,
bool  morph 
) [inline]

! Directly serialize the contentof a message into this ShapeShifter.

Definition at line 235 of file shape_shifter.hpp.

std::string const & RosIntrospection::ShapeShifter::getDataType ( ) const [inline]

Definition at line 267 of file shape_shifter.hpp.

std::string const & RosIntrospection::ShapeShifter::getMD5Sum ( ) const [inline]

Definition at line 270 of file shape_shifter.hpp.

std::string const & RosIntrospection::ShapeShifter::getMessageDefinition ( ) const [inline]

Definition at line 273 of file shape_shifter.hpp.

template<class M >
void RosIntrospection::ShapeShifter::instantiate ( M &  destination) const [inline]

Call to try instantiating as a particular type.

Definition at line 194 of file shape_shifter.hpp.

void RosIntrospection::ShapeShifter::morph ( const std::string &  md5sum,
const std::string &  datatype_,
const std::string &  msg_def_ 
) [inline]

Definition at line 276 of file shape_shifter.hpp.

const uint8_t * RosIntrospection::ShapeShifter::raw_data ( ) const [inline]

Definition at line 216 of file shape_shifter.hpp.

template<typename Stream >
void RosIntrospection::ShapeShifter::read ( Stream &  stream) [inline]

Definition at line 226 of file shape_shifter.hpp.

uint32_t RosIntrospection::ShapeShifter::size ( ) const [inline]

Return the size of the serialized message.

Definition at line 220 of file shape_shifter.hpp.

template<typename Stream >
void RosIntrospection::ShapeShifter::write ( Stream &  stream) const [inline]

Write serialized message contents out to a stream.

Definition at line 211 of file shape_shifter.hpp.


Member Data Documentation

boost::flyweight<std::string> RosIntrospection::ShapeShifter::datatype_ [private]

Definition at line 101 of file shape_shifter.hpp.

boost::flyweight<std::string> RosIntrospection::ShapeShifter::md5_ [private]

Definition at line 100 of file shape_shifter.hpp.

boost::flyweight<std::string> RosIntrospection::ShapeShifter::msg_def_ [private]

Definition at line 102 of file shape_shifter.hpp.

std::vector<uint8_t> RosIntrospection::ShapeShifter::msgBuf_ [mutable, private]

Definition at line 105 of file shape_shifter.hpp.

Definition at line 103 of file shape_shifter.hpp.

Definition at line 60 of file shape_shifter.hpp.


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


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Tue May 14 2019 02:49:42