serialization.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Josh Faust */
31 
32 /*
33  * Test serialization templates
34  */
35 
36 #include <gtest/gtest.h>
37 #include <ros/static_assert.h>
38 #include <std_msgs/Header.h>
39 #include "helpers.h"
40 
41 using namespace ros;
42 using namespace ros::serialization;
43 using namespace test_roscpp;
44 
45 ROS_STATIC_ASSERT(sizeof(ros::Time) == 8);
46 ROS_STATIC_ASSERT(sizeof(ros::Duration) == 8);
47 
49 // Tests for compilation/validity of serialization/deserialization of primitive types
51 
52 #define PRIMITIVE_SERIALIZATION_TEST(Type, SerInit, DeserInit) \
53  TEST(Serialization, Type) \
54  { \
55  Type ser_val SerInit; \
56  Type deser_val DeserInit; \
57  Array b = serializeAndDeserialize(ser_val, deser_val); \
58  EXPECT_EQ(*(Type*)b.get(), ser_val); \
59  EXPECT_EQ(ser_val, deser_val); \
60  }
61 
62 PRIMITIVE_SERIALIZATION_TEST(uint8_t, (5), (0));
63 PRIMITIVE_SERIALIZATION_TEST(int8_t, (5), (0));
64 PRIMITIVE_SERIALIZATION_TEST(uint16_t, (5), (0));
65 PRIMITIVE_SERIALIZATION_TEST(int16_t, (5), (0));
66 PRIMITIVE_SERIALIZATION_TEST(uint32_t, (5), (0));
67 PRIMITIVE_SERIALIZATION_TEST(int32_t, (5), (0));
68 PRIMITIVE_SERIALIZATION_TEST(uint64_t, (5), (0));
69 PRIMITIVE_SERIALIZATION_TEST(int64_t, (5), (0));
70 PRIMITIVE_SERIALIZATION_TEST(float, (5.0f), (0.0f));
71 PRIMITIVE_SERIALIZATION_TEST(double, (5.0), (0.0));
72 PRIMITIVE_SERIALIZATION_TEST(Time, (500, 10000), (0, 0));
73 PRIMITIVE_SERIALIZATION_TEST(Duration, (500, 10000), (0, 0));
74 
75 #define PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(Type, Start, Increment) \
76  TEST(Serialization, variableLengthArray_##Type) \
77  { \
78  std::vector<Type> ser_val, deser_val; \
79  Type val = Start; \
80  for (uint32_t i = 0; i < 8; ++i) \
81  { \
82  ser_val.push_back(val); \
83  val = val + Increment; \
84  } \
85  \
86  Array b = serializeAndDeserialize(ser_val, deser_val); \
87  EXPECT_TRUE(ser_val == deser_val); \
88  \
89  EXPECT_EQ(*(uint32_t*)b.get(), (uint32_t)ser_val.size()); \
90  for(size_t i = 0; i < ser_val.size(); ++i) \
91  { \
92  Type* ptr = ((Type*)(b.get() + 4)) + i; \
93  EXPECT_EQ(*ptr, ser_val[i]); \
94  } \
95  }
96 
99 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(uint16_t, 0, 100);
100 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(int16_t, 0, 100);
101 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(uint32_t, 0, 100);
102 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(int32_t, 0, 100);
103 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(uint64_t, 0, 100);
104 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(int64_t, 0, 100);
105 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(float, 0.0f, 100.0f);
106 PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(double, 0.0, 100.0);
109 
110 #define PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(Type, Start, Increment) \
111  TEST(Serialization, fixedLengthArray_##Type) \
112  { \
113  boost::array<Type, 8> ser_val, deser_val; \
114  Type val = Start; \
115  for (uint32_t i = 0; i < 8; ++i) \
116  { \
117  ser_val[i] = val; \
118  val = val + Increment; \
119  } \
120  \
121  Array b = serializeAndDeserialize(ser_val, deser_val); \
122  EXPECT_TRUE(ser_val == deser_val); \
123  \
124  for(size_t i = 0; i < ser_val.size(); ++i) \
125  { \
126  Type* ptr = ((Type*)b.get()) + i; \
127  EXPECT_EQ(*ptr, ser_val[i]); \
128  } \
129  }
130 
131 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint8_t, 65, 1);
132 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int8_t, 65, 1);
133 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint16_t, 0, 100);
134 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int16_t, 0, 100);
135 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint32_t, 0, 100);
136 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int32_t, 0, 100);
137 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint64_t, 0, 100);
138 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int64_t, 0, 100);
139 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(float, 0.0f, 100.0f);
140 PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(double, 0.0, 100.0);
143 
144 TEST(Serialization, string)
145 {
146  std::string ser_val = "hello world";
147  std::string deser_val;
148  Array b = serializeAndDeserialize(ser_val, deser_val);
149  EXPECT_STREQ(ser_val.c_str(), deser_val.c_str());
150 
151  EXPECT_EQ(*(uint32_t*)b.get(), (uint32_t)ser_val.size());
152  EXPECT_EQ(memcmp(b.get() + 4, ser_val.data(), ser_val.size()), 0);
153 }
154 
155 TEST(Serialization, variableLengthArray_string)
156 {
157  std::vector<std::string> ser_val, deser_val;
158  ser_val.push_back("hello world");
159  ser_val.push_back("hello world22");
160  ser_val.push_back("hello world333");
161  ser_val.push_back("hello world4444");
162  ser_val.push_back("hello world55555");
163  Array b = serializeAndDeserialize(ser_val, deser_val);
164  EXPECT_TRUE(ser_val == deser_val);
165 }
166 
167 TEST(Serialization, fixedLengthArray_string)
168 {
169  boost::array<std::string, 5> ser_val, deser_val;
170  ser_val[0] = "hello world";
171  ser_val[1] = "hello world22";
172  ser_val[2] = "hello world333";
173  ser_val[3] = "hello world4444";
174  ser_val[4] = "hello world55555";
175  Array b = serializeAndDeserialize(ser_val, deser_val);
176  EXPECT_TRUE(ser_val == deser_val);
177 }
178 
180 // Test custom types and traits
182 
183 // Class used to make sure fixed-size simple structs use a memcpy when serializing an array of them
184 // serialization only serializes a, memcpy will get both a and b.
186 {
188  : a(0)
189  , b(0)
190  {}
191 
192  int32_t a;
193  int32_t b;
194 };
195 
196 namespace ros
197 {
198 namespace message_traits
199 {
200 template<> struct IsFixedSize<FixedSizeSimple> : public TrueType {};
201 template<> struct IsSimple<FixedSizeSimple> : public TrueType {};
202 } // namespace message_traits
203 
204 namespace serialization
205 {
206 template<>
208 {
209  template<typename Stream>
210  inline static void write(Stream& stream, const FixedSizeSimple& v)
211  {
212  serialize(stream, v.a);
213  }
214 
215  template<typename Stream>
216  inline static void read(Stream& stream, FixedSizeSimple& v)
217  {
218  deserialize(stream, v.a);
219  }
220 
221  inline static uint32_t serializedLength(const FixedSizeSimple&)
222  {
223  return 4;
224  }
225 };
226 } // namespace serialization
227 } // namespace ros
228 
229 TEST(Serialization, fixedSizeSimple_vector)
230 {
231  {
232  FixedSizeSimple in, out;
233  in.a = 1;
234  in.b = 1;
235 
236  serializeAndDeserialize(in, out);
237  ASSERT_EQ(out.a, 1);
238  ASSERT_EQ(out.b, 0);
239  }
240 
241  {
242  std::vector<FixedSizeSimple> in, out;
243  in.resize(1);
244  in[0].a = 1;
245  in[0].b = 1;
246 
247  serializeAndDeserialize(in, out);
248  ASSERT_EQ(out[0].a, 1);
249  ASSERT_EQ(out[0].b, 1);
250  }
251 }
252 
253 TEST(Serialization, fixedSizeSimple_array)
254 {
255  boost::array<FixedSizeSimple, 2> in, out;
256  in[0].a = 1;
257  in[0].b = 1;
258 
259  serializeAndDeserialize(in, out);
260  ASSERT_EQ(out[0].a, 1);
261  ASSERT_EQ(out[0].b, 1);
262 }
263 
264 // Class used to make sure fixed-size non-simple structs only query the length of the first element
265 // in an array.
267 {
269  : length_to_report(4)
270  {}
271 
273 };
274 
275 namespace ros
276 {
277 namespace message_traits
278 {
279 template<> struct IsFixedSize<FixedSizeNonSimple> : public TrueType {};
280 } // namespace message_traits
281 
282 namespace serialization
283 {
284 template<>
286 {
287  inline static uint32_t serializedLength(const FixedSizeNonSimple& v)
288  {
289  return v.length_to_report;
290  }
291 };
292 } // namespace serialization
293 } // namespace ros
294 
295 TEST(Serialization, fixedSizeNonSimple_vector)
296 {
297  std::vector<FixedSizeNonSimple> in;
298  in.resize(2);
299  in[1].length_to_report = 100;
300 
301  int32_t len = ros::serialization::serializationLength(in);
302  ASSERT_EQ(len, 12); // 12 = 4 bytes for each item + 4-byte array length
303 }
304 
305 TEST(Serialization, fixedSizeNonSimple_array)
306 {
307  boost::array<FixedSizeNonSimple, 2> in;
308  in[1].length_to_report = 100;
309 
310  int32_t len = ros::serialization::serializationLength(in);
311  ASSERT_EQ(len, 8); // 8 = 4 bytes for each item
312 }
313 
314 // Class used to make sure variable-size structs query the length of the every element
315 // in an array.
317 {
319  : length_to_report(4)
320  {}
321 
323 };
324 
325 namespace ros
326 {
327 namespace serialization
328 {
329 template<>
331 {
332  inline static uint32_t serializedLength(const VariableSize& v)
333  {
334  return v.length_to_report;
335  }
336 };
337 } // namespace serialization
338 } // namespace ros
339 
340 TEST(Serialization, variableSize_vector)
341 {
342  std::vector<VariableSize> in;
343  in.resize(2);
344  in[1].length_to_report = 100;
345 
346  int32_t len = ros::serialization::serializationLength(in);
347  ASSERT_EQ(len, 108); // 108 = 4 bytes for the first item + 100 bytes for the second + 4-byte array length
348 }
349 
350 TEST(Serialization, variableSize_array)
351 {
352  boost::array<VariableSize, 2> in;
353  in[1].length_to_report = 100;
354 
355  int32_t len = ros::serialization::serializationLength(in);
356  ASSERT_EQ(len, 104); // 104 = 4 bytes for the first item + 100 bytes for the second
357 }
358 
360 {
361  uint32_t a;
362 };
363 
364 namespace ros
365 {
366 namespace serialization
367 {
368 template<>
370 {
371  template<typename Stream, typename T>
372  inline static void allInOne(Stream& stream, T t)
373  {
374  stream.next(t.a);
375  }
376 
378 };
379 } // namespace serialization
380 } // namespace ros
381 
382 TEST(Serialization, allInOne)
383 {
384  AllInOneSerializer in, out;
385  in.a = 5;
386  serializeAndDeserialize(in, out);
387  ASSERT_EQ(out.a, in.a);
388 }
389 
390 // Class with a header, used to ensure message_traits::header(m) returns the header
392 {
394  {}
395 
396  std_msgs::Header header;
397 };
398 
399 // Class without a header, used to ensure message_traits::header(m) return NULL
401 {
403  {}
404 };
405 
406 namespace ros
407 {
408 namespace message_traits
409 {
410 template<> struct HasHeader<WithHeader> : public TrueType {};
411 } // namespace message_traits
412 } // namespace ros
413 
414 TEST(MessageTraits, headers)
415 {
416  WithHeader wh;
417  WithoutHeader woh;
418  const WithHeader cwh;
419  const WithoutHeader cwoh;
420 
421  wh.header.seq = 100;
422  ASSERT_TRUE(ros::message_traits::header(wh) != 0);
423  ASSERT_EQ(ros::message_traits::header(wh)->seq, 100UL);
424 
425  ASSERT_TRUE(ros::message_traits::header(woh) == 0);
426 
427  ASSERT_TRUE(ros::message_traits::header(cwh) != 0);
428  ASSERT_TRUE(ros::message_traits::header(cwoh) == 0);
429 
430  ASSERT_TRUE(ros::message_traits::frameId(wh) != 0);
431  ASSERT_TRUE(ros::message_traits::frameId(woh) == 0);
432  ASSERT_TRUE(ros::message_traits::frameId(cwh) != 0);
433  ASSERT_TRUE(ros::message_traits::frameId(cwoh) == 0);
434 
435  ASSERT_TRUE(ros::message_traits::timeStamp(wh) != 0);
436  ASSERT_TRUE(ros::message_traits::timeStamp(woh) == 0);
437  ASSERT_TRUE(ros::message_traits::timeStamp(cwh) != 0);
438  ASSERT_TRUE(ros::message_traits::timeStamp(cwoh) == 0);
439 }
440 
441 TEST(Serialization, bufferOverrun)
442 {
443  Array b(new uint8_t[4]);
444  IStream stream(b.get(), 4);
445  uint32_t i;
446  deserialize(stream, i);
447  try
448  {
449  deserialize(stream, i);
450  FAIL();
451  }
452  catch(ros::Exception&)
453  {
454  SUCCEED();
455  }
456 }
457 
458 TEST(Serialization, streamOperators)
459 {
460  Array b(new uint8_t[4]);
461  OStream ostream(b.get(), 4);
462  uint32_t a = 5;
463  ostream << a;
464  a = 100;
465  IStream istream(b.get(), 4);
466  istream >> a;
467  ASSERT_EQ(a, 5UL);
468 }
469 
470 int main(int argc, char** argv)
471 {
472  testing::InitGoogleTest(&argc, argv);
473  return RUN_ALL_TESTS();
474 }
475 
476 
477 
std_msgs::Header header
#define PRIMITIVE_SERIALIZATION_TEST(Type, SerInit, DeserInit)
#define PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(Type, Start, Increment)
ros::Time * timeStamp(M &m)
#define ROS_DECLARE_ALLINONE_SERIALIZER
ROS_STATIC_ASSERT(sizeof(ros::Time)==8)
int main(int argc, char **argv)
std::string * frameId(M &m)
std_msgs::Header * header(M &m)
static void read(Stream &stream, FixedSizeSimple &v)
void serialize(Stream &stream, const T &t)
static uint32_t serializedLength(const FixedSizeNonSimple &v)
#define PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(Type, Start, Increment)
Array serializeAndDeserialize(const T &ser_val, T &deser_val)
Definition: helpers.h:43
static void write(Stream &stream, const FixedSizeSimple &v)
uint32_t serializationLength(const T &t)
int32_t length_to_report
TEST(Serialization, string)
void deserialize(Stream &stream, T &t)
ros::WallTime t
static uint32_t serializedLength(const FixedSizeSimple &)
static uint32_t serializedLength(const VariableSize &v)


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:30:13