Go to the documentation of this file.
10 #define MRPT_NO_WARN_BIG_HDR // Yes, we really want to include all classes.
13 #include <CTraitsTest.h>
14 #include <gtest/gtest.h>
26 #define TEST_CLASS_MOVE_COPY_CTORS(_classname) \
27 template class mrpt::CTraitsTest<_classname>
44 #if MRPT_HAS_OPENCV // These classes need CImage serialization
65 #if MRPT_HAS_OPENCV // These classes need CImage serialization
75 TEST(Observations, WriteReadToMem)
94 catch (
const std::exception& e)
96 GTEST_FAIL() <<
"Exception during serialization test for class '"
97 << cl->className <<
"':\n"
104 TEST(Observations, WriteReadToOctectVectors)
110 std::vector<uint8_t> buf;
121 catch (
const std::exception& e)
123 GTEST_FAIL() <<
"Exception during serialization test for class '"
124 << cl->className <<
"':\n"
154 std::stringstream ss;
156 auto ptr_org = T::Create();
157 auto ptr_copy_op = T::Create();
158 *ptr_copy_op = *ptr_org;
161 ptr_copy_op->getDescriptionAsText(ss);
164 auto ptr_org = T::Create();
165 auto ptr_copy_ctor = T::Create(*ptr_org);
168 ptr_copy_ctor->getDescriptionAsText(ss);
189 std::stringstream ss1, ss2;
190 obj1.getDescriptionAsText(ss1);
191 obj2.getDescriptionAsText(ss2);
194 <<
"className: " << obj1.className <<
"\n";
198 TEST(Observations, CopyCtorAssignOp)
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>();
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>();
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.
This represents a measurement of the batteries on the robot.
This represents a measurement of the wireless strength perceived by the robot.
A structure that holds runtime class type information.
Store raw data from a Data Acquisition (DAQ) device, such that input or output analog and digital cha...
std::shared_ptr< CSerializable > Ptr
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
TEST(ICP_SLAM_App, MapFromRawlog_PointMap)
Declares a class derived from "CObservation" that encapsules a single short-range reflectivity measur...
Represents a probabilistic 3D (6D) movement.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
mrpt::img::CImage image
The image captured by the camera, that is, the main piece of information of this observation.
Represents a probabilistic 2D movement of the robot mobile base.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
mrpt::img::CImage imageRight
Image from the right camera, only contains a valid image if hasImageRight == true.
This namespace contains representation of robot actions and observations.
An observation of the current (cumulative) odometry for a wheeled robot.
Declares a class derived from "CObservation" that represents one (or more) range measurements to labe...
mrpt::img::CImage imageLeft
Image from the left camera (this image will be ALWAYS present)
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
int round(const T value)
Returns the closer integer (int) to x.
static CAST_TO::Ptr from(const CAST_FROM_PTR &ptr)
An observation of one or more "features" or "objects", possibly identified with a unique ID,...
EXPECT_EQ(out.image_pair_was_used.size(), NUM_IMGS)
This observation represents a number of range-bearing value pairs, each one for a detected landmark,...
This class stores a message from a CAN BUS with the protocol J1939.
This CStream derived class allow using a memory buffer as a CStream.
static bool aux_get_sample_data(mrpt::obs::CObservation &)
Declares a class derived from "CObservation" that encapsules a single range measurement,...
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...
Declares a class derived from "CObservation" that represents a set of readings from gas sensors.
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT's CStream,...
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
This class stores messages from GNSS or GNSS+IMU devices, from consumer-grade inexpensive GPS receive...
void example2DRangeScan(mrpt::obs::CObservation2DRangeScan &s, int i=0)
Example 2D lidar scans (form a venerable SICK LMS200).
This represents one or more RFID tags observed by a receiver.
Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from...
const mrpt::rtti::TRuntimeClassId * lstClasses[]
Declares a class that represents any robot's observation.
This base provides a set of functions for maths stuff.
void ObjectToOctetVector(const CSerializable *o, std::vector< uint8_t > &out_vector)
Converts (serializes) an MRPT object into an array of bytes.
Declares a class for storing a robot action.
void exampleImage(mrpt::img::CImage &im, int i=0)
Example images (an 800x640 image pair from a Bumblebee 1) Implemented indices: 0,1.
Declares a class derived from "CObservation" that encapsules an image from a camera,...
Observation class for either a pair of left+right or left+disparity images from a stereo camera.
#define TEST_CLASS_MOVE_COPY_CTORS(_classname)
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Fri Jul 17 08:43:33 UTC 2020 | |