Public Types | Public Member Functions | Static Public Attributes | Private Attributes | List of all members
topic_tools::ShapeShifter Class Reference

#include <shape_shifter.h>

Public Types

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

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
 
std::vector< uint8_t > msgBuf
 
bool typed
 

Detailed Description

Definition at line 91 of file shape_shifter.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 95 of file shape_shifter.h.

◆ Ptr

Definition at line 94 of file shape_shifter.h.

Constructor & Destructor Documentation

◆ ShapeShifter()

ShapeShifter::ShapeShifter ( )

Definition at line 41 of file shape_shifter.cpp.

◆ ~ShapeShifter()

ShapeShifter::~ShapeShifter ( )
virtual

Definition at line 43 of file shape_shifter.cpp.

Member Function Documentation

◆ advertise()

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 65 of file shape_shifter.cpp.

◆ getDataType()

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

Definition at line 45 of file shape_shifter.cpp.

◆ getMD5Sum()

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

Definition at line 48 of file shape_shifter.cpp.

◆ getMessageDefinition()

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

Definition at line 51 of file shape_shifter.cpp.

◆ instantiate()

template<class M >
boost::shared_ptr< M > topic_tools::ShapeShifter::instantiate

Call to try instantiating as a particular type.

Definition at line 194 of file shape_shifter.h.

◆ morph()

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

Definition at line 54 of file shape_shifter.cpp.

◆ read()

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

Definition at line 223 of file shape_shifter.h.

◆ size()

uint32_t ShapeShifter::size ( ) const

Return the size of the serialized message.

Definition at line 74 of file shape_shifter.cpp.

◆ write()

template<typename Stream >
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.

Member Data Documentation

◆ datatype

std::string topic_tools::ShapeShifter::datatype
private

Definition at line 131 of file shape_shifter.h.

◆ latching

std::string topic_tools::ShapeShifter::latching
private

Definition at line 131 of file shape_shifter.h.

◆ md5

std::string topic_tools::ShapeShifter::md5
private

Definition at line 131 of file shape_shifter.h.

◆ msg_def

std::string topic_tools::ShapeShifter::msg_def
private

Definition at line 131 of file shape_shifter.h.

◆ msgBuf

std::vector<uint8_t> topic_tools::ShapeShifter::msgBuf
private

Definition at line 134 of file shape_shifter.h.

◆ typed

bool topic_tools::ShapeShifter::typed
private

Definition at line 132 of file shape_shifter.h.

◆ uses_old_API_

bool ShapeShifter::uses_old_API_ = false
static

Definition at line 97 of file shape_shifter.h.


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


topic_tools
Author(s): Morgan Quigley, Brian Gerkey, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:02:10