Message.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright (C) 2014 by Ralf Kaestner *
3  * ralf.kaestner@gmail.com *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the Lesser GNU General Public License as published by*
7  * the Free Software Foundation; either version 3 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * Lesser GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the Lesser GNU General Public License *
16  * along with this program. If not, see <http://www.gnu.org/licenses/>. *
17  ******************************************************************************/
18 
24 
25 namespace variant_topic_tools {
26 
27 /*****************************************************************************/
28 /* Constructors and Destructor */
29 /*****************************************************************************/
30 
32 }
33 
35  header(src.header),
36  type(src.type),
37  data(src.data) {
38 }
39 
41 }
42 
43 /*****************************************************************************/
44 /* Accessors */
45 /*****************************************************************************/
46 
48  this->header = header;
49 
50  type.setMD5Sum(header["md5sum"]);
51  type.setDataType(header["type"]);
52  type.setDefinition(header["message_definition"]);
53 }
54 
56  return header;
57 }
58 
60  this->type = type;
61 
62  header["md5sum"] = type.getMD5Sum();
63  header["type"] = type.getDataType();
64  header["message_definition"] = type.getDefinition();
65 }
66 
67 const MessageType& Message::getType() const {
68  return type;
69 }
70 
71 void Message::setData(const std::vector<uint8_t>& data) {
72  this->data = data;
73 }
74 
75 std::vector<uint8_t>& Message::getData() {
76  return data;
77 }
78 
79 const std::vector<uint8_t>& Message::getData() const {
80  return data;
81 }
82 
83 void Message::setSize(size_t size) {
84  data.resize(size);
85 }
86 
87 size_t Message::getSize() const {
88  return data.size();
89 }
90 
91 /*****************************************************************************/
92 /* Methods */
93 /*****************************************************************************/
94 
95 void Message::serialize(const MessageVariant& variant) {
96  MessageDataType dataType = variant.getType();
97  MessageType type(dataType.getIdentifier(), dataType.getMD5Sum(),
98  dataType.getDefinition());
99 
100  setType(type);
101  MessageSerializer serializer = variant.createSerializer();
102  data.resize(serializer.getSerializedLength(variant));
103  ros::serialization::OStream stream(const_cast<uint8_t*>(
104  data.data()), data.size());
105 
106  serializer.serialize(stream, variant);
107 }
108 
109 void Message::deserialize(MessageVariant& variant) const {
110  DataTypeRegistry registry;
111  DataType dataType = registry.getDataType(type.getDataType());
112 
113  if (!dataType) {
115  dataType = definition.getMessageDataType();
116  }
117 
118  variant = dataType.createVariant();
119  MessageSerializer serializer = variant.createSerializer();
120  ros::serialization::IStream stream(const_cast<uint8_t*>(
121  data.data()), data.size());
122 
123  serializer.deserialize(stream, variant);
124 }
125 
128  new variant_msgs::Variant());
129 
130  variant->header.publisher = header.getPublisher();
131  variant->header.topic = header.getTopic();
132  variant->header.latched = header.isLatched();
133 
134  variant->type.data_type = type.getDataType();
135  variant->type.md5_sum = type.getMD5Sum();
136  variant->type.definition = type.getDefinition();
137 
138  variant->data = data;
139 
140  return variant;
141 }
142 
143 }
void serialize(const MessageVariant &variant)
Attempt to serialize this message from a variant.
Definition: Message.cpp:95
void setHeader(const MessageHeader &header)
Set the message header.
Definition: Message.cpp:47
const DataType & getType() const
Retrieve the data type of this variant.
Definition: Variant.cpp:52
Header file providing the MessageDefinition class interface.
std::vector< uint8_t > data
The data of this message.
Definition: Message.h:143
Generic message type.
Definition: Message.h:43
Serializer createSerializer() const
Create a serializer for this variant.
Definition: Variant.cpp:138
bool isLatched() const
True, if the message publication is latched.
Message()
Default constructor.
Definition: Message.cpp:31
Header file providing the Message class interface.
Header file providing the MessageSerializer class interface.
Variant message type information.
Definition: MessageType.h:33
Header file providing the MessageVariant class interface.
void setDataType(const std::string &dataType)
Set the data type of the message.
Definition: MessageType.cpp:70
const MessageType & getType() const
Retrieve the message type.
Definition: Message.cpp:67
size_t getSize() const
Retrieve the message size.
Definition: Message.cpp:87
const std::string & getDefinition() const
Retrieve the message definition.
Definition: MessageType.cpp:90
std::string getMD5Sum() const
Retrieve the MD5 sum of this message data type.
void serialize(ros::serialization::OStream &stream, const Variant &value)
Serialize a variant value to an output stream.
Definition: Serializer.cpp:73
const std::string & getDefinition() const
Retrieve the definition this message data type.
const std::string & getIdentifier() const
Retrieve the identifier representing this data type.
Definition: DataType.cpp:75
MessageHeader header
The header of this message.
Definition: Message.h:135
void setSize(size_t size)
Set the message size.
Definition: Message.cpp:83
const std::string & getPublisher() const
Retrieve the name of the publishing node.
void setMD5Sum(const std::string &md5Sum)
Set the MD5 sum of the message.
Definition: MessageType.cpp:78
size_t getSerializedLength(const Variant &value) const
Retrieve the serialized length of a variant value.
Definition: Serializer.cpp:54
const std::string & getDataType() const
Retrieve the data type of the message.
Definition: MessageType.cpp:74
MessageDataType getMessageDataType() const
Retrieve the message data type represented by this message definition.
Header file providing the DataTypeRegistry class interface.
void deserialize(MessageVariant &variant) const
Attempt to deserialize this message into a variant.
Definition: Message.cpp:109
const std::string & getMD5Sum() const
Retrieve the MD5 sum of the message.
Definition: MessageType.cpp:82
DataType getDataType(const std::string &identifier)
Retrieve a data type from the registry by identifier (non-const version)
void deserialize(ros::serialization::IStream &stream, Variant &value)
Deserialize a variant value from an input stream.
Definition: Serializer.cpp:81
void setType(const MessageType &type)
Set the message type.
Definition: Message.cpp:59
MessageType type
The type of this message.
Definition: Message.h:139
boost::shared_ptr< variant_msgs::Variant > toVariantMessage() const
Attempt to convert the message to a variant message.
Definition: Message.cpp:126
const std::string & getTopic() const
Retrieve the message publishing topic.
Variant createVariant() const
Create a variant from this data type.
Definition: DataType.cpp:168
const MessageHeader & getHeader() const
Retrieve the message header.
Definition: Message.cpp:55
Variant message header.
Definition: MessageHeader.h:33
void setDefinition(const std::string &definition)
Set the message definition.
Definition: MessageType.cpp:86
const char * definition()
std::vector< uint8_t > & getData()
Retrieve the message data (non-const version)
Definition: Message.cpp:75
void setData(const std::vector< uint8_t > &data)
Set the message data.
Definition: Message.cpp:71


variant_topic_tools
Author(s): Ralf Kaestner
autogenerated on Sat Jan 9 2021 03:56:49