Main MRPT website > C++ reference
MRPT logo
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions
mrpt::poses::CPosePDF Class Referenceabstract

Detailed Description

Declares a class that represents a probability density function (pdf) of a 2D pose (x,y,phi).

This class is just the base class for unifying many diferent ways this pdf can be implemented.

For convenience, a pose composition is also defined for any pdf derived class, changeCoordinatesReference, in the form of a method rather than an operator.

See also the tutorial on probabilistic spatial representations in the MRPT.

See also
CPose2D, CPose3DPDF, CPoseRandomSampler

Definition at line 41 of file CPosePDF.h.

#include <mrpt/poses/CPosePDF.h>

Inheritance diagram for mrpt::poses::CPosePDF:
Inheritance graph
[legend]

Public Types

enum  { is_3D_val = 0 }
 
enum  { is_PDF_val = 1 }
 
typedef CPose2D type_value
 The type of the state the PDF represents. More...
 

Public Member Functions

virtual void copyFrom (const CPosePDF &o)=0
 Copy operator, translating if necesary (for example, between particles and gaussian representations) More...
 
virtual void bayesianFusion (const CPosePDF &p1, const CPosePDF &p2, const double &minMahalanobisDistToDrop=0)=0
 Bayesian fusion of two pose distributions (product of two distributions->new distribution), then save the result in this object (WARNING: See implementing classes to see classes that can and cannot be mixtured!) More...
 
virtual void inverse (CPosePDF &o) const =0
 Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF. More...
 
