Back to list of all libraries | See all modules
mrpt-base
This is the most fundamental library in MRPT, since it provides a vast amount of utilities and OS-abstraction classes upon which the rest of MRPT is built. Here resides critical functionality such as mathematics, linear algebra, serialization, smart pointers and multi-threading. l This library comprises classes in a number of namespaces, briefly described below (click on the namespaces names to see the complete list of its classes):
A comprehensive collection of geometry-related classes to represent all kind of 2D and 3D geomtry transformations in different formats (Euler angles, rotation matrices, quaternions), as well as networks of pose constrains (as used typically in SLAM problems).
There are also implemented representations for probability distributions over all of these transformations, in a generic way that allow mono and multi-modal Gaussians and particle-based representations.
See mrpt::poses for the complete list of classes here.
RTTI (RunTime Type Information): A cross-platform, compiler-independent RTTI system is built around the base class mrpt::utils::CObject.
Smart pointers: Based on std::shared_ptr<>, any class CFoo inheriting from CObject, automatically has associated smart pointers types CFoo::Ptr and CFoo::ConstPtr. MRPT implements advanced smart pointers capable of multi-thread safe usage and smart pointer typecasting with runtime check for correct castings (tutorial]).
Image handling: The class mrpt::utils::CImage represents a wrapper around OpenCV IplImage's, plus extra functionality such as on-the-fly loading of images stored in disk upon first usage. The internal IplImage is always available so OpenCV's functions can be still used to operate on MRPT images.
Serialization/Persistence: Object serialization in a simple but powerful (including versioning) format is supported by dozens of MRPT classes, all based on mrpt::utils::CSerializable.
Streams: Stream classes (see the base mrpt::utils::CStream) allow serialization of MRPT objects. There are classes for tranparent GZ-compressed files, sockets, serial ports, etc.
XML-based databases: Simple databases can be mantained, loaded and saved to files with mrpt::utils::CSimpleDatabase.
Name-based argument passing: See the structure mrpt::utils::TParameters
Configuration files: There is one base virtual class (mrpt::utils::CConfigFileBase) which can be used to read/write configuration files (including basic types, vectors, matrices,...) from any "configuration source" transparently (an actual configuration file, a text block created on the fly, etc.).
MRPT defines a number of generic math containers, which are:
For a more in-depth description of these types, and their relation to the base Eigen classes, read this page.
Notice that fixed-size containers should be preferred where possible, since they allow more compile-time optimizations.
Apart from the containers, this namespace contains much more functionality:
This namespace includes threading tools such as critical sections, semaphores or utilities such as the template mrpt::synch::CThreadSafeVariable that converts any variable into a pair variable-critical section.
Here can be found functions for filesystem managing, watching directories, creating and handling threads in an OS-independent way, etc.
GZip compression methods can be found in this namespace.
Classes | |
class | mrpt::bayes::CParticleFilter |
This class acts as a common interface to the different interfaces (see CParticleFilter::TParticleFilterAlgorithm) any bayes::CParticleFilterCapable class can implement: it is the invoker of particle filter algorithms. More... | |
class | mrpt::bayes::CParticleFilterCapable |
This virtual class defines the interface that any particles based PDF class must implement in order to be executed by a mrpt::bayes::CParticleFilter. More... | |
struct | mrpt::bayes::CParticleFilterDataImpl< Derived, particle_list_t > |
A curiously recurring template pattern (CRTP) approach to providing the basic functionality of any CParticleFilterData<> class. More... | |
class | mrpt::bayes::CParticleFilterData< T > |
This template class declares the array of particles and its internal data, managing some memory-related issues and providing an easy implementation of virtual methods required for implementing a CParticleFilterCapable. More... | |
struct | mrpt::bayes::CProbabilityParticle< T > |
A template class for holding a the data and the weight of a particle. More... | |
class | mrpt::math::CAtan2LookUpTable |
A look-up-table (LUT) of atan values for any (x,y) value in a square/rectangular grid of predefined resolution. More... | |
class | mrpt::math::CAtan2LookUpTableMultiRes |
Like CAtan2LookUpTable but with a multiresolution grid for increasingly better accuracy in points nearer to the origin. More... | |
class | mrpt::math::CBinaryRelation< T, U, UIsObject > |
This class models a binary relation through the elements of any given set. More... | |
class | mrpt::math::CHistogram |
This class provides an easy way of computing histograms for unidimensional real valued variables. More... | |
class | mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM > |
An implementation of the Levenberg-Marquardt algorithm for least-square minimization. More... | |
class | mrpt::math::CMatrix |
This class is a "CSerializable" wrapper for "CMatrixFloat". More... | |
class | mrpt::math::CMatrixB |
This class is a "CSerializable" wrapper for "CMatrixBool". More... | |
class | mrpt::math::CMatrixD |
This class is a "CSerializable" wrapper for "CMatrixTemplateNumeric<double>". More... | |
class | mrpt::math::CMatrixFixedNumeric< T, NROWS, NCOLS > |
A numeric matrix of compile-time fixed size. More... | |
class | mrpt::math::CMatrixTemplate< T > |
This template class provides the basic functionality for a general 2D any-size, resizable container of numerical or non-numerical elements. More... | |
class | mrpt::math::CMatrixTemplateNumeric< T > |
A matrix of dynamic size. More... | |
class | mrpt::math::CMatrixTemplateObjects< T > |
This template class extends the class "CMatrixTemplate" for storing "objects" at each matrix entry. More... | |
class | mrpt::math::CMonteCarlo< T, NUM, OTHER > |
Montecarlo simulation for experiments in 1D. More... | |
class | mrpt::math::CQuaternion< T > |
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector , or alternatively, q = r + ix + jy + kz. More... | |
class | mrpt::math::CSparseMatrix |
A sparse matrix structure, wrapping T. More... | |
class | mrpt::math::CSparseMatrixTemplate< T > |
A sparse matrix container (with cells of any type), with iterators. More... | |
class | mrpt::math::KDTreeCapable< Derived, num_t, metric_t > |
A generic adaptor class for providing Nearest Neighbor (NN) lookup via the nanoflann library. More... | |
struct | mrpt::math::MatrixBlockSparseCols< Scalar, NROWS, NCOLS, INFO, HAS_REMAP, INDEX_REMAP_MAP_IMPL > |
A templated column-indexed efficient storage of block-sparse Jacobian or Hessian matrices, together with other arbitrary information. More... | |
struct | mrpt::math::RobustKernel< KERNEL_TYPE, T > |
struct | mrpt::math::RobustKernel< rkLeastSquares, T > |
No robust kernel, use standard least squares: rho(r) = r^2. More... | |
struct | mrpt::math::RobustKernel< rkPseudoHuber, T > |
Pseudo-huber robust kernel: rho(r) = 2 * delta^2 * ( -1+sqrt( 1+ r^2/delta^2 ) ) More... | |
class | mrpt::random::CRandomGenerator |
A thred-safe pseudo random number generator, based on an internal MT19937 randomness generator. More... | |
class | mrpt::system::CDirectoryExplorer |
This class allows the enumeration of the files/directories that exist into a given path. More... | |
class | mrpt::system::CFileSystemWatcher |
This class subscribes to notifications of file system changes, thus it can be used to efficiently stay informed about changes in a directory tree. More... | |
class | mrpt::utils::CCanvas |
This virtual class defines the interface of any object accepting drawing primitives on it. More... | |
class | mrpt::utils::CConfigFile |
This class allows loading and storing values and vectors of different types from ".ini" files easily. More... | |
class | mrpt::utils::CConfigFileBase |
This class allows loading and storing values and vectors of different types from a configuration text, which can be implemented as a ".ini" file, a memory-stored string, etc... More... | |
class | mrpt::utils::CConfigFileMemory |
This class implements a config file-like interface over a memory-stored string list. More... | |
class | mrpt::utils::CConfigFilePrefixer |
A wrapper for other CConfigFileBase-based objects that prefixes a given token to every key and/or section. More... | |
class | mrpt::utils::CConsoleRedirector |
By creating an object of this class, all the output to std::cout (and std::cerr) will be redirected to a text file, and optionally also shown on the console. More... | |
class | mrpt::utils::CDynamicGrid< T > |
A 2D grid of dynamic size which stores any kind of data at each cell. More... | |
class | mrpt::utils::CEnhancedMetaFile |
This class represents a Windows Enhanced Meta File (EMF) for generating and saving graphics. More... | |
class | mrpt::utils::CFileGZInputStream |
Transparently opens a compressed "gz" file and reads uncompressed data from it. More... | |
class | mrpt::utils::CFileInputStream |
This CStream derived class allow using a file as a read-only, binary stream. More... | |
class | mrpt::utils::CFileOutputStream |
This CStream derived class allow using a file as a write-only, binary stream. More... | |
class | mrpt::utils::CFileStream |
This CStream derived class allow using a file as a read/write binary stream, creating it if the file didn't exist. More... | |
class | mrpt::utils::CImage |
A class for storing images as grayscale or RGB bitmaps. More... | |
class | mrpt::utils::CListOfClasses |
A list (actually based on a std::set) of MRPT classes, capable of keeping any class registered by the mechanism of CSerializable classes. More... | |
class | mrpt::utils::CLoadableOptions |
This is a virtual base class for sets of options than can be loaded from and/or saved to configuration plain-text files. More... | |
class | mrpt::utils::CMappedImage |
This class encapsulates a MRPT Image and allows the sampling of individual pixels with sub-pixel accuracy and with a change of coordinates (eg, meters). More... | |
class | mrpt::utils::CMemoryChunk |
A memory buffer (implements CStream) which can be itself serialized. More... | |
class | mrpt::utils::CMemoryStream |
This CStream derived class allow using a memory buffer as a CStream. More... | |
class | mrpt::utils::CMessage |
A class that contain generic messages, that can be sent and received from a "CClientTCPSocket" object. More... | |
class | mrpt::utils::CMHPropertiesValuesList |
An arbitrary list of "annotations", or named attributes, each being an instance of any CSerializable object (Multi-hypotheses version). More... | |
struct | mrpt::utils::TRuntimeClassId |
A structure that holds runtime class type information. More... | |
struct | mrpt::utils::CLASSINIT |
Auxiliary structure used for CObject-based RTTI. More... | |
class | mrpt::utils::CObject |
The virtual base class of all MRPT classes with a unified RTTI system. More... | |
struct | mrpt::ptr_cast< CAST_TO > |
Converts a smart pointer Base::Ptr to Derived::Ptr, in a way compatible with MRPT >=1.5.4 and MRPT 2.x series. More... | |
class | mrpt::utils::CObservable |
Inherit from this class for those objects capable of being observed by a CObserver class. More... | |
class | mrpt::utils::CObserver |
Inherit from this class to get notified about events from any CObservable object after subscribing to it. More... | |
class | mrpt::utils::CProbabilityDensityFunction< TDATA, STATE_LEN > |
A generic template for probability density distributions (PDFs). More... | |
class | mrpt::utils::CPropertiesValuesList |
An arbitrary list of "annotations", or named attributes, each being an instance of any CSerializable object. More... | |
class | mrpt::utils::CRateTimer |
A class for calling sleep() in a loop, such that the amount of sleep time will be computed to make the loop run at the desired rate (in Hz). More... | |
class | mrpt::utils::CReferencedMemBlock |
Represents a memory block (via "void*") that can be shared between several objects through copy operator (=). More... | |
class | mrpt::utils::CSerializable |
The virtual base class which provides a unified interface for all persistent objects in MRPT. More... | |
class | mrpt::utils::CSimpleDatabaseTable |
This class implements the tables of databases. More... | |
class | mrpt::utils::CStdOutStream |
This CStdOutStream derived class allow printing to standard out, normally the console text output. More... | |
class | mrpt::utils::CStream |
This base class is used to provide a unified interface to files,memory buffers,..Please see the derived classes. More... | |
class | mrpt::utils::CStringList |
A class for storing a list of text lines. More... | |
class | mrpt::utils::CTextFileLinesParser |
A class for parsing text files, returning each non-empty and non-comment line, along its line number. More... | |
class | mrpt::utils::CThreadSafeQueue< T > |
A thread-safe template queue for object passing between threads; for a template argument of T, the objects being passed in the queue are "T*". More... | |
class | mrpt::utils::CTicTac |
This class implements a high-performance stopwatch. More... | |
class | mrpt::utils::CTimeLogger |
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats. More... | |
struct | mrpt::utils::CTimeLoggerEntry |
A safe way to call enter() and leave() of a mrpt::utils::CTimeLogger upon construction and destruction of this auxiliary object, making sure that leave() will be called upon exceptions, etc. More... | |
class | mrpt::utils::CTypeSelector |
This class represents a std::string derived class which is also CSerializable. More... | |
class | mrpt::utils::CMRPTException |
The base for MRPT-especific exceptions. More... | |
class | mrpt::utils::mrptEvent |
The basic event type for the observer-observable pattern in MRPT. More... | |
class | mrpt::utils::mrptEventOnDestroy |
An event sent by any CObservable object (automatically) just before being destroyed and telling its observers to unsubscribe. More... | |
struct | mrpt::utils::pimpl< T > |
Pointer to IMPLementation auxiliary structure to make raw pointers movable, copiable and automatically deleted. More... | |
class | mrpt::utils::PLY_Importer |
A virtual base class that implements the capability of importing 3D point clouds and faces from a file in the Stanford PLY format. More... | |
class | mrpt::utils::PLY_Exporter |
A virtual base class that implements the capability of exporting 3D point clouds and faces to a file in the Stanford PLY format. More... | |
struct | mrpt::utils::safe_ptr_basic< T > |
A wrapper class for pointers that can be safely copied with "=" operator without problems. More... | |
struct | mrpt::utils::safe_ptr< T > |
A wrapper class for pointers that can be safely copied with "=" operator without problems. More... | |
struct | mrpt::utils::non_copiable_ptr_basic< T > |
A wrapper class for pointers that can NOT be copied with "=" operator, raising an exception at runtime if a copy is attempted. More... | |
struct | mrpt::utils::non_copiable_ptr< T > |
A wrapper class for pointers that can NOT be copied with "=" operator, raising an exception at runtime if a copy is attempted. More... | |
struct | mrpt::utils::ignored_copy_ptr< T > |
A wrapper class for pointers whose copy operations from other objects of the same type are ignored, that is, doing "a=b;" has no effect neiter on "a" or "b". More... | |
struct | mrpt::utils::copiable_NULL_ptr_basic< T > |
A wrapper class for pointers that, if copied with the "=" operator, should be set to nullptr in the copy. More... | |
struct | mrpt::utils::copiable_NULL_ptr< T > |
A wrapper class for pointers that, if copied with the "=" operator, should be set to nullptr in the new copy. More... | |
class | mrpt::utils::TCamera |
Structure to hold the parameters of a pinhole camera model. More... | |
struct | mrpt::utils::TColor |
A RGB color - 8bit. More... | |
struct | mrpt::utils::TColorf |
A RGB color - floats in the range [0,1]. More... | |
struct | mrpt::utils::TEnumTypeFiller< ENUMTYPE > |
Only specializations of this class are defined for each enum type of interest. More... | |
struct | mrpt::utils::TEnumType< ENUMTYPE > |
A helper class that can convert an enum value into its textual representation, and viceversa. More... | |
struct | mrpt::utils::TMatchingPair |
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3D. More... | |
class | mrpt::utils::TMatchingPairList |
A list of TMatchingPair. More... | |
struct | mrpt::utils::TParameters< T > |
For usage when passing a dynamic number of (numeric) arguments to a function, by name. More... | |
Namespaces | |
mrpt::bayes | |
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorithms. | |
mrpt::compress | |
Data compression/decompression algorithms. | |
mrpt::math::jacobians | |
A collection of functions to compute jacobians of diverse transformations, etc (some functions are redirections to existing methods elsewhere, so this namespace is actually used with grouping purposes). | |
mrpt::math | |
This base provides a set of functions for maths stuff. | |
mrpt::random | |
A namespace of pseudo-random numbers genrators of diferent distributions. | |
mrpt::system | |
This namespace provides a OS-independent interface to many useful functions: filenames manipulation, time and date, string parsing, file I/O, threading, memory allocation, etc. | |
mrpt::system::os | |
This namespace provides a OS-independent interface to low-level functions. | |
mrpt::utils | |
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL. | |
Macros | |
#define | CFileGZOutputStream CFileOutputStream |
Saves data to a file and transparently compress the data using the given compression level. More... | |
Typedefs | |
typedef CThreadSafeQueue< CMessage > | mrpt::utils::CMessageQueue |
A thread-safe class for message passing between threads. More... | |
Enumerations | |
enum | mrpt::math::TRobustKernelType { mrpt::math::rkLeastSquares = 0, mrpt::math::rkPseudoHuber } |
The different types of kernels for usage within a robustified least-squares estimator. More... | |
enum | mrpt::utils::TInterpolationMethod { mrpt::utils::IMG_INTERP_NN = 0, mrpt::utils::IMG_INTERP_LINEAR = 1, mrpt::utils::IMG_INTERP_CUBIC = 2, mrpt::utils::IMG_INTERP_AREA = 3 } |
Interpolation methods for images. More... | |
Functions | |
PIMPL_FORWARD_DECLARATION (namespace exprtk { template< typename T > class expression;}) namespace mrpt | |
template<typename T , class... Args> | |
std::shared_ptr< T > | mrpt::make_aligned_shared (Args &&... args) |
Creates a shared_ptr with 16-byte aligned memory. More... | |
RTTI classes and functions | |
mrpt::utils::CObject::Ptr | mrpt::utils::CObject::duplicateGetSmartPtr () const |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More... | |
Parsing of textfiles with poses | |
template<class POSE_T > | |
void | mrpt::utils::readFileWithPoses (const std::string &fname, std::vector< POSE_T > *poses_vec, std::vector< mrpt::system::TTimeStamp > *timestamps=NULL, bool substract_init_offset=false) |
Parse the textfile and fill in the corresponding poses vector. More... | |
#define CFileGZOutputStream CFileOutputStream |
Saves data to a file and transparently compress the data using the given compression level.
The generated files are in gzip format ("file.gz"). This class requires compiling MRPT with wxWidgets. If wxWidgets is not available then the class is actually mapped to the standard CFileOutputStream
Definition at line 29 of file CFileGZOutputStream.h.
Referenced by mrpt::compress::zip::compress_gz_file(), mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::nav::CAbstractPTGBasedReactive::enableLogFile(), mrpt::hmtslam::CHMTSLAM::generateLogFiles(), mrpt::obs::CObservation3DRangeScan::points3D_convertToExternalStorage(), mrpt::obs::CObservation3DRangeScan::rangeImage_convertToExternalStorage(), mrpt::maps::CGasConcentrationGridMap2D::save_Gaussian_Wind_Grid_To_File(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::saveColGridsToFile(), mrpt::slam::CMetricMapBuilder::saveCurrentMapToFile(), mrpt::pbmap::PbMap::savePbMap(), mrpt::maps::CSimpleMap::saveToFile(), mrpt::opengl::COpenGLScene::saveToFile(), and mrpt::obs::CRawlog::saveToRawLogFile().
A thread-safe class for message passing between threads.
Definition at line 22 of file CMessageQueue.h.
The different types of kernels for usage within a robustified least-squares estimator.
Enumerator | |
---|---|
rkLeastSquares | No robust kernel, use standard least squares: rho(r)= 1/2 * r^2. |
rkPseudoHuber | Pseudo-huber robust kernel. |
Definition at line 26 of file robust_kernels.h.
|
inline |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer).
A smart pointer to a CObject object.
Definition at line 179 of file CObject.h.
References mrpt::utils::CObject::clone().
Referenced by mrpt::obs::CRawlog::addActions(), mrpt::slam::CIncrementalMapPartitioner::addMapFrame(), and mrpt::obs::CRawlog::addObservations().
std::shared_ptr<T> mrpt::make_aligned_shared | ( | Args &&... | args | ) |
Creates a shared_ptr
with 16-byte aligned memory.
Definition at line 68 of file aligned_allocator.h.
Referenced by mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), and mrpt::nav::CNavigatorManualSequence::loadConfigFile().
PIMPL_FORWARD_DECLARATION | ( | namespace exprtk { template< typename T > class expression;} | ) |
A wrapper of exprtk
runtime expression compiler: it takes a string representing an expression (from a simple mathematical formula to a complete program), compiles it and evaluates its result as many times as required. The result will change as the "variables" appearing in the expression (hold and managed by the user of this object) change.
Refer to exprtk documentation for reference on supported formulas, control flow instructions, etc.
This wrapper is provided to reduce the (very large) compilation time and memory required by the original library, at the cost of only exposing the most commonly used part of its API:
double
are supported.std::map
container or pointers to user-stored variables.See examples of usage in the unit test file.
Default ctor
Initializes the object by compiling an expression.
std::runtime_error | On any syntax error or undefined symbol while compiling the expression. The e.what() message describes what is exactly the problem. |
[in] The expression to be compiled.
[in] Map of variables/constants by name
-> value
. The references to the values in this map must be ensured to be valid thoughout all the life of the compiled expression.
A descriptive name of this formula, to be used when generating error reports via an exception, if needed
Can be used before calling compile() to register additional variables by means of pointers instead of a std::map
[in] Map of variables/constants by name
-> value
. The references to the values in this map must be ensured to be valid thoughout all the life of the compiled expression.
Evaluates the current value of the precompiled formula.
std::runtime_error | If the formula has not been compiled yet. |
Returns true if compile() was called and ended without errors.
Returns the original formula passed to compile(), or an empty string if still not compiled.
Access raw exprtk expression object.
Access raw exprtk expression object.
Definition at line 16 of file CRuntimeCompiledExpression.h.
void mrpt::utils::readFileWithPoses | ( | const std::string & | fname, |
std::vector< POSE_T > * | poses_vec, | ||
std::vector< mrpt::system::TTimeStamp > * | timestamps = NULL , |
||
bool | substract_init_offset = false |
||
) |
Parse the textfile and fill in the corresponding poses vector.
The file to be parsed is to contain 2D or 3D poses along with their corresponding timestamps, one line for each.
The expected format is the following:
For 2D Poses: timestamp x y theta (in rad) For 3D Poses in RPY form : x y z yaw pitch roll For 3D Poses in Quaternion form : x y z qw qx qy qz For 3D Poses in Quaternion form [TUM Datasets] : x y z qx qy qz qw
The 2D format abides to the groundtruth file format used by the GridMapNavSimul application
The TUM format is compatible with the groundtruth format for the TUM RGBD datasets as generated by the * rgbd_dataset2rawlog MRPT tool.
[in] | fname | Filename from which the timestamps and poses are read |
[out] | poses_vec | std::vector which is to contain the 2D poses. |
[out] | timestamps | std::vector which is to contain the timestamps for the corresponding ground truth poses. Ignore this argument if timestamps are not needed. |
[in] | substract_init_offset | If true, the filled poses are to start from 0, that means, that if the first found pose is non-zero, it's going to be considered and offset and substracted from all poses in the file. |
Definition at line 138 of file pose_utils.h.
References ASSERTMSG_, mrpt::utils::CFileInputStream::close(), mrpt::system::fileExists(), mrpt::utils::CFileInputStream::fileOpenCorrectly(), mrpt::format(), mrpt::utils::internal::getPoseFromString(), MRPT_END, MRPT_START, and mrpt::utils::CFileInputStream::readLine().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019 |