Main MRPT website > C++ reference
MRPT logo
Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions

mrpt::poses::CPose3DQuatPDFGaussian Class Reference


Detailed Description

Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion $ p(\mathbf{x}) = [x ~ y ~ z ~ qr ~ qx ~ qy ~ qz]^\top $.

This class implements that PDF using a mono-modal Gaussian distribution. See mrpt::poses::CPose3DQuatPDF for more details, or mrpt::poses::CPose3DPDF for classes based on Euler angles instead.

Uncertainty of pose composition operations ( $ y = x \oplus u $) is implemented in the methods "CPose3DQuatPDFGaussian::operator+=" and "CPose3DQuatPDFGaussian::jacobiansPoseComposition".

For further details on implemented methods and the theory behind them, see this report.

See also:
CPose3DQuat, CPose3DQuatPDF, CPose3DPDF

Definition at line 57 of file CPose3DQuatPDFGaussian.h.

#include <mrpt/poses/CPose3DQuatPDFGaussian.h>

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

List of all members.

Public Member Functions

 CPose3DQuatPDFGaussian ()
 Default constructor - set all values to zero.
 CPose3DQuatPDFGaussian (TConstructorFlags_Quaternions constructor_dummy_param)
 Constructor which left all the member uninitialized, for using when speed is critical - as argument, use UNINITIALIZED_QUATERNION.
 CPose3DQuatPDFGaussian (const CPose3DQuat &init_Mean)
 Constructor from a default mean value, covariance equals to zero.
 CPose3DQuatPDFGaussian (const CPose3DQuat &init_Mean, const CMatrixDouble77 &init_Cov)
 Constructor with mean and covariance.
 CPose3DQuatPDFGaussian (const CPosePDFGaussian &o)
 Constructor from a Gaussian 2D pose PDF (sets to 0 the missing variables).
 CPose3DQuatPDFGaussian (const CPose3DPDFGaussian &o)
 Constructor from an equivalent Gaussian in Euler angles representation.
void getMean (CPose3DQuat &mean_pose) const
 Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF).
void getCovarianceAndMean (CMatrixDouble77 &cov, CPose3DQuat &mean_point) const
 Returns an estimate of the pose covariance matrix (7x7 cov matrix) and the mean, both at once.
void copyFrom (const CPose3DQuatPDF &o)
 Copy operator, translating if necesary (for example, between particles and gaussian representations)
void copyFrom (const CPosePDF &o)
 Copy operator, translating if necesary (for example, between particles and gaussian representations)
void copyFrom (const CPose3DPDFGaussian &o)
 Copy operator, translating if necesary (for example, between particles and gaussian representations)
void saveToTextFile (const std::string &file) const
 Save the PDF to a text file, containing the 3D pose in the first line (x y z qr qx qy qz), then the covariance matrix in the next 7 lines.
void changeCoordinatesReference (const CPose3DQuat &newReferenceBase)
 This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which "to project" the current pdf.
void changeCoordinatesReference (const CPose3D &newReferenceBase)
 This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which "to project" the current pdf.
void drawSingleSample (CPose3DQuat &outPart) const
 Draws a single sample from the distribution.
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 1x7 vectors, where each row contains a (x,y,z,qr,qx,qy,qz) datum.
void bayesianFusion (const CPose3DQuatPDF &p1, const CPose3DQuatPDF &p2)
 Bayesian fusion of two points gauss.
void inverse (CPose3DQuatPDF &o) const
 Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF.
CPose3DQuatPDFGaussian operator- () const
 Unary - operator, returns the PDF of the inverse pose.
void operator+= (const CPose3DQuat &Ap)
 Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the mean, and the covariance matrix are updated).
void operator+= (const CPose3DQuatPDFGaussian &Ap)
 Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the mean, and the covariance matrix are updated) (see formulas in jacobiansPoseComposition ).
void operator-= (const CPose3DQuatPDFGaussian &Ap)
 Makes: thisPDF = thisPDF - Ap, where "-" is pose inverse composition (both the mean, and the covariance matrix are updated).
double evaluatePDF (const CPose3DQuat &x) const
 Evaluates the PDF at a given point.
double evaluateNormalizedPDF (const CPose3DQuat &x) const
 Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,1].
double mahalanobisDistanceTo (const CPose3DQuatPDFGaussian &theOther)
 Computes the Mahalanobis distance between the centers of two Gaussians.

Static Public Member Functions

static void jacobiansPoseComposition (const CPose3DQuat &x, const CPose3DQuat &u, CMatrixDouble77 &df_dx, CMatrixDouble77 &df_du, CPose3DQuat *out_x_oplus_u=NULL)
 This static method computes the two Jacobians of a pose composition operation $f(x,u)= x u$.