template<class OPENGL_SETOFOBJECTSPTR >
void getAs3DObject (OPENGL_SETOFOBJECTSPTR &out_obj) const
 Returns a 3D representation of this PDF (it doesn't clear the current contents of out_obj, but append new OpenGL objects to that list) More...
 
template<class OPENGL_SETOFOBJECTSPTR >
OPENGL_SETOFOBJECTSPTR getAs3DObject () const
 Returns a 3D representation of this PDF. More...
 
virtual CObject * duplicate () const =0
 Returns a copy of the object, indepently of its class. More...
 
mrpt::utils::CObjectPtr 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...
 
CObject * clone () const
 Cloning interface for smart pointers. More...
 
virtual void getMean (CPose2D &mean_point) const=0
 Returns the mean, or mathematical expectation of the probability density distribution (PDF). More...
 
virtual void getCovarianceAndMean (CMatrixFixedNumeric< double, STATE_LEN, STATE_LEN > &cov, CPose2D &mean_point) const=0
 Returns an estimate of the pose covariance matrix (STATE_LENxSTATE_LEN cov matrix) and the mean, both at once. More...
 
void getCovarianceDynAndMean (CMatrixDouble &cov, CPose2D &mean_point) const
 Returns an estimate of the pose covariance matrix (STATE_LENxSTATE_LEN cov matrix) and the mean, both at once. More...
 
CPose2D getMeanVal () const
 Returns the mean, or mathematical expectation of the probability density distribution (PDF). More...
 
void getCovariance (CMatrixDouble &cov) const
 Returns the estimate of the covariance matrix (STATE_LEN x STATE_LEN covariance matrix) More...
 
void getCovariance (CMatrixFixedNumeric< double, STATE_LEN, STATE_LEN > &cov) const
 Returns the estimate of the covariance matrix (STATE_LEN x STATE_LEN covariance matrix) More...
 
CMatrixFixedNumeric< double, STATE_LEN, STATE_LEN > getCovariance () const
 Returns the estimate of the covariance matrix (STATE_LEN x STATE_LEN covariance matrix) More...
 
virtual void getInformationMatrix (CMatrixFixedNumeric< double, STATE_LEN, STATE_LEN > &inf) const
 Returns the information (inverse covariance) matrix (a STATE_LEN x STATE_LEN matrix) Unless reimplemented in derived classes, this method first reads the covariance, then invert it. More...
 
virtual void saveToTextFile (const std::string &file) const=0
 Save PDF's particles to a text file. More...
 
virtual void drawSingleSample (CPose2D &outPart) const=0
 Draws a single sample from the distribution. More...
 
virtual void drawManySamples (size_t N, std::vector< vector_double > &outSamples) const
 Draws a number of samples from the distribution, and saves as a list of 1xSTATE_LEN vectors, where each row contains a (x,y,z,yaw,pitch,roll) datum. More...
 
virtual void changeCoordinatesReference (const mrpt::poses::CPose3D &newReferenceBase)=0
 this = p (+) this. More...
 
double getCovarianceEntropy () const
 Compute the entropy of the estimated covariance matrix. More...
 

Static Public Member Functions

static void jacobiansPoseComposition (const CPose2D &x, const CPose2D &u, CMatrixDouble33 &df_dx, CMatrixDouble33 &df_du, const bool compute_df_dx=true, const bool compute_df_du=true)
 This static method computes the pose composition Jacobians, with these formulas: More...
 
static void jacobiansPoseComposition (const CPosePDFGaussian &x, const CPosePDFGaussian &u, CMatrixDouble33 &df_dx, CMatrixDouble33 &df_du)
 
static bool is_3D ()
 
static bool is_PDF ()
 

Static Public Attributes

static const mrpt::utils::TRuntimeClassId classCObject
 
static const size_t state_length
 The length of the variable, for example, 3 for a 3D point, 6 for a 3D pose (x y z yaw pitch roll). More...
 
RTTI stuff
static const mrpt::utils::TRuntimeClassId classCSerializable
 

Protected Member Functions

virtual void writeToStream (mrpt::utils::CStream &out, int *getVersion) const =0
 Introduces a pure virtual method responsible for writing to a CStream. More...
 
virtual void readFromStream (mrpt::utils::CStream &in, int version)=0
 Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More...
 

RTTI stuff

static const mrpt::utils::TRuntimeClassId classCPosePDF
 
class mrpt::utils::CStream
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const
 Returns information about the class of an object in runtime. More...
 

Member Typedef Documentation

◆ type_value

The type of the state the PDF represents.

Definition at line 35 of file CProbabilityDensityFunction.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
is_3D_val 

Definition at line 93 of file CPosePDF.h.

◆ anonymous enum

anonymous enum
Enumerator
is_PDF_val 

Definition at line 95 of file CPosePDF.h.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId* mrpt::poses::CPosePDF::_GetBaseClass ( )
staticprotected

◆ bayesianFusion()

virtual void mrpt::poses::CPosePDF::bayesianFusion ( const CPosePDF p1,
const CPosePDF p2,
const double &  minMahalanobisDistToDrop = 0 
)
pure virtual

Bayesian fusion of two pose distributions (product of two distributions->new distribution), then save the result in this object (WARNING: See implementing classes to see classes that can and cannot be mixtured!)

Parameters
p1The first distribution to fuse
p2The second distribution to fuse
minMahalanobisDistToDropIf set to different of 0, the result of very separate Gaussian modes (that will result in negligible components) in SOGs will be dropped to reduce the number of modes in the output.

Implemented in mrpt::poses::CPosePDFSOG, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFGaussian, mrpt::poses::CPosePDFParticles, and mrpt::poses::CPosePDFGrid.

◆ changeCoordinatesReference()

virtual void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::changeCoordinatesReference ( const mrpt::poses::CPose3D newReferenceBase)
pure virtualinherited

this = p (+) this.

This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which "to project" the current pdf. Result PDF substituted the currently stored one in the object.

Implemented in mrpt::poses::CPosePDFSOG, mrpt::poses::CPosePDFParticles, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFGaussian, and mrpt::poses::CPosePDFGrid.

◆ clone()

CObject* mrpt::utils::CObject::clone ( ) const
inlineinherited

Cloning interface for smart pointers.

Definition at line 135 of file CObject.h.

◆ copyFrom()

virtual void mrpt::poses::CPosePDF::copyFrom ( const CPosePDF o)
pure virtual

Copy operator, translating if necesary (for example, between particles and gaussian representations)

Implemented in mrpt::poses::CPosePDFSOG, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFGaussian, mrpt::poses::CPosePDFParticles, and mrpt::poses::CPosePDFGrid.

◆ drawManySamples()

virtual void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::drawManySamples ( size_t  N,
std::vector< vector_double > &  outSamples 
) const
inlinevirtualinherited

Draws a number of samples from the distribution, and saves as a list of 1xSTATE_LEN vectors, where each row contains a (x,y,z,yaw,pitch,roll) datum.

This base method just call N times to drawSingleSample, but derived classes should implemented optimized method for each particular PDF.

Definition at line 120 of file CProbabilityDensityFunction.h.

◆ drawSingleSample()

virtual void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::drawSingleSample ( CPose2D outPart) const
pure virtualinherited

Draws a single sample from the distribution.

◆ duplicate()

virtual CObject* mrpt::utils::CObject::duplicate ( ) const
pure virtualinherited

Returns a copy of the object, indepently of its class.

Implemented in mrpt::reactivenav::CLogFileRecord_ND, mrpt::utils::CSimpleDatabase, mrpt::slam::CObservationIMU, mrpt::slam::CObservation3DRangeScan, mrpt::utils::CImage, mrpt::detectors::CDetectable3D, mrpt::hmtslam::THypothesisIDSet, mrpt::slam::COccupancyGridMap2D, mrpt::gui::CDisplayWindow3D, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::hmtslam::CHMTSLAM, mrpt::slam::CHeightGridMap2D, mrpt::poses::CPose3D, mrpt::slam::CMultiMetricMapPDF, mrpt::slam::CMultiMetricMap, mrpt::opengl::COctoMapVoxels, mrpt::slam::CLandmarksMap, mrpt::vision::CFeature, mrpt::opengl::COpenGLViewport, mrpt::poses::CPointPDFParticles, mrpt::slam::CRawlog, mrpt::slam::CSensoryFrame, mrpt::kinematics::CKinematicChain, mrpt::slam::CObservation2DRangeScan, mrpt::poses::CPose3DInterpolator, mrpt::opengl::CPlanarLaserScan, mrpt::slam::CBeaconMap, mrpt::slam::CReflectivityGridMap2D, mrpt::opengl::CPointCloud, mrpt::hmtslam::CLSLAMParticleData, mrpt::opengl::CPointCloudColoured, mrpt::pbmap::Plane, mrpt::detectors::CDetectable2D, mrpt::opengl::COpenGLScene, mrpt::utils::CMHPropertiesValuesList, mrpt::opengl::CFrustum, mrpt::pbmap::PbMap, mrpt::poses::CPose3DRotVec, mrpt::poses::CPose3DQuat, mrpt::opengl::CEllipsoid, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::hmtslam::CHMHMapNode, mrpt::opengl::CAngularObservationMesh, mrpt::slam::CBeacon, mrpt::slam::CObservationStereoImages, mrpt::opengl::CVectorField2D, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::opengl::CText3D, mrpt::slam::CGasConcentrationGridMap2D, mrpt::slam::CObservationStereoImagesFeatures, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CMeshFast, mrpt::slam::CLandmark, mrpt::poses::CPose3DPDFParticles, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::hmtslam::CRobotPosesGraph, mrpt::slam::CWirelessPowerGridMap2D, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CMesh, mrpt::poses::CPosePDFParticles, mrpt::poses::CPosePDFSOG, mrpt::gui::CDisplayWindowPlots, mrpt::slam::COctoMap, mrpt::slam::CObservationImage, mrpt::opengl::CSetOfLines, mrpt::opengl::CText, mrpt::poses::CPose3DPDFGaussian, mrpt::poses::CPose3DPDFGaussianInf, mrpt::opengl::CPolyhedron, mrpt::poses::CPose2D, mrpt::poses::CPosePDFGaussianInf, mrpt::hmtslam::CHierarchicalMHMap, mrpt::slam::CColouredPointsMap, mrpt::slam::CIncrementalMapPartitioner, mrpt::slam::CRBPFParticleData, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::slam::CColouredOctoMap, mrpt::slam::CSimplePointsMap, mrpt::opengl::CBox, mrpt::opengl::CDisk, mrpt::opengl::CSetOfObjects, mrpt::poses::CPose3DPDFSOG, mrpt::poses::CPosePDFGaussian, mrpt::slam::CActionRobotMovement2D, mrpt::slam::CObservationBatteryState, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::math::CMatrixD, mrpt::poses::CPoint3D, mrpt::utils::TCamera, mrpt::slam::CObservationWindSensor, mrpt::slam::CSimpleMap, mrpt::opengl::CArrow, mrpt::opengl::CAxis, mrpt::opengl::CSphere, mrpt::slam::CWeightedPointsMap, mrpt::opengl::CCamera, mrpt::math::CMatrix, mrpt::poses::CPosePDFGrid, mrpt::utils::CStringList, mrpt::slam::CObservationOdometry, mrpt::opengl::CSetOfTexturedTriangles, mrpt::utils::CMemoryChunk, mrpt::slam::CActionCollection, mrpt::slam::CObservationGPS, mrpt::slam::CObservationRange, mrpt::slam::CObservationRawDAQ, mrpt::reactivenav::CLogFileRecord, mrpt::math::CSplineInterpolator1D, mrpt::utils::CPropertiesValuesList, mrpt::gui::CDisplayWindow, mrpt::slam::CObservationBearingRange, mrpt::slam::CObservationGasSensors, mrpt::slam::CObservationWirelessPower, mrpt::opengl::C3DSScene, mrpt::slam::CObservationVisualLandmarks, mrpt::math::CMatrixB, mrpt::poses::CPointPDFGaussian, mrpt::poses::CPoses2DSequence, mrpt::poses::CPoses3DSequence, mrpt::utils::CSimpleDatabaseTable, mrpt::slam::CActionRobotMovement3D, mrpt::slam::CObservationBeaconRanges, mrpt::slam::CObservationComment, mrpt::slam::CObservationRFID, mrpt::opengl::CCylinder, mrpt::opengl::CSetOfTriangles, mrpt::poses::TSimple3DPoint, mrpt::utils::TStereoCamera, mrpt::slam::CObservationReflectivity, mrpt::opengl::CGeneralizedCylinder, mrpt::math::CPolygon, mrpt::poses::CPoint2DPDFGaussian, mrpt::slam::CObservationCANBusJ1939, mrpt::opengl::COpenGLStandardObject, mrpt::opengl::CSimpleLine, mrpt::opengl::CTexturedPlane, mrpt::utils::CTypeSelector, and mrpt::reactivenav::CLogFileRecord_VFF.

◆ duplicateGetSmartPtr()

mrpt::utils::CObjectPtr mrpt::utils::CObject::duplicateGetSmartPtr ( ) const
inlineinherited

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).

