EventMessage.h
Go to the documentation of this file.
1 #pragma once
2 
6 #include <swarmros/EventHeader.h>
7 
8 namespace swarmros::bridge
9 {
16  {
17  private:
18 
23  EventHeader _eventHeader;
24 
29  swarmio::data::Map _parameters;
30 
31  public:
32 
39  static bool IsEventSerializer(const introspection::MessageSerializer& serializer)
40  {
41  bool hasHeader = false;
42  serializer.EnumerateFields([&hasHeader, &serializer](unsigned n, const introspection::Field& field) {
43  if (n == 0 && serializer.HasHeader())
44  {
45  // Skip this field
46  return true;
47  }
48  else if (field.GetSerializer().GetFullName() == "swarmros/EventHeader")
49  {
50  // We found it!
51  hasHeader = true;
52  return false;
53  }
54  else
55  {
56  // No point looking anymore
57  return false;
58  }
59  });
60  return hasHeader;
61  }
62 
68 
74 
80 
88  EventMessage(const std::string& type, const std::string& name, const std::string& node, const swarmio::data::Map& parameters)
89  : Message(type), _parameters(parameters)
90  {
91  _eventHeader.name = name;
92  _eventHeader.node = node;
93  }
94 
100  const std::string& GetName() const
101  {
102  return _eventHeader.name;
103  }
104 
110  void SetName(const std::string& name)
111  {
112  _eventHeader.name = name;
113  }
114 
120  const std::string& GetNode() const
121  {
122  return _eventHeader.node;
123  }
124 
130  void SetNode(const std::string& node)
131  {
132  _eventHeader.node = node;
133  }
134 
140  const swarmio::data::Map& GetParameters() const
141  {
142  return _parameters;
143  }
144 
150  swarmio::data::Map& GetMutableParameters()
151  {
152  return _parameters;
153  }
154 
160  void SetParameters(const swarmio::data::Map& parameters)
161  {
162  _parameters = parameters;
163  }
164 
170  const EventHeader& GetEventHeader() const
171  {
172  return _eventHeader;
173  }
174 
180  EventHeader& GetMutableEventHeader()
181  {
182  return _eventHeader;
183  }
184  };
185 }
186 
187 namespace ros
188 {
189  namespace message_traits
190  {
195  template<>
196  struct IsMessage<swarmros::bridge::EventMessage> : public IsMessage<swarmros::introspection::Message> { };
197 
202  template<>
203  struct IsMessage<const swarmros::bridge::EventMessage> : public IsMessage<const swarmros::introspection::Message> { };
204 
210  template<>
211  struct MD5Sum<swarmros::bridge::EventMessage> : public MD5Sum<swarmros::introspection::Message> { };
212 
217  template<>
218  struct DataType<swarmros::bridge::EventMessage> : public DataType<swarmros::introspection::Message> { };
219 
224  template<>
225  struct Definition<swarmros::bridge::EventMessage> : public Definition<swarmros::introspection::Message> { };
226  }
227 
228  namespace serialization
229  {
234  template<>
235  struct PreDeserialize<swarmros::bridge::EventMessage>
236  {
244  {
245  params.message->SetType((*params.connection_header)["type"]);
246  }
247  };
248 
253  template<>
254  struct Serializer<swarmros::bridge::EventMessage>
255  {
264  {
265  auto serializer = message.GetSerializer();
266  if (serializer != nullptr)
267  {
268  // Handle header
270 
271  // Handle event header
273 
274  // Handle contents
275  swarmros::introspection::RootFieldStack stack(serializer->GetFullName());
276  return headerLength + serializer->CalculateSerializedLength(message.GetParameters(), serializer->HasHeader() ? 2 : 1, stack);
277  }
278  else
279  {
280  throw Exception("Trying to serialize EventMessage without serializer");
281  }
282  }
283 
292  template<typename Stream>
293  inline static void write(Stream& stream, const swarmros::bridge::EventMessage& message)
294  {
295  auto serializer = message.GetSerializer();
296  if (serializer != nullptr)
297  {
298  // Handle header
300 
301  // Handle event header
303 
304  // Handle contents
305  swarmros::introspection::RootFieldStack stack(serializer->GetFullName());
306  serializer->Serialize(dynamic_cast<ros::serialization::OStream&>(stream), message.GetParameters(), serializer->HasHeader() ? 2 : 1, stack);
307  }
308  else
309  {
310  throw Exception("Trying to serialize EventMessage without serializer");
311  }
312  }
313 
322  template<typename Stream>
323  inline static void read(Stream& stream, swarmros::bridge::EventMessage& message)
324  {
325  auto serializer = message.GetSerializer();
326  if (serializer != nullptr)
327  {
328  // Handle header
330 
331  // Handle event header
333 
334  // Handle contents
335  swarmros::introspection::RootFieldStack stack(serializer->GetFullName());
336  serializer->Deserialize(dynamic_cast<ros::serialization::IStream&>(stream), message.GetMutableParameters(), serializer->HasHeader() ? 2 : 1, stack);
337  }
338  else
339  {
340  throw Exception("Trying to deserialize EventMessage without serializer");
341  }
342  }
343  };
344  }
345 }
boost::shared_ptr< EventMessage > Ptr
Pointer type.
Definition: EventMessage.h:73
bool HasHeader() const
Checks whether the message fits the requirements of a message with a header.
EventMessage()
Construct an empty EventMessage instance.
Definition: EventMessage.h:79
bool hasHeader()
const Serializer & GetSerializer() const
Get the associated serializer.
Definition: Field.h:58
const MessageSerializer * GetSerializer() const
Get the associated serializer.
Definition: Message.h:98
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 ...
Definition: EventMessage.h:293
swarmio::data::Map & GetMutableParameters()
Get mutable event parameters.
Definition: EventMessage.h:150
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 &parameters)
Build an EventMessage instance from an event.
Definition: EventMessage.h:88
const EventHeader & GetEventHeader() const
Get event header.
Definition: EventMessage.h:170
EventHeader & GetMutableEventHeader()
Get mutable event header.
Definition: EventMessage.h:180
Serializer for full-fledged message types.
const swarmio::data::Map & GetParameters() const
Get event parameters.
Definition: EventMessage.h:140
Message is the base class for message types supported by the introspection library.
Definition: Message.h:16
A Field represents an entry in a message reader that can read one of its fields.
Definition: Field.h:15
void SetName(const std::string &name)
Set event name.
Definition: EventMessage.h:110
const std::string & GetName() const
Get event name.
Definition: EventMessage.h:100
EventMessage implements an interface with the ROS type system to send and receive events...
Definition: EventMessage.h:15
static void notify(const PreDeserializeParams< swarmros::bridge::EventMessage > &params)
Before deserialization, sets the data type of an EventMessage instance.
Definition: EventMessage.h:243
EventHeader _eventHeader
Event header.
Definition: EventMessage.h:23
swarmio::data::Map _parameters
Parameters.
Definition: EventMessage.h:29
virtual const std::string & GetFullName() const
Get the fully qualified name for the type behind the serializer.
Definition: Serializer.h:77
static bool IsEventSerializer(const introspection::MessageSerializer &serializer)
Checks whether a serializer has the correct layout.
Definition: EventMessage.h:39
void SetParameters(const swarmio::data::Map &parameters)
Set event parameters.
Definition: EventMessage.h:160
boost::shared_ptr< EventMessage const > ConstPtr
Constant pointer type.
Definition: EventMessage.h:67
Message()
Construct an empty Message instance.
Definition: Message.h:45
static uint32_t serializedLength(const swarmros::bridge::EventMessage &message)
Uses the message serializer to calculate the serialized size of the underlying variant.
Definition: EventMessage.h:263
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...
Definition: EventMessage.h:323
const std::string & GetNode() const
Get node UUID.
Definition: EventMessage.h:120
void SetNode(const std::string &node)
Set node UUID.
Definition: EventMessage.h:130


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