-
Notifications
You must be signed in to change notification settings - Fork 304
/
Copy pathSerialization.hh
268 lines (246 loc) · 7.95 KB
/
Serialization.hh
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
/*
* Copyright (C) 2019 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_GAZEBO_COMPONENTS_SERIALIZATION_HH_
#define IGNITION_GAZEBO_COMPONENTS_SERIALIZATION_HH_
#include <google/protobuf/message_lite.h>
#include <ignition/msgs/double_v.pb.h>
#include <string>
#include <vector>
#include <sdf/Sensor.hh>
#include <ignition/gazebo/Conversions.hh>
#include <ignition/msgs/Utility.hh>
// This header holds serialization operators which are shared among several
// components
namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace traits
{
/// \brief Type trait that determines if an ignition::gazebo::convert from In
/// to Out is defined.
/// Usage:
/// \code
/// constexpr bool hasGazeboConvert =
/// HasGazeboConvert<math::Pose, msgs::Pose>::value
/// \endcode
template <typename In, typename Out>
class HasGazeboConvert
{
private: template <typename InArg, typename OutArg>
static auto Test(int _test)
-> decltype(std::declval<OutArg>() =
ignition::gazebo::convert<OutArg>(std::declval<const InArg &>()),
std::true_type());
private: template <typename, typename>
static auto Test(...) -> std::false_type;
public: static constexpr bool value = // NOLINT
decltype(Test<In, Out>(true))::value;
};
}
/// \brief A Serializer class is used to serialize and deserialize a component.
/// It is passed in as the third template parameter to components::Component.
/// Eg.
/// \code
/// using Geometry = components::Component<sdf::Geometry, GeometryTag,
/// serializers::GeometrySerializer>
/// \endcode
/// A serializer class implements two static functions: `Serialize` and
/// `Deserialize` with the following signatures
/// \code
/// class ExampleSerializer
/// {
/// public: static std::ostream &Serialize(std::ostream &_out,
/// const DataType &_data);
/// public: static std::istream &Deserialize(std::istream &_in,
/// DataType &_data)
/// };
/// \endcode
namespace serializers
{
/// \brief Serialization for that converts components data types to
/// ignition::msgs. This assumes that ignition::gazebo::convert<DataType> is
/// defined
/// \tparam DataType Underlying data type of the component
///
/// This can be used for components that can be converted to ignition::msg
/// types via ignition::gazebo::convert. For example sdf::Geometry can be
/// converted to msgs::Geometry so the component can be defined as
/// \code
/// using Geometry = Component<sdf::Geometry, class GeometryTag,
/// ComponentToMsgSerializer<sdf::Geometry, msgs::Geometry>>
/// \endcode
template <typename DataType, typename MsgType>
class ComponentToMsgSerializer
{
/// \brief Serialization
/// \param[in] _out Output stream.
/// \param[in] _data data to stream
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
const DataType &_data)
{
MsgType msg;
// cppcheck-suppress syntaxError
if constexpr (traits::HasGazeboConvert<DataType, MsgType>::value)
{
msg = ignition::gazebo::convert<MsgType>(_data);
}
else
{
msg = ignition::msgs::Convert(_data);
}
msg.SerializeToOstream(&_out);
return _out;
}
/// \brief Deserialization
/// \param[in] _in Input stream.
/// \param[out] _data data to populate
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
DataType &_data)
{
MsgType msg;
msg.ParseFromIstream(&_in);
if constexpr (traits::HasGazeboConvert<MsgType, DataType>::value)
{
_data = ignition::gazebo::convert<DataType>(msg);
}
else
{
_data = ignition::msgs::Convert(msg);
}
return _in;
}
};
/// \brief Common serializer for sensors
using SensorSerializer = ComponentToMsgSerializer<sdf::Sensor, msgs::Sensor>;
/// \brief Serializer for components that hold `std::vector<double>`.
class VectorDoubleSerializer
{
/// \brief Serialization
/// \param[in] _out Output stream.
/// \param[in] _vec Vector to stream
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
const std::vector<double> &_vec)
{
ignition::msgs::Double_V msg;
*msg.mutable_data() = {_vec.begin(), _vec.end()};
msg.SerializeToOstream(&_out);
return _out;
}
/// \brief Deserialization
/// \param[in] _in Input stream.
/// \param[in] _vec Vector to populate
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
std::vector<double> &_vec)
{
ignition::msgs::Double_V msg;
msg.ParseFromIstream(&_in);
_vec = {msg.data().begin(), msg.data().end()};
return _in;
}
};
/// \brief Serializer for components that hold protobuf messages.
class MsgSerializer
{
/// \brief Serialization
/// \param[in] _out Output stream.
/// \param[in] _msg Message to stream
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
const google::protobuf::Message &_msg)
{
_msg.SerializeToOstream(&_out);
return _out;
}
/// \brief Deserialization
/// \param[in] _in Input stream.
/// \param[in] _msg Message to populate
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
google::protobuf::Message &_msg)
{
_msg.ParseFromIstream(&_in);
return _in;
}
};
/// \brief Serializer for components that hold std::string.
class StringSerializer
{
/// \brief Serialization
/// \param[in] _out Output stream.
/// \param[in] _data Data to serialize.
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
const std::string &_data)
{
_out << _data;
return _out;
}
/// \brief Deserialization
/// \param[in] _in Input stream.
/// \param[in] _data Data to populate.
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
std::string &_data)
{
_data = std::string(std::istreambuf_iterator<char>(_in), {});
return _in;
}
};
template <typename T>
class VectorSerializer
{
/// \brief Serialization for `std::vector<T>` with serializable T.
/// \param[in] _out Output stream.
/// \param[in] _data The data to stream.
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
const std::vector<T> &_data)
{
_out << _data.size();
for (const auto& datum : _data)
_out << " " << datum;
return _out;
}
/// \brief Deserialization for `std::vector<T>` with serializable T.
/// \param[in] _in Input stream.
/// \param[out] _data The data to populate.
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
std::vector<T> &_data)
{
size_t size;
_in >> size;
_data.resize(size);
for (size_t i = 0; i < size; ++i)
{
_in >> _data[i];
}
return _in;
}
};
}
}
}
}
#endif