VariantMessage.h
Go to the documentation of this file.
1 #pragma once
2 
6 #include <swarmio/Exception.h>
7 #include <ros/ros.h>
8 #include <ros/message_traits.h>
9 
10 namespace swarmros::introspection
11 {
17  class VariantMessage : public Message
18  {
19  private:
20 
25  swarmio::data::Variant _value;
26 
27  public:
28 
34 
40 
46 
53  VariantMessage(const std::string& type, const swarmio::data::Variant& value)
54  : Message(type), _value(value) { }
55 
61  const swarmio::data::Variant& GetValue() const
62  {
63  return _value;
64  }
65 
71  swarmio::data::Variant& GetMutableValue()
72  {
73  return _value;
74  }
75 
81  void SetValue(const swarmio::data::Variant& value)
82  {
83  _value = value;
84  }
85  };
86 }
87 
88 namespace ros
89 {
90  namespace message_traits
91  {
96  template<>
97  struct IsMessage<swarmros::introspection::VariantMessage> : public IsMessage<swarmros::introspection::Message> { };
98 
103  template<>
104  struct IsMessage<const swarmros::introspection::VariantMessage> : public IsMessage<const swarmros::introspection::Message> { };
105 
111  template<>
112  struct MD5Sum<swarmros::introspection::VariantMessage> : public MD5Sum<swarmros::introspection::Message> { };
113 
118  template<>
119  struct DataType<swarmros::introspection::VariantMessage> : public DataType<swarmros::introspection::Message> { };
120 
125  template<>
126  struct Definition<swarmros::introspection::VariantMessage> : public Definition<swarmros::introspection::Message> { };
127  }
128 
129  namespace serialization
130  {
135  template<>
136  struct PreDeserialize<swarmros::introspection::VariantMessage>
137  {
145  {
146  params.message->SetType((*params.connection_header)["type"]);
147  }
148  };
149 
154  template<>
155  struct Serializer<swarmros::introspection::VariantMessage>
156  {
165  {
166  auto serializer = message.GetSerializer();
167  if (serializer != nullptr)
168  {
169  // Handle header
171 
172  // Handle contents
173  swarmros::introspection::RootFieldStack stack(serializer->GetFullName());
174  return headerLength + serializer->CalculateSerializedLength(message.GetValue(), serializer->HasHeader() ? 1 : 0, stack);
175  }
176  else
177  {
178  throw Exception("Trying to serialize VariantMessage without serializer");
179  }
180  }
181 
190  template<typename Stream>
191  inline static void write(Stream& stream, const swarmros::introspection::VariantMessage& message)
192  {
193  auto serializer = message.GetSerializer();
194  if (serializer != nullptr)
195  {
196  // Handle header
198 
199  // Handle contents
200  swarmros::introspection::RootFieldStack stack(serializer->GetFullName());
201  serializer->Serialize(dynamic_cast<ros::serialization::OStream&>(stream), message.GetValue(), serializer->HasHeader() ? 1 : 0, stack);
202  }
203  else
204  {
205  throw Exception("Trying to serialize VariantMessage without serializer");
206  }
207  }
208 
217  template<typename Stream>
219  {
220  auto serializer = message.GetSerializer();
221  if (serializer != nullptr)
222  {
223  // Handle header
225 
226  // Handle contents
227  swarmros::introspection::RootFieldStack stack(serializer->GetFullName());
228  message.SetValue(serializer->Deserialize(dynamic_cast<ros::serialization::IStream&>(stream), serializer->HasHeader() ? 1 : 0, stack));
229  }
230  else
231  {
232  throw Exception("Trying to deserialize VariantMessage without serializer");
233  }
234  }
235  };
236  }
237 }
boost::shared_ptr< VariantMessage const > ConstPtr
Constant pointer type.
const MessageSerializer * GetSerializer() const
Get the associated serializer.
Definition: Message.h:98
const swarmio::data::Variant & GetValue() const
Get value.
void SetValue(const swarmio::data::Variant &value)
Set value.
static void read(Stream &stream, swarmros::introspection::VariantMessage &message)
Uses the message serializer to read the serialized representation of the underlying variant from an o...
static uint32_t serializedLength(const swarmros::introspection::VariantMessage &message)
Uses the message serializer to calculate the serialized size of the underlying variant.
swarmio::data::Variant _value
Current value.
Message is the base class for message types supported by the introspection library.
Definition: Message.h:16
swarmio::data::Variant & GetMutableValue()
Get mutable value.
static void write(Stream &stream, const swarmros::introspection::VariantMessage &message)
Uses the message serializer to write the serialized representation of the underlying variant onto an ...
boost::shared_ptr< VariantMessage > Ptr
Pointer type.
VariantMessage(const std::string &type, const swarmio::data::Variant &value)
Build an VariantMessage instance from a Variant.
static void notify(const PreDeserializeParams< swarmros::introspection::VariantMessage > &params)
Before deserialization, sets the data type of an VariantMessage instance.
boost::shared_ptr< std::map< std::string, std::string > > connection_header
VariantMessage()
Construct an empty VariantMessage instance.
VariantMessage implements an interface with the ROS type system to send and receive messages of any k...


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