VariantMessage implements an interface with the ROS type system to send and receive messages of any known type. More...
#include <VariantMessage.h>
Public Types | |
typedef boost::shared_ptr< VariantMessage const > | ConstPtr |
Constant pointer type. More... | |
typedef boost::shared_ptr< VariantMessage > | Ptr |
Pointer type. More... | |
Public Member Functions | |
swarmio::data::Variant & | GetMutableValue () |
Get mutable value. More... | |
const swarmio::data::Variant & | GetValue () const |
Get value. More... | |
void | SetValue (const swarmio::data::Variant &value) |
Set value. More... | |
VariantMessage () | |
Construct an empty VariantMessage instance. More... | |
VariantMessage (const std::string &type, const swarmio::data::Variant &value) | |
Build an VariantMessage instance from a Variant. More... | |
Public Member Functions inherited from swarmros::introspection::Message | |
void | EraseType () |
Erase type information from message. More... | |
const std_msgs::Header & | GetHeader () const |
Get a reference to the header. More... | |
std_msgs::Header & | GetMutableHeader () |
Get a mutable reference to the header. More... | |
const MessageSerializer * | GetSerializer () const |
Get the associated serializer. More... | |
const std::string & | GetType () const |
Get the fully qualified type of the message. More... | |
void | SetType (const std::string &type) |
Set the type of the object and fetch its serializer. More... | |
Private Attributes | |
swarmio::data::Variant | _value |
Current value. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from swarmros::introspection::Message | |
Message () | |
Construct an empty Message instance. More... | |
Message (const std::string &type) | |
Build an Message instance for a specific type. More... | |
VariantMessage implements an interface with the ROS type system to send and receive messages of any known type.
Definition at line 17 of file VariantMessage.h.
Constant pointer type.
Definition at line 33 of file VariantMessage.h.
Pointer type.
Definition at line 39 of file VariantMessage.h.
|
inline |
Construct an empty VariantMessage instance.
Definition at line 45 of file VariantMessage.h.
|
inline |
Build an VariantMessage instance from a Variant.
type | ROS type |
value | Variant value |
Definition at line 53 of file VariantMessage.h.
|
inline |
Get mutable value.
Definition at line 71 of file VariantMessage.h.
|
inline |
|
inline |
|
private |
Current value.
Definition at line 25 of file VariantMessage.h.