MRPT  1.9.9
CSerializable_unittest.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #define MRPT_NO_WARN_BIG_HDR // Yes, we really want to include all classes.
11 #include <mrpt/obs.h>
12 
13 #include <CTraitsTest.h>
14 #include <gtest/gtest.h>
15 #include <mrpt/io/CMemoryStream.h>
16 #include <sstream>
17 
18 using namespace mrpt;
19 using namespace mrpt::obs;
20 using namespace mrpt::io;
21 using namespace mrpt::math;
22 using namespace mrpt::serialization;
23 using namespace std;
24 
25 #define TEST_CLASS_MOVE_COPY_CTORS(_classname) \
26  template class mrpt::CTraitsTest<_classname>
27 
43 #if MRPT_HAS_OPENCV // These classes need CImage serialization
46 #endif
53 
55  // Observations:
64 #if MRPT_HAS_OPENCV // These classes need CImage serialization
66 #endif
69  // Actions:
71 
72 // Create a set of classes, then serialize and deserialize to test possible
73 // bugs:
74 TEST(Observations, WriteReadToMem)
75 {
76  for (auto& cl : lstClasses)
77  {
78  try
79  {
80  CMemoryStream buf;
81  auto arch = mrpt::serialization::archiveFrom(buf);
82  {
83  auto o =
84  mrpt::ptr_cast<CSerializable>::from(cl->createObject());
85  arch << *o;
86  o.reset();
87  }
88 
89  CSerializable::Ptr recons;
90  buf.Seek(0);
91  arch >> recons;
92  }
93  catch (const std::exception& e)
94  {
95  GTEST_FAIL() << "Exception during serialization test for class '"
96  << cl->className << "':\n"
97  << e.what() << endl;
98  }
99  }
100 }
101 
102 // Also try to convert them to octect vectors:
103 TEST(Observations, WriteReadToOctectVectors)
104 {
105  for (auto& cl : lstClasses)
106  {
107  try
108  {
109  std::vector<uint8_t> buf;
110  {
111  auto o =
112  mrpt::ptr_cast<CSerializable>::from(cl->createObject());
114  o.reset();
115  }
116 
117  CSerializable::Ptr recons;
119  }
120  catch (const std::exception& e)
121  {
122  GTEST_FAIL() << "Exception during serialization test for class '"
123  << cl->className << "':\n"
124  << e.what() << endl;
125  }
126  }
127 }
128 
129 // Try to invoke a copy ctor and = operator:
130 template <class T>
131 void run_copy_tests()
132 {
133  std::stringstream ss;
134  {
135  auto ptr_org = T::Create();
136  auto ptr_copy_op = T::Create();
137  *ptr_copy_op = *ptr_org; // copy op
138  ptr_org.reset();
139  // make sure the copy works without erroneous mem accesses,etc.
140  ptr_copy_op->getDescriptionAsText(ss);
141  }
142  {
143  auto ptr_org = T::Create();
144  auto ptr_copy_ctor = T::Create(*ptr_org); // copy ctor
145  ptr_org.reset();
146  // make sure the copy works without erroneous mem accesses,etc.
147  ptr_copy_ctor->getDescriptionAsText(ss);
148  }
149 }
150 
151 TEST(Observations, CopyCtorAssignOp)
152 {
153  run_copy_tests<CObservation2DRangeScan>();
154  run_copy_tests<CObservation3DRangeScan>();
155  run_copy_tests<CObservationGPS>();
156  run_copy_tests<CObservationIMU>();
157  run_copy_tests<CObservationOdometry>();
158 }
This "observation" is actually a placeholder for a text block with comments or additional parameters ...
Declares a class derived from "CObservation" that encapsules an image from a camera, whose relative pose to robot is also stored.
This represents a measurement of the batteries on the robot.
Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from...
Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters.
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
This class stores a message from a CAN BUS with the protocol J1939.
void ObjectToOctetVector(const CSerializable *o, std::vector< uint8_t > &out_vector)
Converts (serializes) an MRPT object into an array of bytes.
A structure that holds runtime class type information.
Definition: CObject.h:31
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
Declares a class derived from "CObservation" that represents one (or more) range measurements to labe...
Declares a class derived from "CObservation" that encapsules a single short-range reflectivity measur...
STL namespace.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
TEST(NodeletsTests, pub_sub_multithread_test)
#define TEST_CLASS_MOVE_COPY_CTORS(_classname)
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT&#39;s CStream, std::istream, std::ostream, std::stringstream.
Definition: CArchive.h:586
Represents a probabilistic 3D (6D) movement.
Represents a probabilistic 2D movement of the robot mobile base.
This base provides a set of functions for maths stuff.
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
Definition: CObject.h:89
void OctetVectorToObject(const std::vector< uint8_t > &in_data, CSerializable::Ptr &obj)
Converts back (de-serializes) a sequence of binary data into a MRPT object, without prior information...
This CStream derived class allow using a memory buffer as a CStream.
uint64_t Seek(int64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) override
Introduces a pure virtual method for moving to a specified position in the streamed resource...
Observation class for either a pair of left+right or left+disparity images from a stereo camera...
This namespace contains representation of robot actions and observations.
Declares a class derived from "CObservation" that represents a set of readings from gas sensors...
Store raw data from a Data Acquisition (DAQ) device, such that input or output analog and digital cha...
This represents a measurement of the wireless strength perceived by the robot.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
An observation of one or more "features" or "objects", possibly identified with a unique ID...
This observation represents a number of range-bearing value pairs, each one for a detected landmark...
static CAST_TO::Ptr from(const CAST_FROM_PTR &ptr)
Definition: CObject.h:366
const mrpt::rtti::TRuntimeClassId * lstClasses[]
This represents one or more RFID tags observed by a receiver.
An observation of the current (cumulative) odometry for a wheeled robot.
This class stores messages from GNSS or GNSS+IMU devices, from consumer-grade inexpensive GPS receive...



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019