#include <shape_shifter.h>
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 |
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... | |
void | morph (const std::string &md5sum, const std::string &datatype, const std::string &msg_def, const std::string &latching) |
template<typename Stream > | |
void | read (Stream &stream) |
ShapeShifter () | |
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 () |
Static Public Attributes | |
static bool | uses_old_API_ = false |
Private Attributes | |
std::string | datatype |
std::string | latching |
std::string | md5 |
std::string | msg_def |
uint8_t * | msgBuf |
uint32_t | msgBufAlloc |
uint32_t | msgBufUsed |
bool | typed |
Definition at line 59 of file shape_shifter.h.
typedef boost::shared_ptr<ShapeShifter const> topic_tools::ShapeShifter::ConstPtr |
Definition at line 63 of file shape_shifter.h.
Definition at line 62 of file shape_shifter.h.
ShapeShifter::ShapeShifter | ( | ) |
Definition at line 41 of file shape_shifter.cpp.
|
virtual |
Definition at line 50 of file shape_shifter.cpp.
ros::Publisher 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 80 of file shape_shifter.cpp.
std::string const & ShapeShifter::getDataType | ( | ) | const |
Definition at line 60 of file shape_shifter.cpp.
std::string const & ShapeShifter::getMD5Sum | ( | ) | const |
Definition at line 63 of file shape_shifter.cpp.
std::string const & ShapeShifter::getMessageDefinition | ( | ) | const |
Definition at line 66 of file shape_shifter.cpp.
boost::shared_ptr< M > topic_tools::ShapeShifter::instantiate | ( | ) | const |
Call to try instantiating as a particular type.
Definition at line 197 of file shape_shifter.h.
void ShapeShifter::morph | ( | const std::string & | md5sum, |
const std::string & | datatype, | ||
const std::string & | msg_def, | ||
const std::string & | latching | ||
) |
Definition at line 69 of file shape_shifter.cpp.
void topic_tools::ShapeShifter::read | ( | Stream & | stream | ) |
Definition at line 223 of file shape_shifter.h.
uint32_t ShapeShifter::size | ( | ) | const |
Return the size of the serialized message.
Definition at line 89 of file shape_shifter.cpp.
void topic_tools::ShapeShifter::write | ( | Stream & | stream | ) | const |
Write serialized message contents out to a stream.
Definition at line 217 of file shape_shifter.h.
|
private |
Definition at line 99 of file shape_shifter.h.
|
private |
Definition at line 99 of file shape_shifter.h.
|
private |
Definition at line 99 of file shape_shifter.h.
|
private |
Definition at line 99 of file shape_shifter.h.
|
private |
Definition at line 102 of file shape_shifter.h.
|
private |
Definition at line 104 of file shape_shifter.h.
|
private |
Definition at line 103 of file shape_shifter.h.
|
private |
Definition at line 100 of file shape_shifter.h.
|
static |
Definition at line 65 of file shape_shifter.h.