Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
variant_topic_tools::MessageType Class Reference

Variant message type information. More...

#include <MessageType.h>

Public Member Functions

Publisher advertise (ros::NodeHandle &nodeHandle, const std::string &topic, size_t queueSize, bool latch=false, const ros::SubscriberStatusCallback &connectCallback=ros::SubscriberStatusCallback())
 Advertise this message type. More...
 
void clear ()
 Clear the message type. More...
 
const std::string & getDataType () const
 Retrieve the data type of the message. More...
 
const std::string & getDefinition () const
 Retrieve the message definition. More...
 
const std::string & getMD5Sum () const
 Retrieve the MD5 sum of the message. More...
 
bool isValid () const
 True, if this message type is valid. More...
 
void load (const std::string &messageDataType)
 Attempt to load the message type corresponding to the specified message data type. More...
 
 MessageType (const std::string &dataType=std::string(), const std::string &md5Sum="*", const std::string &definition=std::string())
 Default constructor. More...
 
 MessageType (const MessageDataType &dataType)
 Constructor (overloaded version accepting a message data type) More...
 
 MessageType (const MessageType &src)
 Copy constructor. More...
 
bool operator!= (const MessageType &type) const
 True, if this message type does not equal another message type. More...
 
bool operator== (const MessageType &type) const
 True, if this message type equals another message type. More...
 
void setDataType (const std::string &dataType)
 Set the data type of the message. More...
 
void setDefinition (const std::string &definition)
 Set the message definition. More...
 
void setMD5Sum (const std::string &md5Sum)
 Set the MD5 sum of the message. More...
 
Subscriber subscribe (ros::NodeHandle &nodeHandle, const std::string &topic, size_t queueSize, const SubscriberCallback &callback)
 Subscribe to this message type. More...
 
void write (std::ostream &stream) const
 Write the message type to a stream. More...
 
 ~MessageType ()
 Destructor. More...
 

Static Public Member Functions

template<typename T >
static MessageType create ()
 Create a message type. More...
 

Protected Attributes

std::string dataType
 The data type of this message. More...
 
std::string definition
 The definition of this message. More...
 
std::string md5Sum
 The MD5 sum of this message. More...
 

Detailed Description

Variant message type information.

Definition at line 33 of file MessageType.h.

Constructor & Destructor Documentation

variant_topic_tools::MessageType::MessageType ( const std::string &  dataType = std::string(),
const std::string &  md5Sum = "*",
const std::string &  definition = std::string() 
)

Default constructor.

Definition at line 44 of file MessageType.cpp.

variant_topic_tools::MessageType::MessageType ( const MessageDataType dataType)

Constructor (overloaded version accepting a message data type)

Definition at line 51 of file MessageType.cpp.

variant_topic_tools::MessageType::MessageType ( const MessageType src)

Copy constructor.

Definition at line 57 of file MessageType.cpp.

variant_topic_tools::MessageType::~MessageType ( )

Destructor.

Definition at line 63 of file MessageType.cpp.

Member Function Documentation

Publisher variant_topic_tools::MessageType::advertise ( ros::NodeHandle nodeHandle,
const std::string &  topic,
size_t  queueSize,
bool  latch = false,
const ros::SubscriberStatusCallback connectCallback = ros::SubscriberStatusCallback() 
)

Advertise this message type.

Definition at line 219 of file MessageType.cpp.

void variant_topic_tools::MessageType::clear ( )

Clear the message type.

Definition at line 209 of file MessageType.cpp.

template<typename T >
static MessageType variant_topic_tools::MessageType::create ( )
static

Create a message type.

const std::string & variant_topic_tools::MessageType::getDataType ( ) const

Retrieve the data type of the message.

Definition at line 74 of file MessageType.cpp.

const std::string & variant_topic_tools::MessageType::getDefinition ( ) const

Retrieve the message definition.

Definition at line 90 of file MessageType.cpp.

const std::string & variant_topic_tools::MessageType::getMD5Sum ( ) const

Retrieve the MD5 sum of the message.

Definition at line 82 of file MessageType.cpp.

bool variant_topic_tools::MessageType::isValid ( ) const

True, if this message type is valid.

Definition at line 94 of file MessageType.cpp.

void variant_topic_tools::MessageType::load ( const std::string &  messageDataType)

Attempt to load the message type corresponding to the specified message data type.

Definition at line 103 of file MessageType.cpp.

bool variant_topic_tools::MessageType::operator!= ( const MessageType type) const

True, if this message type does not equal another message type.

Definition at line 250 of file MessageType.cpp.

bool variant_topic_tools::MessageType::operator== ( const MessageType type) const

True, if this message type equals another message type.

Definition at line 246 of file MessageType.cpp.

void variant_topic_tools::MessageType::setDataType ( const std::string &  dataType)

Set the data type of the message.

Definition at line 70 of file MessageType.cpp.

void variant_topic_tools::MessageType::setDefinition ( const std::string &  definition)

Set the message definition.

Definition at line 86 of file MessageType.cpp.

void variant_topic_tools::MessageType::setMD5Sum ( const std::string &  md5Sum)

Set the MD5 sum of the message.

Definition at line 78 of file MessageType.cpp.

Subscriber variant_topic_tools::MessageType::subscribe ( ros::NodeHandle nodeHandle,
const std::string &  topic,
size_t  queueSize,
const SubscriberCallback callback 
)

Subscribe to this message type.

Definition at line 231 of file MessageType.cpp.

void variant_topic_tools::MessageType::write ( std::ostream &  stream) const

Write the message type to a stream.

Definition at line 215 of file MessageType.cpp.

Member Data Documentation

std::string variant_topic_tools::MessageType::dataType
protected

The data type of this message.

Definition at line 121 of file MessageType.h.

std::string variant_topic_tools::MessageType::definition
protected

The definition of this message.

Definition at line 129 of file MessageType.h.

std::string variant_topic_tools::MessageType::md5Sum
protected

The MD5 sum of this message.

Definition at line 125 of file MessageType.h.


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


variant_topic_tools
Author(s): Ralf Kaestner
autogenerated on Sat Jan 9 2021 03:56:50