6 #include <swarmros/EventHeader.h> 88 EventMessage(
const std::string& type,
const std::string& name,
const std::string& node,
const swarmio::data::Map& parameters)
89 :
Message(type), _parameters(parameters)
91 _eventHeader.name = name;
92 _eventHeader.node = node;
102 return _eventHeader.name;
112 _eventHeader.name = name;
122 return _eventHeader.node;
132 _eventHeader.node = node;
162 _parameters = parameters;
189 namespace message_traits
203 struct IsMessage<const swarmros::bridge::EventMessage> :
public IsMessage<const swarmros::introspection::Message> { };
211 struct MD5Sum<swarmros::bridge::EventMessage> :
public MD5Sum<swarmros::introspection::Message> { };
218 struct DataType<swarmros::bridge::EventMessage> :
public DataType<swarmros::introspection::Message> { };
228 namespace serialization
266 if (serializer !=
nullptr)
276 return headerLength + serializer->CalculateSerializedLength(message.
GetParameters(), serializer->HasHeader() ? 2 : 1, stack);
280 throw Exception(
"Trying to serialize EventMessage without serializer");
292 template<
typename Stream>
296 if (serializer !=
nullptr)
306 serializer->Serialize(dynamic_cast<ros::serialization::OStream&>(stream), message.
GetParameters(), serializer->HasHeader() ? 2 : 1, stack);
310 throw Exception(
"Trying to serialize EventMessage without serializer");
322 template<
typename Stream>
326 if (serializer !=
nullptr)
336 serializer->Deserialize(dynamic_cast<ros::serialization::IStream&>(stream), message.
GetMutableParameters(), serializer->HasHeader() ? 2 : 1, stack);
340 throw Exception(
"Trying to deserialize EventMessage without serializer");
boost::shared_ptr< EventMessage > Ptr
Pointer type.
bool HasHeader() const
Checks whether the message fits the requirements of a message with a header.
EventMessage()
Construct an empty EventMessage instance.
const Serializer & GetSerializer() const
Get the associated serializer.
const MessageSerializer * GetSerializer() const
Get the associated serializer.
static void write(Stream &stream, const swarmros::bridge::EventMessage &message)
Uses the message serializer to write the serialized representation of the underlying variant onto an ...
swarmio::data::Map & GetMutableParameters()
Get mutable event parameters.
void EnumerateFields(std::function< bool(unsigned, const Field &)> enumerator) const
Enumerate the fields of the message with a function.
EventMessage(const std::string &type, const std::string &name, const std::string &node, const swarmio::data::Map ¶meters)
Build an EventMessage instance from an event.
const EventHeader & GetEventHeader() const
Get event header.
EventHeader & GetMutableEventHeader()
Get mutable event header.
Serializer for full-fledged message types.
const swarmio::data::Map & GetParameters() const
Get event parameters.
Message is the base class for message types supported by the introspection library.
A Field represents an entry in a message reader that can read one of its fields.
void SetName(const std::string &name)
Set event name.
const std::string & GetName() const
Get event name.
EventMessage implements an interface with the ROS type system to send and receive events...
boost::shared_ptr< M > message
static void notify(const PreDeserializeParams< swarmros::bridge::EventMessage > ¶ms)
Before deserialization, sets the data type of an EventMessage instance.
EventHeader _eventHeader
Event header.
swarmio::data::Map _parameters
Parameters.
virtual const std::string & GetFullName() const
Get the fully qualified name for the type behind the serializer.
static bool IsEventSerializer(const introspection::MessageSerializer &serializer)
Checks whether a serializer has the correct layout.
void SetParameters(const swarmio::data::Map ¶meters)
Set event parameters.
boost::shared_ptr< EventMessage const > ConstPtr
Constant pointer type.
Message()
Construct an empty Message instance.
static uint32_t serializedLength(const swarmros::bridge::EventMessage &message)
Uses the message serializer to calculate the serialized size of the underlying variant.
boost::shared_ptr< std::map< std::string, std::string > > connection_header
static void read(Stream &stream, swarmros::bridge::EventMessage &message)
Uses the message serializer to read the serialized representation of the underlying variant from an o...
const std::string & GetNode() const
Get node UUID.
void SetNode(const std::string &node)
Set node UUID.