Public Types | Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
swarmros::bridge::EventMessage Class Reference

EventMessage implements an interface with the ROS type system to send and receive events. More...

#include <EventMessage.h>

Inheritance diagram for swarmros::bridge::EventMessage:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< EventMessage const > ConstPtr
 Constant pointer type. More...
 
typedef boost::shared_ptr< EventMessagePtr
 Pointer type. More...
 

Public Member Functions

 EventMessage ()
 Construct an empty EventMessage instance. More...
 
 EventMessage (const std::string &type, const std::string &name, const std::string &node, const swarmio::data::Map &parameters)
 Build an EventMessage instance from an event. More...
 
const EventHeader & GetEventHeader () const
 Get event header. More...
 
EventHeader & GetMutableEventHeader ()
 Get mutable event header. More...
 
swarmio::data::Map & GetMutableParameters ()
 Get mutable event parameters. More...
 
const std::string & GetName () const
 Get event name. More...
 
const std::string & GetNode () const
 Get node UUID. More...
 
const swarmio::data::Map & GetParameters () const
 Get event parameters. More...
 
void SetName (const std::string &name)
 Set event name. More...
 
void SetNode (const std::string &node)
 Set node UUID. More...
 
void SetParameters (const swarmio::data::Map &parameters)
 Set event parameters. More...
 
- Public Member Functions inherited from swarmros::introspection::Message
void EraseType ()
 Erase type information from message. More...
 
const std_msgs::HeaderGetHeader () const
 Get a reference to the header. More...
 
std_msgs::HeaderGetMutableHeader ()
 Get a mutable reference to the header. More...
 
const MessageSerializerGetSerializer () 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...
 

Static Public Member Functions

static bool IsEventSerializer (const introspection::MessageSerializer &serializer)
 Checks whether a serializer has the correct layout. More...
 

Private Attributes

EventHeader _eventHeader
 Event header. More...
 
swarmio::data::Map _parameters
 Parameters. 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...
 

Detailed Description

EventMessage implements an interface with the ROS type system to send and receive events.

Definition at line 15 of file EventMessage.h.

Member Typedef Documentation

Constant pointer type.

Definition at line 67 of file EventMessage.h.

Pointer type.

Definition at line 73 of file EventMessage.h.

Constructor & Destructor Documentation

swarmros::bridge::EventMessage::EventMessage ( )
inline

Construct an empty EventMessage instance.

Definition at line 79 of file EventMessage.h.

swarmros::bridge::EventMessage::EventMessage ( const std::string &  type,
const std::string &  name,
const std::string &  node,
const swarmio::data::Map &  parameters 
)
inline

Build an EventMessage instance from an event.

Parameters
typeROS type
nodeNode UUID
eventEvent

Definition at line 88 of file EventMessage.h.

Member Function Documentation

const EventHeader& swarmros::bridge::EventMessage::GetEventHeader ( ) const
inline

Get event header.

Returns
const EventHeader&

Definition at line 170 of file EventMessage.h.

EventHeader& swarmros::bridge::EventMessage::GetMutableEventHeader ( )
inline

Get mutable event header.

Returns
EventHeader&

Definition at line 180 of file EventMessage.h.

swarmio::data::Map& swarmros::bridge::EventMessage::GetMutableParameters ( )
inline

Get mutable event parameters.

Returns
const swarmio::data::event::Notification&

Definition at line 150 of file EventMessage.h.

const std::string& swarmros::bridge::EventMessage::GetName ( ) const
inline

Get event name.

Returns
const std::string&

Definition at line 100 of file EventMessage.h.

const std::string& swarmros::bridge::EventMessage::GetNode ( ) const
inline

Get node UUID.

Returns
const std::string&

Definition at line 120 of file EventMessage.h.

const swarmio::data::Map& swarmros::bridge::EventMessage::GetParameters ( ) const
inline

Get event parameters.

Returns
const swarmio::data::event::Notification&

Definition at line 140 of file EventMessage.h.

static bool swarmros::bridge::EventMessage::IsEventSerializer ( const introspection::MessageSerializer serializer)
inlinestatic

Checks whether a serializer has the correct layout.

Parameters
serializerSerializer
Returns
True if the serializer can be used to serialize events.

Definition at line 39 of file EventMessage.h.

void swarmros::bridge::EventMessage::SetName ( const std::string &  name)
inline

Set event name.

Parameters
nameName

Definition at line 110 of file EventMessage.h.

void swarmros::bridge::EventMessage::SetNode ( const std::string &  node)
inline

Set node UUID.

Parameters
nodeNode

Definition at line 130 of file EventMessage.h.

void swarmros::bridge::EventMessage::SetParameters ( const swarmio::data::Map &  parameters)
inline

Set event parameters.

Parameters
eventEvent

Definition at line 160 of file EventMessage.h.

Member Data Documentation

EventHeader swarmros::bridge::EventMessage::_eventHeader
private

Event header.

Definition at line 23 of file EventMessage.h.

swarmio::data::Map swarmros::bridge::EventMessage::_parameters
private

Parameters.

Definition at line 29 of file EventMessage.h.


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


swarmros
Author(s):
autogenerated on Fri Apr 3 2020 03:42:48