Go to the documentation of this file.
10 #define MRPT_NO_WARN_BIG_HDR // Yes, we really want to include all classes.
14 #include <gtest/gtest.h>
15 #include <CTraitsTest.h>
25 #define TEST_CLASS_MOVE_COPY_CTORS(_classname) \
26 template class mrpt::CTraitsTest<_classname>
43 #if MRPT_HAS_OPENCV // These classes need CImage serialization
64 #if MRPT_HAS_OPENCV // These classes need CImage serialization
74 TEST(Observations, WriteReadToMem)
93 catch (std::exception& e)
95 GTEST_FAIL() <<
"Exception during serialization test for class '"
103 TEST(Observations, WriteReadToOctectVectors)
109 std::vector<uint8_t> buf;
120 catch (std::exception& e)
122 GTEST_FAIL() <<
"Exception during serialization test for class '"
133 std::stringstream ss;
135 auto ptr_org = T::Create();
136 auto ptr_copy_op = T::Create();
137 *ptr_copy_op = *ptr_org;
140 ptr_copy_op->getDescriptionAsText(ss);
143 auto ptr_org = T::Create();
144 auto ptr_copy_ctor = T::Create(*ptr_org);
147 ptr_copy_ctor->getDescriptionAsText(ss);
151 TEST(Observations, CopyCtorAssignOp)
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>();
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...
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.
Represents a probabilistic 2D movement of the robot mobile base.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
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...
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
An observation of one or more "features" or "objects", possibly identified with a unique ID,...
The virtual base class which provides a unified interface for all persistent objects in MRPT.
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.
mrpt::rtti::CObject * createObject() const
This CStream derived class allow using a memory buffer as a CStream.
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...
TEST(SocketTests, send_receive_object)
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[]
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 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 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |