Public Types | Public Member Functions | Public Attributes | Private Attributes | List of all members
blob::ShapeShifter Struct Reference

#include <shape_shifter.h>

Public Types

typedef boost::shared_ptr< ShapeShifter const > ConstPtr
 
typedef boost::shared_ptr< ShapeShifterPtr
 
typedef ShapeShifter Type
 

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
 
const Blobblob () const
 
std::string const & getDataType () const
 
std::string const & getMD5Sum () const
 
std::string const & getMessageDefinition () const
 
template<class M >
boost::shared_ptr< M > instantiate () const
 Call to try instantiating as a particular type. More...
 
ShapeShiftermorph (const std::string &md5sum, const std::string &datatype, const std::string &msg_def=std::string(), const std::string &latching=std::string())
 
template<typename Stream >
void read (Stream &stream)
 
 ShapeShifter ()
 
 ShapeShifter (const Blob &blob)
 
uint32_t size () const
 Return the size of the serialized message. More...
 
template<typename Stream >
void write (Stream &stream) const
 Write serialized message contents out to a stream. More...
 
virtual ~ShapeShifter ()
 

Public Attributes

boost::shared_ptr< std::map< std::string, std::string > > __connection_header
 

Private Attributes

Blob blob_
 
std::string datatype
 
std::string latching
 
std::string md5
 
std::string msg_def
 

Detailed Description

Definition at line 37 of file shape_shifter.h.

Member Typedef Documentation

Definition at line 46 of file shape_shifter.h.

Definition at line 45 of file shape_shifter.h.

Definition at line 39 of file shape_shifter.h.

Constructor & Destructor Documentation

blob::ShapeShifter::ShapeShifter ( )

Definition at line 33 of file shape_shifter.cpp.

blob::ShapeShifter::ShapeShifter ( const Blob blob)

Definition at line 37 of file shape_shifter.cpp.

blob::ShapeShifter::~ShapeShifter ( )
virtual

Definition at line 42 of file shape_shifter.cpp.

Member Function Documentation

ros::Publisher blob::ShapeShifter::advertise ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queue_size_,
bool  latch = false,
const ros::SubscriberStatusCallback connect_cb = ros::SubscriberStatusCallback() 
) const

Definition at line 62 of file shape_shifter.cpp.

const Blob& blob::ShapeShifter::blob ( ) const
inline

Definition at line 74 of file shape_shifter.h.

std::string const & blob::ShapeShifter::getDataType ( ) const

Definition at line 47 of file shape_shifter.cpp.

std::string const & blob::ShapeShifter::getMD5Sum ( ) const

Definition at line 48 of file shape_shifter.cpp.

std::string const & blob::ShapeShifter::getMessageDefinition ( ) const

Definition at line 49 of file shape_shifter.cpp.

template<class M >
boost::shared_ptr< M > blob::ShapeShifter::instantiate ( ) const

Call to try instantiating as a particular type.

Definition at line 187 of file shape_shifter.h.

ShapeShifter & blob::ShapeShifter::morph ( const std::string &  md5sum,
const std::string &  datatype,
const std::string &  msg_def = std::string(),
const std::string &  latching = std::string() 
)

Definition at line 51 of file shape_shifter.cpp.

template<typename Stream >
void blob::ShapeShifter::read ( Stream &  stream)

Definition at line 199 of file shape_shifter.h.

uint32_t blob::ShapeShifter::size ( ) const

Return the size of the serialized message.

Definition at line 71 of file shape_shifter.cpp.

template<typename Stream >
void blob::ShapeShifter::write ( Stream &  stream) const

Write serialized message contents out to a stream.

Definition at line 193 of file shape_shifter.h.

Member Data Documentation

boost::shared_ptr<std::map<std::string, std::string> > blob::ShapeShifter::__connection_header

Definition at line 79 of file shape_shifter.h.

Blob blob::ShapeShifter::blob_
private

Definition at line 83 of file shape_shifter.h.

std::string blob::ShapeShifter::datatype
private

Definition at line 82 of file shape_shifter.h.

std::string blob::ShapeShifter::latching
private

Definition at line 82 of file shape_shifter.h.

std::string blob::ShapeShifter::md5
private

Definition at line 82 of file shape_shifter.h.

std::string blob::ShapeShifter::msg_def
private

Definition at line 82 of file shape_shifter.h.


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


blob
Author(s): Johannes Meyer
autogenerated on Sat Jul 27 2019 03:35:24