MRPT  2.0.1
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-2020, 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>
17 #include <sstream>
18 
19 using namespace mrpt;
20 using namespace mrpt::obs;
21 using namespace mrpt::io;
22 using namespace mrpt::math;
23 using namespace mrpt::serialization;
24 using namespace std;
25 
26 #define TEST_CLASS_MOVE_COPY_CTORS(_classname) \
27  template class mrpt::CTraitsTest<_classname>
28 
44 #if MRPT_HAS_OPENCV // These classes need CImage serialization
47 #endif
54 
56  // Observations:
65 #if MRPT_HAS_OPENCV // These classes need CImage serialization
67 #endif
70  // Actions:
72 
73 // Create a set of classes, then serialize and deserialize to test possible
74 // bugs:
75 TEST(Observations, WriteReadToMem)
76 {
77  for (auto& cl : lstClasses)
78  {
79  try
80  {
81  CMemoryStream buf;
82  auto arch = mrpt::serialization::archiveFrom(buf);
83  {
84  auto o =
85  mrpt::ptr_cast<CSerializable>::from(cl->createObject());
86  arch << *o;
87  o.reset();
88  }
89 
90  CSerializable::Ptr recons;
91  buf.Seek(0);
92  arch >> recons;
93  }
94  catch (const std::exception& e)
95  {
96  GTEST_FAIL() << "Exception during serialization test for class '"
97  << cl->className << "':\n"
98  << e.what() << endl;
99  }
100  }
101 }
102 
103 // Also try to convert them to octect vectors:
104 TEST(Observations, WriteReadToOctectVectors)
105 {
106  for (auto& cl : lstClasses)
107  {
108  try
109  {
110  std::vector<uint8_t> buf;
111  {
112  auto o =
113  mrpt::ptr_cast<CSerializable>::from(cl->createObject());
115  o.reset();
116  }
117 
118  CSerializable::Ptr recons;
120  }
121  catch (const std::exception& e)
122  {
123  GTEST_FAIL() << "Exception during serialization test for class '"
124  << cl->className << "':\n"
125  << e.what() << endl;
126  }
127  }
128 }
129 
130 static bool aux_get_sample_data(mrpt::obs::CObservation&) { return false; }
131 static bool aux_get_sample_data(mrpt::obs::CAction&) { return false; }
132 
134 {
136  return true;
137 }
139 {
141  return true;
142 }
144 {
147  return true;
148 }
149 
150 // Try to invoke a copy ctor and = operator:
151 template <class T>
152 void run_copy_tests()
153 {
154  std::stringstream ss;
155  {
156  auto ptr_org = T::Create();
157  auto ptr_copy_op = T::Create();
158  *ptr_copy_op = *ptr_org; // copy op
159  ptr_org.reset();
160  // make sure the copy works without erroneous mem accesses,etc.
161  ptr_copy_op->getDescriptionAsText(ss);
162  }
163  {
164  auto ptr_org = T::Create();
165  auto ptr_copy_ctor = T::Create(*ptr_org); // copy ctor
166  ptr_org.reset();
167  // make sure the copy works without erroneous mem accesses,etc.
168  ptr_copy_ctor->getDescriptionAsText(ss);
169  }
170  // deep copy tests via serialization:
171  // 1st round: default object state after default ctors
172  // 2nd round: with an example dataset, if present.
173  for (int round = 0; round < 2; round++)
174  {
175  CMemoryStream buf;
176  auto arch = mrpt::serialization::archiveFrom(buf);
177  T obj1;
178 
179  if (round == 1)
180  if (!aux_get_sample_data(obj1)) break;
181 
182  arch << obj1;
183  buf.Seek(0);
184 
185  T obj2;
186  arch >> obj2;
187 
188  // Check they are identical:
189  std::stringstream ss1, ss2;
190  obj1.getDescriptionAsText(ss1);
191  obj2.getDescriptionAsText(ss2);
192 
193  EXPECT_EQ(ss1.str(), ss2.str())
194  << "className: " << obj1.className << "\n";
195  }
196 }
197 
198 TEST(Observations, CopyCtorAssignOp)
199 {
200  run_copy_tests<CObservation2DRangeScan>();
201  run_copy_tests<CObservation3DRangeScan>();
202  run_copy_tests<CObservationGPS>();
203  run_copy_tests<CObservationIMU>();
204  run_copy_tests<CObservationOdometry>();
205  run_copy_tests<CObservationRGBD360>();
206  run_copy_tests<CObservationBearingRange>();
207  run_copy_tests<CObservationBatteryState>();
208  run_copy_tests<CObservationWirelessPower>();
209  run_copy_tests<CObservationRFID>();
210  run_copy_tests<CObservationBeaconRanges>();
211  run_copy_tests<CObservationComment>();
212  run_copy_tests<CObservationGasSensors>();
213  run_copy_tests<CObservationReflectivity>();
214  run_copy_tests<CObservationRange>();
215 #if MRPT_HAS_OPENCV // These classes need CImage serialization
216  run_copy_tests<CObservationImage>();
217  run_copy_tests<CObservationStereoImages>();
218 #endif
219  run_copy_tests<CObservationCANBusJ1939>();
220  run_copy_tests<CObservationRawDAQ>();
221  run_copy_tests<CObservation6DFeatures>();
222  run_copy_tests<CObservationVelodyneScan>();
223  run_copy_tests<CActionRobotMovement2D>();
224  run_copy_tests<CActionRobotMovement3D>();
225 }
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...
mrpt::img::CImage imageLeft
Image from the left camera (this image will be ALWAYS present)
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.
void example2DRangeScan(mrpt::obs::CObservation2DRangeScan &s, int i=0)
Example 2D lidar scans (form a venerable SICK LMS200).
A structure that holds runtime class type information.
Definition: CObject.h:31
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
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.
#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:592
TEST(ICP_SLAM_App, MapFromRawlog_PointMap)
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:102
mrpt::img::CImage image
The image captured by the camera, that is, the main piece of information of this observation.
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.
static bool aux_get_sample_data(mrpt::obs::CObservation &)
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.
Declares a class for storing a robot action.
Definition: CAction.h:24
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...
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
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...
EXPECT_EQ(out.image_pair_was_used.size(), NUM_IMGS)
static CAST_TO::Ptr from(const CAST_FROM_PTR &ptr)
Definition: CObject.h:356
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...
void exampleImage(mrpt::img::CImage &im, int i=0)
Example images (an 800x640 image pair from a Bumblebee 1) Implemented indices: 0,1.
mrpt::img::CImage imageRight
Image from the right camera, only contains a valid image if hasImageRight == true.
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:24



Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020