#include <shape_shifter.h>
Public Types | |
typedef boost::shared_ptr< ShapeShifter const > | ConstPtr |
typedef boost::shared_ptr< ShapeShifter > | Ptr |
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 Blob & | blob () 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... | |
ShapeShifter & | morph (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 |
Definition at line 37 of file shape_shifter.h.
typedef boost::shared_ptr< ShapeShifter const> blob::ShapeShifter::ConstPtr |
Definition at line 46 of file shape_shifter.h.
typedef boost::shared_ptr< ShapeShifter > blob::ShapeShifter::Ptr |
Definition at line 45 of file shape_shifter.h.
typedef ShapeShifter blob::ShapeShifter::Type |
Definition at line 39 of file shape_shifter.h.
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.
|
virtual |
Definition at line 42 of file shape_shifter.cpp.
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.
|
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.
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.
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.
void blob::ShapeShifter::write | ( | Stream & | stream | ) | const |
Write serialized message contents out to a stream.
Definition at line 193 of file shape_shifter.h.
boost::shared_ptr<std::map<std::string, std::string> > blob::ShapeShifter::__connection_header |
Definition at line 79 of file shape_shifter.h.
|
private |
Definition at line 83 of file shape_shifter.h.
|
private |
Definition at line 82 of file shape_shifter.h.
|
private |
Definition at line 82 of file shape_shifter.h.
|
private |
Definition at line 82 of file shape_shifter.h.
|
private |
Definition at line 82 of file shape_shifter.h.