SerializerTest.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 
19 #include <gtest/gtest.h>
20 
21 #include <std_msgs/Bool.h>
22 #include <std_msgs/String.h>
23 
24 #include <variant_msgs/Test.h>
25 
31 
32 using namespace variant_topic_tools;
33 
34 TEST(Serializer, Array) {
35  DataTypeRegistry registry;
36 
37  std::vector<uint8_t> d1(1024);
38  ros::serialization::OStream o1(d1.data(), d1.size());
39  ros::serialization::IStream i1(d1.data(), d1.size());
40 
41  boost::array<int, 3> a1;
42  a1[0] = 0; a1[1] = 1; a1[2] = 2;
43  std::vector<int> a2(3);
44  a2[0] = 0; a2[1] = 1; a2[2] = 2;
45  Variant v1, v2;
46 
47  Serializer s1 = registry.getDataType<int[3]>().createSerializer();
48  Serializer s2 = registry.getDataType<int[]>().createSerializer();
49 
50  s1.serialize(o1, a1);
51  EXPECT_EQ(d1.size()-ros::serialization::serializationLength(a1),
52  o1.getLength());
53  s1.deserialize(i1, v1);
54  EXPECT_EQ(a1[0], v1.getValue<int[3]>()[0]);
55  EXPECT_EQ(a1[1], v1.getValue<int[3]>()[1]);
56  EXPECT_EQ(a1[2], v1.getValue<int[3]>()[2]);
57  s2.serialize(o1, a2);
58  s2.deserialize(i1, v2);
59  EXPECT_EQ(a2[0], v2.getValue<int[]>()[0]);
60  EXPECT_EQ(a2[1], v2.getValue<int[]>()[1]);
61  EXPECT_EQ(a2[2], v2.getValue<int[]>()[2]);
62 
63  registry.clear();
64 }
65 
66 TEST(Serializer, Builtin) {
67  DataTypeRegistry registry;
68 
69  std::vector<uint8_t> d1(1024);
70  ros::serialization::OStream o1(d1.data(), d1.size());
71  ros::serialization::IStream i1(d1.data(), d1.size());
72 
73  int b1 = 42;
74  double b2 = 42.0;
75  Variant v1, v2;
76 
77  Serializer s1 = registry.getDataType<int>().createSerializer();
78  Serializer s2 = registry.getDataType<double>().createSerializer();
79  Serializer s3 = registry.getDataType<bool>().createSerializer();
80 
81  s1.serialize(o1, b1);
82  EXPECT_EQ(d1.size()-sizeof(b1), o1.getLength());
83  s1.deserialize(i1, v1);
84  EXPECT_EQ(b1, v1.getValue<int>());
85  s2.serialize(o1, b2);
86  s2.deserialize(i1, v2);
87  EXPECT_EQ(b2, v2.getValue<double>());
88  EXPECT_ANY_THROW(s3.serialize(o1, b1));
89 }
90 
92  DataTypeRegistry registry;
93 
94  std::vector<uint8_t> d1(1024);
95  ros::serialization::OStream o1(d1.data(), d1.size());
96  ros::serialization::IStream i1(d1.data(), d1.size());
98 
99  std_msgs::Bool m1;
100  m1.data = true;
101  std_msgs::String m2;
102  m2.data = "Test";
103  variant_msgs::Test m3;
104  m3.header.stamp = ros::Time::now();
105  m3.builtin_int = 42;
106  m3.builtin_string = "Test";
107  m3.string.data = "Test";
108  m3.builtin_int_array[0] = 0;
109  m3.builtin_int_array[1] = 1;
110  m3.builtin_int_array[2] = 2;
111  m3.builtin_int_vector.resize(3);
112  m3.builtin_int_vector[0] = 0;
113  m3.builtin_int_vector[1] = 1;
114  m3.builtin_int_vector[2] = 2;
115  Variant v1, v2, v3;
116 
117  Serializer s1 = registry.getDataType<std_msgs::Bool>().createSerializer();
118  Serializer s2 = registry.getDataType<std_msgs::String>().createSerializer();
119  Serializer s3 = registry.getDataType<variant_msgs::Test>().
120  createSerializer();
121 
122  s1.serialize(o1, m1);
123  EXPECT_EQ(d1.size()-ros::serialization::serializationLength(m1),
124  o1.getLength());
125  s1.deserialize(i1, v1);
126  EXPECT_EQ(m1.data, v1.getValue<std_msgs::Bool>().data);
127  s2.serialize(o1, m2);
128  s2.deserialize(i1, v2);
129  EXPECT_EQ(m2.data, v2.getValue<std_msgs::String>().data);
130  s3.serialize(o1, m3);
131  s3.deserialize(i1, v3);
132  EXPECT_EQ(m3.header.stamp, v3.getValue<variant_msgs::Test>().header.stamp);
133  EXPECT_EQ(m3.builtin_int, v3.getValue<variant_msgs::Test>().builtin_int);
134  EXPECT_EQ(m3.builtin_string,
135  v3.getValue<variant_msgs::Test>().builtin_string);
136  EXPECT_EQ(m3.string.data, v3.getValue<variant_msgs::Test>().string.data);
137  EXPECT_EQ(m3.builtin_int_array[0],
138  v3.getValue<variant_msgs::Test>().builtin_int_array[0]);
139  EXPECT_EQ(m3.builtin_int_array[1],
140  v3.getValue<variant_msgs::Test>().builtin_int_array[1]);
141  EXPECT_EQ(m3.builtin_int_array[2],
142  v3.getValue<variant_msgs::Test>().builtin_int_array[2]);
143  EXPECT_EQ(m3.builtin_int_vector[0],
144  v3.getValue<variant_msgs::Test>().builtin_int_vector[0]);
145  EXPECT_EQ(m3.builtin_int_vector[1],
146  v3.getValue<variant_msgs::Test>().builtin_int_vector[1]);
147  EXPECT_EQ(m3.builtin_int_vector[2],
148  v3.getValue<variant_msgs::Test>().builtin_int_vector[2]);
149 
150  registry.clear();
151 }
152 
153 TEST(Serializer, VariantArray) {
154  DataTypeRegistry registry;
155 
156  std::vector<uint8_t> d1(1024);
157  ros::serialization::OStream o1(d1.data(), d1.size());
158  ros::serialization::IStream i1(d1.data(), d1.size());
159  std::vector<uint8_t> d2(1024);
160  ros::serialization::OStream o2(d2.data(), d2.size());
161  ros::serialization::IStream i2(d2.data(), d2.size());
162 
163  boost::array<int, 3> a1;
164  a1[0] = 0; a1[1] = 1; a1[2] = 2;
165  std::vector<int> a2(3);
166  a2[0] = 0; a2[1] = 1; a2[2] = 2;
167 
168  ArrayVariant v1 = registry.getDataType("int32[3]").createVariant();
169  v1[0] = a1[0]; v1[1] = a1[1]; v1[2] = a1[2];
170  ArrayVariant v2 = registry.getDataType("int32[3]").createVariant();
171  ArrayVariant v3 = registry.getDataType("int32[]").createVariant();
172  v3 += a2[0]; v3 += a2[1]; v3 += a2[2];
173  ArrayVariant v4 = registry.getDataType("int32[]").createVariant();
174 
175  Serializer s1 = v1.createSerializer();
176  Serializer s2 = v3.createSerializer();
177 
178  s1.serialize(o1, v1);
179  EXPECT_EQ(d1.size()-v1.getType().getSize(), o1.getLength());
180  s1.deserialize(i1, v2);
181  EXPECT_EQ(v1, v2);
183  s1.deserialize(i2, v2);
184  EXPECT_EQ(a1[0], v2[0].getValue<int>());
185  EXPECT_EQ(a1[1], v2[1].getValue<int>());
186  EXPECT_EQ(a1[2], v2[2].getValue<int>());
187  s1.serialize(o2, v1);
189  EXPECT_EQ(v1[0].getValue<int>(), a1[0]);
190  EXPECT_EQ(v1[1].getValue<int>(), a1[1]);
191  EXPECT_EQ(v1[2].getValue<int>(), a1[2]);
192 
193  s2.serialize(o1, v3);
194  s2.deserialize(i1, v4);
195  EXPECT_EQ(v3, v4);
197  s2.deserialize(i2, v4);
198  EXPECT_EQ(a2.size(), v4.getNumMembers());
199  EXPECT_EQ(a2[0], v4[0].getValue<int>());
200  EXPECT_EQ(a2[1], v4[1].getValue<int>());
201  EXPECT_EQ(a2[2], v4[2].getValue<int>());
202  s2.serialize(o2, v3);
204  EXPECT_EQ(v3.getNumMembers(), a2.size());
205  EXPECT_EQ(v3[0].getValue<int>(), a2[0]);
206  EXPECT_EQ(v3[1].getValue<int>(), a2[1]);
207  EXPECT_EQ(v3[2].getValue<int>(), a2[2]);
208 
209  registry.clear();
210 }
211 
212 TEST(Serializer, VariantMessage) {
213  DataTypeRegistry registry;
214 
215  std::vector<uint8_t> d1(1024);
216  ros::serialization::OStream o1(d1.data(), d1.size());
217  ros::serialization::IStream i1(d1.data(), d1.size());
218  std::vector<uint8_t> d2(1024);
219  ros::serialization::OStream o2(d2.data(), d2.size());
220  ros::serialization::IStream i2(d2.data(), d2.size());
221  ros::Time::init();
222 
223  variant_msgs::Test m1;
224  m1.header.stamp = ros::Time::now();
225  m1.builtin_int = 42;
226  m1.builtin_string = "Test";
227  m1.string.data = "Test";
228  m1.builtin_int_array[0] = 0;
229  m1.builtin_int_array[1] = 1;
230  m1.builtin_int_array[2] = 2;
231  m1.builtin_int_vector.resize(3);
232  m1.builtin_int_vector[0] = 0;
233  m1.builtin_int_vector[1] = 1;
234  m1.builtin_int_vector[2] = 2;
235 
236  MessageDataType t1 = MessageDefinition::create<variant_msgs::Test>().
237  getMessageDataType();
238  MessageVariant v1 = t1.createVariant();
239  v1["header/stamp"] = m1.header.stamp;
240  v1["builtin_int"] = m1.builtin_int;
241  v1["builtin_string"] = m1.builtin_string;
242  v1["string/data"] = m1.string.data;
243  v1["builtin_int_array/0"] = m1.builtin_int_array[0];
244  v1["builtin_int_array/1"] = m1.builtin_int_array[1];
245  v1["builtin_int_array/2"] = m1.builtin_int_array[2];
246  v1["builtin_int_vector"].asArray().resize(3);
247  v1["builtin_int_vector/0"] = m1.builtin_int_vector[0];
248  v1["builtin_int_vector/1"] = m1.builtin_int_vector[1];
249  v1["builtin_int_vector/2"] = m1.builtin_int_vector[2];
250  MessageVariant v2 = t1.createVariant();
251 
252  Serializer s1 = v1.createSerializer();
253 
254  s1.serialize(o1, v1);
255  s1.deserialize(i1, v2);
256  EXPECT_EQ(v1, v2);
257 
259  s1.deserialize(i2, v2);
260  EXPECT_EQ(m1.header.stamp, v2["header/stamp"].getValue<ros::Time>());
261  EXPECT_EQ(m1.builtin_int, v2["builtin_int"].getValue<int>());
262  EXPECT_EQ(m1.builtin_string, v2["builtin_string"].getValue<std::string>());
263  EXPECT_EQ(m1.string.data, v2["string/data"].getValue<std::string>());
264  EXPECT_EQ(m1.builtin_int_array[0], v2["builtin_int_array/0"].
265  getValue<int>());
266  EXPECT_EQ(m1.builtin_int_array[1], v2["builtin_int_array/1"].
267  getValue<int>());
268  EXPECT_EQ(m1.builtin_int_array[2], v2["builtin_int_array/2"].
269  getValue<int>());
270  EXPECT_EQ(m1.builtin_int_vector.size(), v2["builtin_int_vector"].
271  asArray().getNumMembers());
272  EXPECT_EQ(m1.builtin_int_vector[0], v2["builtin_int_vector/0"].
273  getValue<int>());
274  EXPECT_EQ(m1.builtin_int_vector[1], v2["builtin_int_vector/1"].
275  getValue<int>());
276  EXPECT_EQ(m1.builtin_int_vector[2], v2["builtin_int_vector/2"].
277  getValue<int>());
278  s1.serialize(o2, v1);
280  EXPECT_EQ(v1["header/stamp"].getValue<ros::Time>(), m1.header.stamp);
281  EXPECT_EQ(v1["builtin_int"].getValue<int>(), m1.builtin_int);
282  EXPECT_EQ(v1["builtin_string"].getValue<std::string>(), m1.builtin_string);
283  EXPECT_EQ(v1["string/data"].getValue<std::string>(), m1.string.data);
284  EXPECT_EQ(v1["builtin_int_array/0"].getValue<int>(),
285  m1.builtin_int_array[0]);
286  EXPECT_EQ(v1["builtin_int_array/1"].getValue<int>(),
287  m1.builtin_int_array[1]);
288  EXPECT_EQ(v1["builtin_int_array/2"].getValue<int>(),
289  m1.builtin_int_array[2]);
290  EXPECT_EQ(v1["builtin_int_vector"].asArray().getNumMembers(),
291  m1.builtin_int_vector.size());
292  EXPECT_EQ(v1["builtin_int_vector/0"].getValue<int>(),
293  m1.builtin_int_vector[0]);
294  EXPECT_EQ(v1["builtin_int_vector/1"].getValue<int>(),
295  m1.builtin_int_vector[1]);
296  EXPECT_EQ(v1["builtin_int_vector/2"].getValue<int>(),
297  m1.builtin_int_vector[2]);
298 
299  registry.clear();
300 }
Header file providing the ArraySerializer class interface.
const DataType & getType() const
Retrieve the data type of this variant.
Definition: Variant.cpp:52
Header file providing the MessageDefinition class interface.
Generic message type.
Definition: Message.h:43
void resize(size_t numMembers)
Resize the array.
Serializer createSerializer() const
Create a serializer for this variant.
Definition: Variant.cpp:138
Header file providing the MessageSerializer class interface.
void clear()
Clear the data type registry.
void serialize(ros::serialization::OStream &stream, const Variant &value)
Serialize a variant value to an output stream.
Definition: Serializer.cpp:73
type_traits::DataType< T >::ValueType & getValue()
Retrieve the variant&#39;s value (non-const version)
void serialize(Stream &stream, const T &t)
Header file providing the DataTypeRegistry class interface.
static void init()
T & getValue(int index)
Retrieve a member value of the collection by index (non-const version)
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
size_t getNumMembers() const
Retrieve the number of members of the collection.
uint32_t serializationLength(const T &t)
Header file providing the BuiltinSerializer class interface.
size_t getSize() const
Retrieve the size of the instances of this data type.
Definition: DataType.cpp:91
Variant createVariant() const
Create a variant from this data type.
Definition: DataType.cpp:168
static Time now()
ArrayVariant asArray() const
Retrieve this variant as array.
Definition: Variant.cpp:107
void deserialize(Stream &stream, T &t)
TEST(Serializer, Array)


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