Public Attributes

CPose3DQuat mean
 The mean value.
CMatrixDouble77 cov
 The 7x7 covariance matrix.

Protected Member Functions

void assureSymmetry ()
 Assures the symmetry of the covariance matrix (eventually certain operations in the math-coprocessor lead to non-symmetric matrixes!)

RTTI stuff

typedef CPose3DQuatPDFGaussianPtr SmartPtr
static mrpt::utils::CLASSINIT _init_CPose3DQuatPDFGaussian
static mrpt::utils::TRuntimeClassId classCPose3DQuatPDFGaussian
static const
mrpt::utils::TRuntimeClassId
classinfo
static const
mrpt::utils::TRuntimeClassId
_GetBaseClass ()
virtual const
mrpt::utils::TRuntimeClassId
GetRuntimeClass () const
 Returns information about the class of an object in runtime.
virtual mrpt::utils::CObjectduplicate () const
 Returns a copy of the object, indepently of its class.
static mrpt::utils::CObjectCreateObject ()
static CPose3DQuatPDFGaussianPtr Create ()

Member Typedef Documentation

A typedef for the associated smart pointer

Definition at line 60 of file CPose3DQuatPDFGaussian.h.


Constructor & Destructor Documentation

mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian ( )

Default constructor - set all values to zero.

mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian ( TConstructorFlags_Quaternions  constructor_dummy_param)

Constructor which left all the member uninitialized, for using when speed is critical - as argument, use UNINITIALIZED_QUATERNION.

mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian ( const CPose3DQuat init_Mean) [explicit]

Constructor from a default mean value, covariance equals to zero.

mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian ( const CPose3DQuat init_Mean,
const CMatrixDouble77 init_Cov 
)

Constructor with mean and covariance.

mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian ( const CPosePDFGaussian o) [explicit]

Constructor from a Gaussian 2D pose PDF (sets to 0 the missing variables).

mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian ( const CPose3DPDFGaussian o) [explicit]

Constructor from an equivalent Gaussian in Euler angles representation.


Member Function Documentation

static const mrpt::utils::TRuntimeClassId* mrpt::poses::CPose3DQuatPDFGaussian::_GetBaseClass ( ) [static, protected]

Reimplemented from mrpt::poses::CPose3DQuatPDF.

void mrpt::poses::CPose3DQuatPDFGaussian::assureSymmetry ( ) [protected]

Assures the symmetry of the covariance matrix (eventually certain operations in the math-coprocessor lead to non-symmetric matrixes!)

void mrpt::poses::CPose3DQuatPDFGaussian::bayesianFusion ( const CPose3DQuatPDF p1,
const CPose3DQuatPDF p2 
) [virtual]

Bayesian fusion of two points gauss.

distributions, then save the result in this object. The process is as follows:

  • (x1,S1): Mean and variance of the p1 distribution.
  • (x2,S2): Mean and variance of the p2 distribution.
  • (x,S): Mean and variance of the resulting distribution.

S = (S1-1 + S2-1)-1; x = S * ( S1-1*x1 + S2-1*x2 );

Implements mrpt::poses::CPose3DQuatPDF.

void mrpt::poses::CPose3DQuatPDFGaussian::changeCoordinatesReference ( const CPose3DQuat newReferenceBase)

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.

void mrpt::poses::CPose3DQuatPDFGaussian::changeCoordinatesReference ( const CPose3D newReferenceBase) [virtual]

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.

Implements mrpt::utils::CProbabilityDensityFunction< CPose3DQuat, 7 >.

void mrpt::poses::CPose3DQuatPDFGaussian::copyFrom ( const CPose3DQuatPDF o) [virtual]

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

Implements mrpt::poses::CPose3DQuatPDF.

void mrpt::poses::CPose3DQuatPDFGaussian::copyFrom ( const CPosePDF o)

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

void mrpt::poses::CPose3DQuatPDFGaussian::copyFrom ( const CPose3DPDFGaussian o)

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

static CPose3DQuatPDFGaussianPtr mrpt::poses::CPose3DQuatPDFGaussian::Create ( ) [static]
static mrpt::utils::CObject* mrpt::poses::CPose3DQuatPDFGaussian::CreateObject ( ) [static]
void mrpt::poses::CPose3DQuatPDFGaussian::drawManySamples ( size_t  N,
std::vector< vector_double > &  outSamples 
) const [virtual]

Draws a number of samples from the distribution, and saves as a list of 1x7 vectors, where each row contains a (x,y,z,qr,qx,qy,qz) datum.