Definition at line 132 of file CObject.h.

◆ getAs3DObject() [1/2]

template<class OPENGL_SETOFOBJECTSPTR >
void mrpt::poses::CPosePDF::getAs3DObject ( OPENGL_SETOFOBJECTSPTR &  out_obj) const
inline

Returns a 3D representation of this PDF (it doesn't clear the current contents of out_obj, but append new OpenGL objects to that list)

Note
Needs the mrpt-opengl library, and using mrpt::opengl::CSetOfObjectsPtr as template argument.

Definition at line 102 of file CPosePDF.h.

References mrpt::opengl::posePDF2opengl().

◆ getAs3DObject() [2/2]

template<class OPENGL_SETOFOBJECTSPTR >
OPENGL_SETOFOBJECTSPTR mrpt::poses::CPosePDF::getAs3DObject ( ) const
inline

Returns a 3D representation of this PDF.

Note
Needs the mrpt-opengl library, and using mrpt::opengl::CSetOfObjectsPtr as template argument.

Definition at line 111 of file CPosePDF.h.

References mrpt::opengl::posePDF2opengl().

◆ getCovariance() [1/3]

void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getCovariance ( CMatrixDouble cov) const
inlineinherited

Returns the estimate of the covariance matrix (STATE_LEN x STATE_LEN covariance matrix)

See also
getMean, getCovarianceAndMean, getInformationMatrix

Definition at line 70 of file CProbabilityDensityFunction.h.

References mrpt::math::cov().

◆ getCovariance() [2/3]

void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getCovariance ( CMatrixFixedNumeric< double, STATE_LEN, STATE_LEN > &  cov) const
inlineinherited

Returns the estimate of the covariance matrix (STATE_LEN x STATE_LEN covariance matrix)

See also
getMean, getCovarianceAndMean, getInformationMatrix

Definition at line 79 of file CProbabilityDensityFunction.h.

References mrpt::math::cov().

◆ getCovariance() [3/3]

CMatrixFixedNumeric<double,STATE_LEN,STATE_LEN> mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getCovariance ( ) const
inlineinherited

Returns the estimate of the covariance matrix (STATE_LEN x STATE_LEN covariance matrix)

See also
getMean, getInformationMatrix

Definition at line 88 of file CProbabilityDensityFunction.h.

References mrpt::math::cov(), and mrpt::math::UNINITIALIZED_MATRIX.

◆ getCovarianceAndMean()

virtual void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getCovarianceAndMean ( CMatrixFixedNumeric< double, STATE_LEN, STATE_LEN > &  cov,
CPose2D mean_point 
) const
pure virtualinherited

Returns an estimate of the pose covariance matrix (STATE_LENxSTATE_LEN cov matrix) and the mean, both at once.

See also
getMean, getInformationMatrix

◆ getCovarianceDynAndMean()

void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getCovarianceDynAndMean ( CMatrixDouble cov,
CPose2D mean_point 
) const
inlineinherited

Returns an estimate of the pose covariance matrix (STATE_LENxSTATE_LEN cov matrix) and the mean, both at once.

See also
getMean, getInformationMatrix

Definition at line 50 of file CProbabilityDensityFunction.h.

References mrpt::math::cov(), and mrpt::math::UNINITIALIZED_MATRIX.

◆ getCovarianceEntropy()

double mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getCovarianceEntropy ( ) const
inlineinherited

Compute the entropy of the estimated covariance matrix.

See also
http://en.wikipedia.org/wiki/Multivariate_normal_distribution#Entropy

Definition at line 139 of file CProbabilityDensityFunction.h.

References det().

◆ getInformationMatrix()

virtual void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getInformationMatrix ( CMatrixFixedNumeric< double, STATE_LEN, STATE_LEN > &  inf) const
inlinevirtualinherited

Returns the information (inverse covariance) matrix (a STATE_LEN x STATE_LEN matrix) Unless reimplemented in derived classes, this method first reads the covariance, then invert it.

See also
getMean, getCovarianceAndMean

Definition at line 101 of file CProbabilityDensityFunction.h.

References mrpt::math::cov(), and mrpt::math::UNINITIALIZED_MATRIX.

◆ getMean()

virtual void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getMean ( CPose2D mean_point) const
pure virtualinherited

Returns the mean, or mathematical expectation of the probability density distribution (PDF).

See also
getCovarianceAndMean, getInformationMatrix

◆ getMeanVal()

CPose2D mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::getMeanVal ( ) const
inlineinherited

Returns the mean, or mathematical expectation of the probability density distribution (PDF).

See also
getCovariance, getInformationMatrix

Definition at line 60 of file CProbabilityDensityFunction.h.

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId* mrpt::poses::CPosePDF::GetRuntimeClass ( ) const
virtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::utils::CSerializable.

Reimplemented in mrpt::poses::CPosePDFParticles, mrpt::poses::CPosePDFSOG, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFGaussian, and mrpt::poses::CPosePDFGrid.

◆ inverse()

virtual void mrpt::poses::CPosePDF::inverse ( CPosePDF o) const
pure virtual

◆ is_3D()

static bool mrpt::poses::CPosePDF::is_3D ( )
inlinestatic

Definition at line 94 of file CPosePDF.h.

◆ is_PDF()

static bool mrpt::poses::CPosePDF::is_PDF ( )
inlinestatic

Definition at line 96 of file CPosePDF.h.

◆ jacobiansPoseComposition() [1/2]

static void mrpt::poses::CPosePDF::jacobiansPoseComposition ( const CPose2D x,
const CPose2D u,
CMatrixDouble33 df_dx,
CMatrixDouble33 df_du,
const bool  compute_df_dx = true,
const bool  compute_df_du = true 
)
static

This static method computes the pose composition Jacobians, with these formulas:

df_dx =
[ 1, 0, -sin(phi_x)*x_u-cos(phi_x)*y_u ]
[ 0, 1, cos(phi_x)*x_u-sin(phi_x)*y_u ]
[ 0, 0, 1 ]
df_du =
[ cos(phi_x) , -sin(phi_x) , 0 ]
[ sin(phi_x) , cos(phi_x) , 0 ]
[ 0 , 0 , 1 ]

◆ jacobiansPoseComposition() [2/2]

static void mrpt::poses::CPosePDF::jacobiansPoseComposition ( const CPosePDFGaussian x,
const CPosePDFGaussian u,
CMatrixDouble33 df_dx,
CMatrixDouble33 df_du 
)
static

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ readFromStream()

virtual void mrpt::utils::CSerializable::readFromStream ( mrpt::utils::CStream in,
int  version 
)
protectedpure virtualinherited

Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.

Parameters
inThe input binary stream where the object data must read from.
versionThe version of the object stored in the stream: use this version number in your code to know how to read the incoming data.
Exceptions
std::exceptionOn any error, see CStream::ReadBuffer
See also
CStream

Implemented in mrpt::reactivenav::CLogFileRecord_ND, mrpt::utils::CSimpleDatabase, mrpt::slam::CObservationIMU, mrpt::slam::CObservation3DRangeScan, mrpt::utils::CImage, mrpt::detectors::CDetectable3D, mrpt::hmtslam::THypothesisIDSet, mrpt::slam::COccupancyGridMap2D, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::hmtslam::CHMTSLAM, mrpt::slam::CHeightGridMap2D, mrpt::poses::CPose3D, mrpt::slam::CMultiMetricMapPDF, mrpt::slam::CMultiMetricMap, mrpt::opengl::COctoMapVoxels, mrpt::slam::CLandmarksMap, mrpt::vision::CFeature, mrpt::opengl::COpenGLViewport, mrpt::poses::CPointPDFParticles, mrpt::slam::CRawlog, mrpt::slam::CSensoryFrame, mrpt::kinematics::CKinematicChain, mrpt::slam::CObservation2DRangeScan, mrpt::poses::CPose3DInterpolator, mrpt::opengl::CPlanarLaserScan, mrpt::slam::CBeaconMap, mrpt::slam::CReflectivityGridMap2D, mrpt::opengl::CPointCloud, mrpt::hmtslam::CLSLAMParticleData, mrpt::opengl::CPointCloudColoured, mrpt::pbmap::Plane, mrpt::detectors::CDetectable2D, mrpt::opengl::COpenGLScene, mrpt::utils::CMHPropertiesValuesList, mrpt::opengl::CFrustum, mrpt::pbmap::PbMap, mrpt::poses::CPose3DRotVec, mrpt::poses::CPose3DQuat, mrpt::opengl::CEllipsoid, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::hmtslam::CHMHMapNode, mrpt::opengl::CAngularObservationMesh, mrpt::slam::CBeacon, mrpt::slam::CObservationStereoImages, mrpt::opengl::CVectorField2D, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::opengl::CText3D, mrpt::slam::CGasConcentrationGridMap2D, mrpt::slam::CObservationStereoImagesFeatures, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CMeshFast, mrpt::slam::CLandmark, mrpt::poses::CPose3DPDFParticles, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::hmtslam::CRobotPosesGraph, mrpt::slam::CWirelessPowerGridMap2D, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CMesh, mrpt::poses::CPosePDFParticles, mrpt::poses::CPosePDFSOG, mrpt::slam::COctoMap, mrpt::slam::CObservationImage, mrpt::opengl::CSetOfLines, mrpt::opengl::CText, mrpt::poses::CPose3DPDFGaussian, mrpt::poses::CPose3DPDFGaussianInf, mrpt::opengl::CPolyhedron, mrpt::poses::CPose2D, mrpt::poses::CPosePDFGaussianInf, mrpt::hmtslam::CHierarchicalMHMap, mrpt::slam::CColouredPointsMap, mrpt::slam::CIncrementalMapPartitioner, mrpt::slam::CRBPFParticleData, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::slam::CColouredOctoMap, mrpt::slam::CSimplePointsMap, mrpt::opengl::CBox, mrpt::opengl::CDisk, mrpt::opengl::CSetOfObjects, mrpt::poses::CPose3DPDFSOG, mrpt::poses::CPosePDFGaussian, mrpt::slam::CActionRobotMovement2D, mrpt::slam::CObservationBatteryState, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::math::CMatrixD, mrpt::poses::CPoint3D, mrpt::utils::TCamera, mrpt::slam::CObservationWindSensor, mrpt::slam::CSimpleMap, mrpt::opengl::CArrow, mrpt::opengl::CAxis, mrpt::opengl::CSphere, mrpt::slam::CWeightedPointsMap, mrpt::opengl::CCamera, mrpt::math::CMatrix, mrpt::poses::CPosePDFGrid, mrpt::utils::CStringList, mrpt::slam::CObservationOdometry, mrpt::opengl::CSetOfTexturedTriangles, mrpt::utils::CMemoryChunk, mrpt::slam::CActionCollection, mrpt::slam::CObservationGPS, mrpt::slam::CObservationRange, mrpt::slam::CObservationRawDAQ, mrpt::reactivenav::CLogFileRecord, mrpt::math::CSplineInterpolator1D, mrpt::utils::CPropertiesValuesList, mrpt::slam::CObservationBearingRange, mrpt::slam::CObservationGasSensors, mrpt::slam::CObservationWirelessPower, mrpt::opengl::C3DSScene, mrpt::slam::CObservationVisualLandmarks, mrpt::math::CMatrixB, mrpt::poses::CPointPDFGaussian, mrpt::poses::CPoses2DSequence, mrpt::poses::CPoses3DSequence, mrpt::utils::CSimpleDatabaseTable, mrpt::slam::CActionRobotMovement3D, mrpt::slam::CObservationBeaconRanges, mrpt::slam::CObservationComment, mrpt::slam::CObservationRFID, mrpt::opengl::CCylinder, mrpt::opengl::CSetOfTriangles, mrpt::poses::TSimple3DPoint, mrpt::utils::TStereoCamera, mrpt::slam::CObservationReflectivity, mrpt::opengl::CGeneralizedCylinder, mrpt::math::CPolygon, mrpt::poses::CPoint2DPDFGaussian, mrpt::slam::CObservationCANBusJ1939, mrpt::opengl::COpenGLStandardObject, mrpt::opengl::CSimpleLine, mrpt::opengl::CTexturedPlane, mrpt::utils::CTypeSelector, and mrpt::reactivenav::CLogFileRecord_VFF.

◆ saveToTextFile()

virtual void mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::saveToTextFile ( const std::string &  file) const
pure virtualinherited

Save PDF's particles to a text file.

See derived classes for more information about the format of generated files.

Implemented in mrpt::poses::CPosePDFSOG, mrpt::poses::CPosePDFParticles, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFGaussian, and mrpt::poses::CPosePDFGrid.

◆ writeToStream()

virtual void mrpt::utils::CSerializable::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
protectedpure virtualinherited

Introduces a pure virtual method responsible for writing to a CStream.

This can not be used directly be users, instead use "stream << object;" for writing it to a stream.

Parameters
outThe output binary stream where object must be dumped.
getVersionIf NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data.
Exceptions
std::exceptionOn any error, see CStream::WriteBuffer
See also
CStream

Implemented in mrpt::reactivenav::CLogFileRecord_ND, mrpt::utils::CSimpleDatabase, mrpt::slam::CObservationIMU, mrpt::slam::CObservation3DRangeScan, mrpt::utils::CImage, mrpt::detectors::CDetectable3D, mrpt::hmtslam::THypothesisIDSet, mrpt::slam::COccupancyGridMap2D, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::hmtslam::CHMTSLAM, mrpt::slam::CHeightGridMap2D, mrpt::poses::CPose3D, mrpt::slam::CMultiMetricMapPDF, mrpt::slam::CMultiMetricMap, mrpt::opengl::COctoMapVoxels, mrpt::slam::CLandmarksMap, mrpt::vision::CFeature, mrpt::opengl::COpenGLViewport, mrpt::poses::CPointPDFParticles, mrpt::slam::CRawlog, mrpt::slam::CSensoryFrame, mrpt::kinematics::CKinematicChain, mrpt::slam::CObservation2DRangeScan, mrpt::poses::CPose3DInterpolator, mrpt::opengl::CPlanarLaserScan, mrpt::slam::CBeaconMap, mrpt::slam::CReflectivityGridMap2D, mrpt::opengl::CPointCloud, mrpt::hmtslam::CLSLAMParticleData, mrpt::opengl::CPointCloudColoured, mrpt::pbmap::Plane, mrpt::detectors::CDetectable2D, mrpt::opengl::COpenGLScene, mrpt::utils::CMHPropertiesValuesList, mrpt::opengl::CFrustum, mrpt::pbmap::PbMap, mrpt::poses::CPose3DRotVec, mrpt::poses::CPose3DQuat, mrpt::opengl::CEllipsoid, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::hmtslam::CHMHMapNode, mrpt::opengl::CAngularObservationMesh, mrpt::slam::CBeacon, mrpt::slam::CObservationStereoImages, mrpt::opengl::CVectorField2D, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::opengl::CText3D, mrpt::slam::CGasConcentrationGridMap2D, mrpt::slam::CObservationStereoImagesFeatures, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CMeshFast, mrpt::slam::CLandmark, mrpt::poses::CPose3DPDFParticles, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::hmtslam::CRobotPosesGraph, mrpt::slam::CWirelessPowerGridMap2D, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CMesh, mrpt::poses::CPosePDFParticles, mrpt::poses::CPosePDFSOG, mrpt::slam::COctoMap, mrpt::slam::CObservationImage, mrpt::opengl::CSetOfLines, mrpt::opengl::CText, mrpt::poses::CPose3DPDFGaussian, mrpt::poses::CPose3DPDFGaussianInf, mrpt::opengl::CPolyhedron, mrpt::poses::CPose2D, mrpt::poses::CPosePDFGaussianInf, mrpt::hmtslam::CHierarchicalMHMap, mrpt::slam::CColouredPointsMap, mrpt::slam::CIncrementalMapPartitioner, mrpt::slam::CRBPFParticleData, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::slam::CColouredOctoMap, mrpt::slam::CSimplePointsMap, mrpt::opengl::CBox, mrpt::opengl::CDisk, mrpt::opengl::CSetOfObjects, mrpt::poses::CPose3DPDFSOG, mrpt::poses::CPosePDFGaussian, mrpt::slam::CActionRobotMovement2D, mrpt::slam::CObservationBatteryState, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::math::CMatrixD, mrpt::poses::CPoint3D, mrpt::utils::TCamera, mrpt::slam::CObservationWindSensor, mrpt::slam::CSimpleMap, mrpt::opengl::CArrow, mrpt::opengl::CAxis, mrpt::opengl::CSphere, mrpt::slam::CWeightedPointsMap, mrpt::opengl::CCamera, mrpt::math::CMatrix, mrpt::poses::CPosePDFGrid, mrpt::utils::CStringList, mrpt::slam::CObservationOdometry, mrpt::opengl::CSetOfTexturedTriangles, mrpt::utils::CMemoryChunk, mrpt::slam::CActionCollection, mrpt::slam::CObservationGPS, mrpt::slam::CObservationRange, mrpt::slam::CObservationRawDAQ, mrpt::reactivenav::CLogFileRecord, mrpt::math::CSplineInterpolator1D, mrpt::utils::CPropertiesValuesList, mrpt::slam::CObservationBearingRange, mrpt::slam::CObservationGasSensors, mrpt::slam::CObservationWirelessPower, mrpt::opengl::C3DSScene, mrpt::slam::CObservationVisualLandmarks, mrpt::math::CMatrixB, mrpt::poses::CPointPDFGaussian, mrpt::poses::CPoses2DSequence, mrpt::poses::CPoses3DSequence, mrpt::utils::CSimpleDatabaseTable, mrpt::slam::CActionRobotMovement3D, mrpt::slam::CObservationBeaconRanges, mrpt::slam::CObservationComment, mrpt::slam::CObservationRFID, mrpt::opengl::CCylinder, mrpt::opengl::CSetOfTriangles, mrpt::poses::TSimple3DPoint, mrpt::utils::TStereoCamera, mrpt::slam::CObservationReflectivity, mrpt::opengl::CGeneralizedCylinder, mrpt::math::CPolygon, mrpt::poses::CPoint2DPDFGaussian, mrpt::slam::CObservationCANBusJ1939, mrpt::opengl::COpenGLStandardObject, mrpt::opengl::CSimpleLine, mrpt::opengl::CTexturedPlane, mrpt::utils::CTypeSelector, and mrpt::reactivenav::CLogFileRecord_VFF.

Friends And Related Function Documentation

◆ mrpt::utils::CStream

friend class mrpt::utils::CStream
friend

Definition at line 43 of file CPosePDF.h.

Member Data Documentation

◆ classCObject

const mrpt::utils::TRuntimeClassId mrpt::utils::CObject::classCObject
staticinherited

Definition at line 120 of file CObject.h.

◆ classCPosePDF

const mrpt::utils::TRuntimeClassId mrpt::poses::CPosePDF::classCPosePDF
static

Definition at line 43 of file CPosePDF.h.

◆ classCSerializable

const mrpt::utils::TRuntimeClassId mrpt::utils::CSerializable::classCSerializable
staticinherited

Definition at line 35 of file CSerializable.h.

◆ state_length

const size_t mrpt::utils::CProbabilityDensityFunction< CPose2D , STATE_LEN >::state_length
staticinherited

The length of the variable, for example, 3 for a 3D point, 6 for a 3D pose (x y z yaw pitch roll).

Definition at line 34 of file CProbabilityDensityFunction.h.




Page generated by Doxygen 1.8.14 for MRPT 1.1.0 SVN: at lun oct 28 00:54:49 CET 2019 Hosted on:
SourceForge.net Logo