10 #define MRPT_NO_WARN_BIG_HDR // Yes, we really want to include all classes. 15 #include <CTraitsTest.h> 16 #include <gtest/gtest.h> 27 #define TEST_CLASS_MOVE_COPY_CTORS(_classname) \ 28 template class mrpt::CTraitsTest<_classname> 51 TEST(SerializeTestMaps, WriteReadToMem)
80 lstClasse->createObject());
89 catch (
const std::exception& e)
91 GTEST_FAIL() <<
"Exception during serialization test for class '" 92 << lstClasse->className <<
"':\n" Digital Elevation Model (DEM), a mesh or grid representation of a surface which keeps the estimated h...
An observation from any sensor that can be summarized as a pointcloud.
A structure that holds runtime class type information.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
A 2D grid map representing the reflectivity of the environment (for example, measured with an IR prox...
#define TEST_CLASS_MOVE_COPY_CTORS(_classname)
CWirelessPowerGridMap2D represents a PDF of wifi concentrations over a 2D area.
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT's CStream, std::istream, std::ostream, std::stringstream.
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
This CStream derived class allow using a memory buffer as a CStream.
A smart look-up-table (LUT) of sin/cos values for 2D laser scans.
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 namespace contains representation of robot actions and observations.
A class for storing a map of 3D probabilistic beacons, using a Montecarlo, Gaussian, or Sum of Gaussians (SOG) representation (for range-only SLAM).
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
A map of 2D/3D points with individual colours (RGB).
A map of 3D points with reflectance/intensity (float).
A 3D occupancy grid map with a regular, even distribution of voxels.
A class for storing an occupancy grid map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CRandomFieldGridMap3D represents a 3D regular grid where each voxel is associated one real-valued pro...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
static CAST_TO::Ptr from(const CAST_FROM_PTR &ptr)
const mrpt::rtti::TRuntimeClassId * lstClasses[]
CGasConcentrationGridMap2D represents a PDF of gas concentrations over a 2D area. ...
A CObservation-derived class for raw range data from a 2D or 3D rotating scanner. ...
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
TEST(SerializeTestMaps, WriteReadToMem)
The class for storing individual "beacon landmarks" under a variety of 3D position PDF distributions...