Reimplemented from mrpt::utils::CProbabilityDensityFunction< CPose3DQuat, 7 >.

void mrpt::poses::CPose3DQuatPDFGaussian::drawSingleSample ( CPose3DQuat outPart) const [virtual]

Draws a single sample from the distribution.

Implements mrpt::utils::CProbabilityDensityFunction< CPose3DQuat, 7 >.

virtual mrpt::utils::CObject* mrpt::poses::CPose3DQuatPDFGaussian::duplicate ( ) const [virtual]

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

Implements mrpt::utils::CObject.

double mrpt::poses::CPose3DQuatPDFGaussian::evaluateNormalizedPDF ( const CPose3DQuat x) const

Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,1].

double mrpt::poses::CPose3DQuatPDFGaussian::evaluatePDF ( const CPose3DQuat x) const

Evaluates the PDF at a given point.

void mrpt::poses::CPose3DQuatPDFGaussian::getCovarianceAndMean ( CMatrixDouble77 cov,
CPose3DQuat mean_point 
) const

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

See also:
getMean
void mrpt::poses::CPose3DQuatPDFGaussian::getMean ( CPose3DQuat mean_pose) const [virtual]

Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF).

See also:
getCovariance

Implements mrpt::utils::CProbabilityDensityFunction< CPose3DQuat, 7 >.

virtual const mrpt::utils::TRuntimeClassId* mrpt::poses::CPose3DQuatPDFGaussian::GetRuntimeClass ( ) const [virtual]

Returns information about the class of an object in runtime.

Reimplemented from mrpt::poses::CPose3DQuatPDF.

void mrpt::poses::CPose3DQuatPDFGaussian::inverse ( CPose3DQuatPDF o) const [virtual]

Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF.

Implements mrpt::poses::CPose3DQuatPDF.

static void mrpt::poses::CPose3DQuatPDFGaussian::jacobiansPoseComposition ( const CPose3DQuat x,
const CPose3DQuat u,
CMatrixDouble77 df_dx,
CMatrixDouble77 df_du,
CPose3DQuat out_x_oplus_u = NULL 
) [static]

This static method computes the two Jacobians of a pose composition operation $f(x,u)= x u$.

Parameters:
out_x_oplus_uIf set to !=NULL, the result of "x+u" will be stored here (it will be computed internally anyway). To see the mathematical derivation of the formulas, refer to the technical report here:

double mrpt::poses::CPose3DQuatPDFGaussian::mahalanobisDistanceTo ( const CPose3DQuatPDFGaussian theOther)

Computes the Mahalanobis distance between the centers of two Gaussians.

The variables with a variance exactly equal to 0 are not taken into account in the process, but "infinity" is returned if the corresponding elements are not exactly equal.

void mrpt::poses::CPose3DQuatPDFGaussian::operator+= ( const CPose3DQuatPDFGaussian Ap)

Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the mean, and the covariance matrix are updated) (see formulas in jacobiansPoseComposition ).

void mrpt::poses::CPose3DQuatPDFGaussian::operator+= ( const CPose3DQuat Ap)

Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the mean, and the covariance matrix are updated).

CPose3DQuatPDFGaussian mrpt::poses::CPose3DQuatPDFGaussian::operator- ( ) const [inline]

Unary - operator, returns the PDF of the inverse pose.

Definition at line 152 of file CPose3DQuatPDFGaussian.h.

References inverse(), and mrpt::math::UNINITIALIZED_QUATERNION.

void mrpt::poses::CPose3DQuatPDFGaussian::operator-= ( const CPose3DQuatPDFGaussian Ap)

Makes: thisPDF = thisPDF - Ap, where "-" is pose inverse composition (both the mean, and the covariance matrix are updated).

void mrpt::poses::CPose3DQuatPDFGaussian::saveToTextFile ( const std::string &  file) const [virtual]

Save the PDF to a text file, containing the 3D pose in the first line (x y z qr qx qy qz), then the covariance matrix in the next 7 lines.

Implements mrpt::utils::CProbabilityDensityFunction< CPose3DQuat, 7 >.


Member Data Documentation

Definition at line 60 of file CPose3DQuatPDFGaussian.h.

Definition at line 60 of file CPose3DQuatPDFGaussian.h.

Definition at line 60 of file CPose3DQuatPDFGaussian.h.

The 7x7 covariance matrix.

Definition at line 90 of file CPose3DQuatPDFGaussian.h.

The mean value.

Definition at line 87 of file CPose3DQuatPDFGaussian.h.




Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN:exported at Tue Jan 25 21:56:31 UTC 2011