Main MRPT website > C++ reference for MRPT 1.4.0
CPose3DQuatPDFGaussian.h
Go to the documentation of this file.
1/* +---------------------------------------------------------------------------+
2 | Mobile Robot Programming Toolkit (MRPT) |
3 | http://www.mrpt.org/ |
4 | |
5 | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6 | See: http://www.mrpt.org/Authors - All rights reserved. |
7 | Released under BSD License. See details in http://www.mrpt.org/License |
8 +---------------------------------------------------------------------------+ */
9#ifndef CPose3DQuatPDFGaussian_H
10#define CPose3DQuatPDFGaussian_H
11
14#include <mrpt/poses/CPosePDF.h>
15#include <mrpt/math/CMatrixD.h>
16
17namespace mrpt
18{
19namespace poses
20{
21 class CPosePDFGaussian;
23
25
26 /** Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion \f$ p(\mathbf{x}) = [x ~ y ~ z ~ qr ~ qx ~ qy ~ qz]^\top \f$.
27 *
28 * This class implements that PDF using a mono-modal Gaussian distribution. See mrpt::poses::CPose3DQuatPDF for more details, or
29 * mrpt::poses::CPose3DPDF for classes based on Euler angles instead.
30 *
31 * Uncertainty of pose composition operations (\f$ y = x \oplus u \f$) is implemented in the methods "CPose3DQuatPDFGaussian::operator+=" and "CPose3DQuatPDF::jacobiansPoseComposition".
32 *
33 * For further details on implemented methods and the theory behind them,
34 * see <a href="http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty" >this report</a>.
35 *
36 * \sa CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussianInf
37 * \ingroup poses_pdf_grp
38 */
40 {
41 // This must be added to any CSerializable derived class:
43
44 protected:
45 /** Assures the symmetry of the covariance matrix (eventually certain operations in the math-coprocessor lead to non-symmetric matrixes!)
46 */
48
49 public:
50 /** Default constructor - set all values to zero. */
52
53 /** Constructor which left all the member uninitialized, for using when speed is critical - as argument, use UNINITIALIZED_QUATERNION. */
55
56 /** Constructor from a default mean value, covariance equals to zero. */
57 explicit CPose3DQuatPDFGaussian( const CPose3DQuat &init_Mean );
58
59 /** Constructor with mean and covariance. */
61
62 /** Constructor from a Gaussian 2D pose PDF (sets to 0 the missing variables). */
64
65 /** Constructor from an equivalent Gaussian in Euler angles representation. */
67
68
69 CPose3DQuat mean; //!< The mean value
70 mrpt::math::CMatrixDouble77 cov; //!< The 7x7 covariance matrix
71
72 inline const CPose3DQuat & getPoseMean() const { return mean; }
73 inline CPose3DQuat & getPoseMean() { return mean; }
74
75 void getMean(CPose3DQuat &mean_pose) const MRPT_OVERRIDE; //!< Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF). \sa getCovariance
76 void getCovarianceAndMean(mrpt::math::CMatrixDouble77 &cov,CPose3DQuat &mean_point) const MRPT_OVERRIDE; //!< Returns an estimate of the pose covariance matrix (7x7 cov matrix) and the mean, both at once. \sa getMean
77 void copyFrom(const CPose3DQuatPDF &o) MRPT_OVERRIDE; //!< Copy operator, translating if necesary (for example, between particles and gaussian representations)
78 void copyFrom(const CPosePDF &o); //!< Copy operator, translating if necesary (for example, between particles and gaussian representations)
79 void copyFrom(const CPose3DPDFGaussian &o); //!< Copy operator, translating if necesary (for example, between particles and gaussian representations)
80 void saveToTextFile(const std::string &file) const MRPT_OVERRIDE; //!< 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.
81
82 /** this = p (+) this. This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which
83 * "to project" the current pdf. Result PDF substituted the currently stored one in the object. */
84 void changeCoordinatesReference( const CPose3DQuat &newReferenceBase );
85
86 /** this = p (+) this. This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which
87 * "to project" the current pdf. Result PDF substituted the currently stored one in the object.
88 */
89 void changeCoordinatesReference( const CPose3D &newReferenceBase ) MRPT_OVERRIDE;
90
91 void drawSingleSample( CPose3DQuat &outPart ) const MRPT_OVERRIDE;//!< Draws a single sample from the distribution
92 void drawManySamples( size_t N, std::vector<mrpt::math::CVectorDouble> & outSamples ) const MRPT_OVERRIDE; //!< 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.
93 void inverse(CPose3DQuatPDF &o) const MRPT_OVERRIDE; //!< Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF
94
95 /** Unary - operator, returns the PDF of the inverse pose. */
97 {
99 this->inverse(p);
100 return p;
101 }
102
103 void operator += ( const CPose3DQuat &Ap); //!< Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the mean, and the covariance matrix are updated).
104 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 ).
105 void operator -= ( const CPose3DQuatPDFGaussian &Ap); //!< Makes: thisPDF = thisPDF - Ap, where "-" is pose inverse composition (both the mean, and the covariance matrix are updated).
106
107 double evaluatePDF( const CPose3DQuat &x ) const; //!< Evaluates the PDF at a given point.
108
109 double evaluateNormalizedPDF( const CPose3DQuat &x ) const; //!< Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,1].
110
111 /** Computes the Mahalanobis distance between the centers of two Gaussians.
112 * The variables with a variance exactly equal to 0 are not taken into account in the process, but
113 * "infinity" is returned if the corresponding elements are not exactly equal. */
115
116 }; // End of class def.
118
119
120 bool BASE_IMPEXP operator==(const CPose3DQuatPDFGaussian &p1,const CPose3DQuatPDFGaussian &p2);
121 /** Pose composition for two 3D pose Gaussians \sa CPose3DQuatPDFGaussian::operator += */
123 /** Inverse pose composition for two 3D pose Gaussians \sa CPose3DQuatPDFGaussian::operator -= */
125
126 /** Dumps the mean and covariance matrix to a text stream. */
127 std::ostream BASE_IMPEXP & operator << (std::ostream & out, const CPose3DQuatPDFGaussian& obj);
128
129 } // End of namespace
130
131 namespace global_settings
132 {
133 /** If set to true (default), a Scaled Unscented Transform is used instead of a linear approximation with Jacobians.
134 * Affects to:
135 * - CPose3DQuatPDFGaussian::copyFrom(const CPose3DPDFGaussian &o)
136 * - CPose3DQuatPDFGaussianInf::copyFrom(const CPose3DPDFGaussianInf &o)
137 */
138 extern BASE_IMPEXP bool USE_SUT_EULER2QUAT_CONVERSION;
139 }
140
141} // End of namespace
142
143#endif
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE(class_name, base_name)
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE(class_name, base_name)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
A numeric matrix of compile-time fixed size.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:73
Declares a class that represents a Probability Density function (PDF) of a 3D pose .
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,...
Definition: CPose3DQuat.h:42
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...
void getMean(CPose3DQuat &mean_pose) const MRPT_OVERRIDE
Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF).
CPose3DQuatPDFGaussian()
Default constructor - set all values to zero.
void changeCoordinatesReference(const CPose3D &newReferenceBase) MRPT_OVERRIDE
this = p (+) this.
CPose3DQuatPDFGaussian(const CPosePDFGaussian &o)
Constructor from a Gaussian 2D pose PDF (sets to 0 the missing variables).
mrpt::math::CMatrixDouble77 cov
The 7x7 covariance matrix.
void drawManySamples(size_t N, std::vector< mrpt::math::CVectorDouble > &outSamples) const MRPT_OVERRIDE
Draws a number of samples from the distribution, and saves as a list of 1x7 vectors,...
void drawSingleSample(CPose3DQuat &outPart) const MRPT_OVERRIDE
Draws a single sample from the distribution.
double mahalanobisDistanceTo(const CPose3DQuatPDFGaussian &theOther)
Computes the Mahalanobis distance between the centers of two Gaussians.
void assureSymmetry()
Assures the symmetry of the covariance matrix (eventually certain operations in the math-coprocessor ...
void inverse(CPose3DQuatPDF &o) const MRPT_OVERRIDE
Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF.
CPose3DQuatPDFGaussian(mrpt::math::TConstructorFlags_Quaternions constructor_dummy_param)
Constructor which left all the member uninitialized, for using when speed is critical - as argument,...
void copyFrom(const CPosePDF &o)
Copy operator, translating if necesary (for example, between particles and gaussian representations)
double evaluateNormalizedPDF(const CPose3DQuat &x) const
Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,...
void copyFrom(const CPose3DQuatPDF &o) MRPT_OVERRIDE
Copy operator, translating if necesary (for example, between particles and gaussian representations)
void changeCoordinatesReference(const CPose3DQuat &newReferenceBase)
this = p (+) this.
CPose3DQuatPDFGaussian(const CPose3DPDFGaussian &o)
Constructor from an equivalent Gaussian in Euler angles representation.
CPose3DQuatPDFGaussian(const CPose3DQuat &init_Mean, const mrpt::math::CMatrixDouble77 &init_Cov)
Constructor with mean and covariance.
void saveToTextFile(const std::string &file) const MRPT_OVERRIDE
Save the PDF to a text file, containing the 3D pose in the first line (x y z qr qx qy qz),...
CPose3DQuatPDFGaussian(const CPose3DQuat &init_Mean)
Constructor from a default mean value, covariance equals to zero.
double evaluatePDF(const CPose3DQuat &x) const
Evaluates the PDF at a given point.
void getCovarianceAndMean(mrpt::math::CMatrixDouble77 &cov, CPose3DQuat &mean_point) const MRPT_OVERRIDE
Returns an estimate of the pose covariance matrix (7x7 cov matrix) and the mean, both at once.
const CPose3DQuat & getPoseMean() const
void copyFrom(const CPose3DPDFGaussian &o)
Copy operator, translating if necesary (for example, between particles and gaussian representations)
Declares a class that represents a Probability Density Function (PDF) of a 3D pose (6D actually),...
Declares a class that represents a Probability Density function (PDF) of a 2D pose .
Declares a class that represents a probability density function (pdf) of a 2D pose (x,...
Definition: CPosePDF.h:40
EIGEN_STRONG_INLINE double mean() const
Computes the mean of the entire matrix.
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Definition: mrpt_macros.h:28
TConstructorFlags_Quaternions
Definition: CQuaternion.h:22
@ UNINITIALIZED_QUATERNION
Definition: CQuaternion.h:23
CPose2D BASE_IMPEXP operator-(const CPose2D &p)
Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...
class BASE_IMPEXP CPose3DPDFGaussian
class BASE_IMPEXP CPosePDFGaussian
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
STL namespace.



Page generated by Doxygen 1.9.5 for MRPT 1.4.0 SVN: at Sun Nov 27 03:17:04 UTC 2022