54 :
Message(type), _value(value) { }
81 void SetValue(
const swarmio::data::Variant& value)
90 namespace message_traits
104 struct IsMessage<const swarmros::introspection::VariantMessage> :
public IsMessage<const swarmros::introspection::Message> { };
112 struct MD5Sum<swarmros::introspection::VariantMessage> :
public MD5Sum<swarmros::introspection::Message> { };
119 struct DataType<swarmros::introspection::VariantMessage> :
public DataType<swarmros::introspection::Message> { };
126 struct Definition<swarmros::introspection::VariantMessage> :
public Definition<swarmros::introspection::Message> { };
129 namespace serialization
167 if (serializer !=
nullptr)
174 return headerLength + serializer->CalculateSerializedLength(message.
GetValue(), serializer->HasHeader() ? 1 : 0, stack);
178 throw Exception(
"Trying to serialize VariantMessage without serializer");
190 template<
typename Stream>
194 if (serializer !=
nullptr)
201 serializer->Serialize(dynamic_cast<ros::serialization::OStream&>(stream), message.
GetValue(), serializer->HasHeader() ? 1 : 0, stack);
205 throw Exception(
"Trying to serialize VariantMessage without serializer");
217 template<
typename Stream>
221 if (serializer !=
nullptr)
228 message.
SetValue(serializer->Deserialize(dynamic_cast<ros::serialization::IStream&>(stream), serializer->HasHeader() ? 1 : 0, stack));
232 throw Exception(
"Trying to deserialize VariantMessage without serializer");
boost::shared_ptr< VariantMessage const > ConstPtr
Constant pointer type.
const MessageSerializer * GetSerializer() const
Get the associated serializer.
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.
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< M > message
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 > ¶ms)
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...