#include <shape_shifter.h>
Public Types | |
typedef boost::shared_ptr < ShapeShifter const > | ConstPtr |
typedef boost::shared_ptr < ShapeShifter > | Ptr |
Public Member Functions | |
virtual ROS_DEPRECATED const std::string | __getDataType () const |
virtual ROS_DEPRECATED const std::string | __getMD5Sum () const |
virtual ROS_DEPRECATED const std::string | __getMessageDefinition () const |
ros::Publisher | advertise (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size_, bool latch=false) const |
virtual ROS_DEPRECATED uint8_t * | deserialize (uint8_t *readPtr) |
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. | |
void | morph (const std::string &md5sum, const std::string &datatype, const std::string &msg_def) |
template<typename Stream > | |
void | read (Stream &stream) |
ROS_DEPRECATED uint32_t | serializationLength () const |
virtual ROS_DEPRECATED uint8_t * | serialize (uint8_t *writePtr, uint32_t) const |
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 Member Functions | |
static ROS_DEPRECATED const std::string | __s_getDataType () |
static ROS_DEPRECATED const std::string | __s_getMD5Sum () |
static ROS_DEPRECATED const std::string | __s_getMessageDefinition () |
Static Public Attributes | |
static bool | uses_old_API_ = false |
Private Attributes | |
std::string | datatype |
std::string | md5 |
std::string | msg_def |
uint8_t * | msgBuf |
uint32_t | msgBufAlloc |
uint32_t | msgBufUsed |
bool | typed |
Definition at line 49 of file shape_shifter.h.
typedef boost::shared_ptr<ShapeShifter const> topic_tools::ShapeShifter::ConstPtr |
Definition at line 53 of file shape_shifter.h.
typedef boost::shared_ptr<ShapeShifter> topic_tools::ShapeShifter::Ptr |
Definition at line 52 of file shape_shifter.h.
ShapeShifter::ShapeShifter | ( | ) |
Definition at line 41 of file shape_shifter.cpp.
ShapeShifter::~ShapeShifter | ( | ) | [virtual] |
Definition at line 50 of file shape_shifter.cpp.
const std::string ShapeShifter::__getDataType | ( | ) | const [virtual] |
Definition at line 95 of file shape_shifter.cpp.
const std::string ShapeShifter::__getMD5Sum | ( | ) | const [virtual] |
Definition at line 101 of file shape_shifter.cpp.
const std::string ShapeShifter::__getMessageDefinition | ( | ) | const [virtual] |
Definition at line 107 of file shape_shifter.cpp.
const std::string ShapeShifter::__s_getDataType | ( | ) | [static] |
Definition at line 114 of file shape_shifter.cpp.
const std::string ShapeShifter::__s_getMD5Sum | ( | ) | [static] |
Definition at line 120 of file shape_shifter.cpp.
const std::string ShapeShifter::__s_getMessageDefinition | ( | ) | [static] |
Definition at line 126 of file shape_shifter.cpp.
ros::Publisher ShapeShifter::advertise | ( | ros::NodeHandle & | nh, | |
const std::string & | topic, | |||
uint32_t | queue_size_, | |||
bool | latch = false | |||
) | const |
Definition at line 79 of file shape_shifter.cpp.
uint8_t * ShapeShifter::deserialize | ( | uint8_t * | readPtr | ) | [virtual] |
Definition at line 145 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 [inline] |
Call to try instantiating as a particular type.
Definition at line 200 of file shape_shifter.h.
void ShapeShifter::morph | ( | const std::string & | md5sum, | |
const std::string & | datatype, | |||
const std::string & | msg_def | |||
) |
Definition at line 69 of file shape_shifter.cpp.
void topic_tools::ShapeShifter::read | ( | Stream & | stream | ) | [inline] |
Definition at line 229 of file shape_shifter.h.
ROS_DEPRECATED uint32_t topic_tools::ShapeShifter::serializationLength | ( | ) | const [inline] |
Definition at line 94 of file shape_shifter.h.
uint8_t * ShapeShifter::serialize | ( | uint8_t * | writePtr, | |
uint32_t | ||||
) | const [virtual] |
Definition at line 135 of file shape_shifter.cpp.
uint32_t ShapeShifter::size | ( | ) | const |
Return the size of the serialized message.
Definition at line 88 of file shape_shifter.cpp.
void topic_tools::ShapeShifter::write | ( | Stream & | stream | ) | const [inline] |
Write serialized message contents out to a stream.
Definition at line 223 of file shape_shifter.h.
std::string topic_tools::ShapeShifter::datatype [private] |
Definition at line 100 of file shape_shifter.h.
std::string topic_tools::ShapeShifter::md5 [private] |
Definition at line 100 of file shape_shifter.h.
std::string topic_tools::ShapeShifter::msg_def [private] |
Definition at line 100 of file shape_shifter.h.
uint8_t* topic_tools::ShapeShifter::msgBuf [private] |
Definition at line 103 of file shape_shifter.h.
uint32_t topic_tools::ShapeShifter::msgBufAlloc [private] |
Definition at line 105 of file shape_shifter.h.
uint32_t topic_tools::ShapeShifter::msgBufUsed [private] |
Definition at line 104 of file shape_shifter.h.
bool topic_tools::ShapeShifter::typed [private] |
Definition at line 101 of file shape_shifter.h.
bool ShapeShifter::uses_old_API_ = false [static] |
Definition at line 55 of file shape_shifter.h.