Main MRPT website > C++ reference for MRPT 1.9.9
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-2018, 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 
13 #include <mrpt/poses/CPose3DPDF.h>
14 #include <mrpt/poses/CPosePDF.h>
15 #include <mrpt/math/CMatrixD.h>
16 
17 namespace mrpt
18 {
19 namespace poses
20 {
21 class CPosePDFGaussian;
22 class CPose3DPDFGaussian;
23 
24 /** Declares a class that represents a Probability Density function (PDF) of a
25  * 3D pose using a quaternion \f$ p(\mathbf{x}) = [x ~ y ~ z ~ qr ~ qx ~ qy ~
26  * qz]^\top \f$.
27  *
28  * This class implements that PDF using a mono-modal Gaussian distribution.
29  * See mrpt::poses::CPose3DQuatPDF for more details, or
30  * mrpt::poses::CPose3DPDF for classes based on Euler angles instead.
31  *
32  * Uncertainty of pose composition operations (\f$ y = x \oplus u \f$) is
33  * implemented in the methods "CPose3DQuatPDFGaussian::operator+=" and
34  * "CPose3DQuatPDF::jacobiansPoseComposition".
35  *
36  * For further details on implemented methods and the theory behind them,
37  * see <a
38  * href="http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty"
39  * >this report</a>.
40  *
41  * \sa CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussianInf
42  * \ingroup poses_pdf_grp
43  */
45 {
47 
48  protected:
49  /** Assures the symmetry of the covariance matrix (eventually certain
50  * operations in the math-coprocessor lead to non-symmetric matrixes!)
51  */
52  void assureSymmetry();
53 
54  public:
55  /** Default constructor - set all values to zero. */
57 
58  /** Constructor which left all the member uninitialized, for using when
59  * speed is critical - as argument, use UNINITIALIZED_QUATERNION. */
61  mrpt::math::TConstructorFlags_Quaternions constructor_dummy_param);
62 
63  /** Constructor from a default mean value, covariance equals to zero. */
64  explicit CPose3DQuatPDFGaussian(const CPose3DQuat& init_Mean);
65 
66  /** Constructor with mean and covariance. */
68  const CPose3DQuat& init_Mean,
69  const mrpt::math::CMatrixDouble77& init_Cov);
70 
71  /** Constructor from a Gaussian 2D pose PDF (sets to 0 the missing
72  * variables). */
73  explicit CPose3DQuatPDFGaussian(const CPosePDFGaussian& o);
74 
75  /** Constructor from an equivalent Gaussian in Euler angles representation.
76  */
77  explicit CPose3DQuatPDFGaussian(const CPose3DPDFGaussian& o);
78 
79  /** The mean value */
81  /** The 7x7 covariance matrix */
83 
84  inline const CPose3DQuat& getPoseMean() const { return mean; }
85  inline CPose3DQuat& getPoseMean() { return mean; }
86  /** Returns an estimate of the pose, (the mean, or mathematical expectation
87  * of the PDF). \sa getCovariance */
88  void getMean(CPose3DQuat& mean_pose) const override;
89  /** Returns an estimate of the pose covariance matrix (7x7 cov matrix) and
90  * the mean, both at once. \sa getMean */
93  CPose3DQuat& mean_point) const override;
94  /** Copy operator, translating if necesary (for example, between particles
95  * and gaussian representations) */
96  void copyFrom(const CPose3DQuatPDF& o) override;
97  /** Copy operator, translating if necesary (for example, between particles
98  * and gaussian representations) */
99  void copyFrom(const CPosePDF& o);
100  /** Copy operator, translating if necesary (for example, between particles
101  * and gaussian representations) */
102  void copyFrom(const CPose3DPDFGaussian& o);
103  /** Save the PDF to a text file, containing the 3D pose in the first line (x
104  * y z qr qx qy qz), then the covariance matrix in the next 7 lines. */
105  bool saveToTextFile(const std::string& file) const override;
106 
107  /** this = p (+) this. This can be used to convert a PDF from local
108  * coordinates to global, providing the point (newReferenceBase) from which
109  * "to project" the current pdf. Result PDF substituted the currently
110  * stored one in the object. */
111  void changeCoordinatesReference(const CPose3DQuat& newReferenceBase);
112 
113  /** this = p (+) this. This can be used to convert a PDF from local
114  * coordinates to global, providing the point (newReferenceBase) from which
115  * "to project" the current pdf. Result PDF substituted the currently
116  * stored one in the object.
117  */
118  void changeCoordinatesReference(const CPose3D& newReferenceBase) override;
119 
120  /** Draws a single sample from the distribution */
121  void drawSingleSample(CPose3DQuat& outPart) const override;
122  /** Draws a number of samples from the distribution, and saves as a list of
123  * 1x7 vectors, where each row contains a (x,y,z,qr,qx,qy,qz) datum. */
124  void drawManySamples(
125  size_t N,
126  std::vector<mrpt::math::CVectorDouble>& outSamples) const override;
127  /** Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF */
128  void inverse(CPose3DQuatPDF& o) const override;
129 
130  /** Unary - operator, returns the PDF of the inverse pose. */
132  {
134  this->inverse(p);
135  return p;
136  }
137 
138  /** Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the
139  * mean, and the covariance matrix are updated). */
140  void operator+=(const CPose3DQuat& Ap);
141  /** Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the
142  * mean, and the covariance matrix are updated) (see formulas in
143  * jacobiansPoseComposition ). */
144  void operator+=(const CPose3DQuatPDFGaussian& Ap);
145  /** Makes: thisPDF = thisPDF - Ap, where "-" is pose inverse composition
146  * (both the mean, and the covariance matrix are updated). */
147  void operator-=(const CPose3DQuatPDFGaussian& Ap);
148 
149  /** Evaluates the PDF at a given point. */
150  double evaluatePDF(const CPose3DQuat& x) const;
151 
152  /** Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in
153  * the range [0,1]. */
154  double evaluateNormalizedPDF(const CPose3DQuat& x) const;
155 
156  /** Computes the Mahalanobis distance between the centers of two Gaussians.
157  * The variables with a variance exactly equal to 0 are not taken into
158  * account in the process, but
159  * "infinity" is returned if the corresponding elements are not exactly
160  * equal. */
161  double mahalanobisDistanceTo(const CPose3DQuatPDFGaussian& theOther);
162 
163 }; // End of class def.
164 
165 bool operator==(
166  const CPose3DQuatPDFGaussian& p1, const CPose3DQuatPDFGaussian& p2);
167 /** Pose composition for two 3D pose Gaussians \sa
168  * CPose3DQuatPDFGaussian::operator += */
169 CPose3DQuatPDFGaussian operator+(
170  const CPose3DQuatPDFGaussian& x, const CPose3DQuatPDFGaussian& u);
171 /** Inverse pose composition for two 3D pose Gaussians \sa
172  * CPose3DQuatPDFGaussian::operator -= */
173 CPose3DQuatPDFGaussian operator-(
174  const CPose3DQuatPDFGaussian& x, const CPose3DQuatPDFGaussian& u);
175 
176 /** Dumps the mean and covariance matrix to a text stream. */
177 std::ostream& operator<<(std::ostream& out, const CPose3DQuatPDFGaussian& obj);
178 
179 } // End of namespace
180 
181 namespace global_settings
182 {
183 /** If set to true (default), a Scaled Unscented Transform is used instead of a
184  *linear approximation with Jacobians.
185  * Affects to:
186  * - CPose3DQuatPDFGaussian::copyFrom(const CPose3DPDFGaussian &o)
187  * - CPose3DQuatPDFGaussianInf::copyFrom(const CPose3DPDFGaussianInf &o)
188  */
191 }
192 
193 } // End of namespace
194 
195 #endif
mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian
CPose3DQuatPDFGaussian()
Default constructor - set all values to zero.
Definition: CPose3DQuatPDFGaussian.cpp:44
mrpt::poses::CPose3DQuatPDF
Declares a class that represents a Probability Density Function (PDF) of a 3D pose (6D actually),...
Definition: CPose3DQuatPDF.h:46
mrpt::poses::CPose3DPDFGaussian
Declares a class that represents a Probability Density function (PDF) of a 3D pose .
Definition: CPose3DPDFGaussian.h:40
mrpt::poses::CPose3DQuatPDFGaussian::getMean
void getMean(CPose3DQuat &mean_pose) const override
Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF).
Definition: CPose3DQuatPDFGaussian.cpp:86
mrpt::poses::CPose3DQuatPDFGaussian::operator-
CPose3DQuatPDFGaussian operator-() const
Unary - operator, returns the PDF of the inverse pose.
Definition: CPose3DQuatPDFGaussian.h:131
mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION
void USE_SUT_EULER2QUAT_CONVERSION(bool value)
If set to true (default), a Scaled Unscented Transform is used instead of a linear approximation with...
Definition: CPose3DQuatPDFGaussian.cpp:36
mrpt::poses::CPose3DQuatPDFGaussian::getPoseMean
CPose3DQuat & getPoseMean()
Definition: CPose3DQuatPDFGaussian.h:85
mrpt::poses::operator+
mrpt::math::TPoint2D operator+(const CPose2D &pose, const mrpt::math::TPoint2D &pnt)
Compose a 2D point from a new coordinate base given by a 2D pose.
Definition: CPose2D.cpp:364
obj
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
mrpt::poses::CPose3DQuatPDFGaussian::copyFrom
void copyFrom(const CPose3DQuatPDF &o) override
Copy operator, translating if necesary (for example, between particles and gaussian representations)
Definition: CPose3DQuatPDFGaussian.cpp:120
mrpt::poses::CPose3DQuatPDFGaussian::assureSymmetry
void assureSymmetry()
Assures the symmetry of the covariance matrix (eventually certain operations in the math-coprocessor ...
Definition: CPose3DQuatPDFGaussian.cpp:402
mrpt::poses::CPose3DQuatPDFGaussian::changeCoordinatesReference
void changeCoordinatesReference(const CPose3DQuat &newReferenceBase)
this = p (+) this.
Definition: CPose3DQuatPDFGaussian.cpp:247
mrpt::poses::CPose3DQuatPDFGaussian::drawManySamples
void drawManySamples(size_t N, std::vector< mrpt::math::CVectorDouble > &outSamples) const override
Draws a number of samples from the distribution, and saves as a list of 1x7 vectors,...
Definition: CPose3DQuatPDFGaussian.cpp:284
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::poses::CPose3DQuat
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,...
Definition: CPose3DQuat.h:48
p
GLfloat GLfloat p
Definition: glext.h:6305
mrpt::poses::operator-
CPose2D operator-(const CPose2D &p)
Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...
Definition: CPose2D.cpp:315
mrpt::poses::CPose3DQuatPDFGaussian::saveToTextFile
bool saveToTextFile(const std::string &file) const override
Save the PDF to a text file, containing the 3D pose in the first line (x y z qr qx qy qz),...
Definition: CPose3DQuatPDFGaussian.cpp:215
mrpt::poses::CPose3DQuatPDFGaussian::drawSingleSample
void drawSingleSample(CPose3DQuat &outPart) const override
Draws a single sample from the distribution.
Definition: CPose3DQuatPDFGaussian.cpp:274
mrpt::poses::CPose3DQuatPDFGaussian::evaluatePDF
double evaluatePDF(const CPose3DQuat &x) const
Evaluates the PDF at a given point.
Definition: CPose3DQuatPDFGaussian.cpp:384
CPose3DQuatPDF.h
mrpt::poses::CPose3DQuatPDFGaussian::operator+=
void operator+=(const CPose3DQuat &Ap)
Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the mean, and the covariance matri...
Definition: CPose3DQuatPDFGaussian.cpp:331
mrpt::poses::CPose3DQuatPDFGaussian::cov
mrpt::math::CMatrixDouble77 cov
The 7x7 covariance matrix.
Definition: CPose3DQuatPDFGaussian.h:82
CPosePDF.h
mrpt::poses::CPose3DQuatPDFGaussian::mahalanobisDistanceTo
double mahalanobisDistanceTo(const CPose3DQuatPDFGaussian &theOther)
Computes the Mahalanobis distance between the centers of two Gaussians.
Definition: CPose3DQuatPDFGaussian.cpp:414
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
mrpt::poses::CPose3DQuatPDFGaussian::inverse
void inverse(CPose3DQuatPDF &o) const override
Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF.
Definition: CPose3DQuatPDFGaussian.cpp:301
mrpt::math::TConstructorFlags_Quaternions
TConstructorFlags_Quaternions
Definition: CQuaternion.h:22
CMatrixD.h
mrpt::poses::CPose3DQuatPDFGaussian::getCovarianceAndMean
void getCovarianceAndMean(mrpt::math::CMatrixDouble77 &cov, CPose3DQuat &mean_point) const override
Returns an estimate of the pose covariance matrix (7x7 cov matrix) and the mean, both at once.
Definition: CPose3DQuatPDFGaussian.cpp:90
mrpt::math::CMatrixFixedNumeric
A numeric matrix of compile-time fixed size.
Definition: CMatrixFixedNumeric.h:40
mrpt::poses::CPosePDF
Declares a class that represents a probability density function (pdf) of a 2D pose (x,...
Definition: CPosePDF.h:41
mrpt::poses::CPose3DQuatPDFGaussian::mean
CPose3DQuat mean
The mean value.
Definition: CPose3DQuatPDFGaussian.h:80
mrpt::poses::operator==
bool operator==(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
Definition: CPoint.h:166
DEFINE_SERIALIZABLE
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Definition: CSerializable.h:102
value
GLsizei const GLfloat * value
Definition: glext.h:4117
mrpt::poses::CPose3DQuatPDFGaussian
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...
Definition: CPose3DQuatPDFGaussian.h:44
mrpt::poses::CPose3DQuatPDFGaussian::evaluateNormalizedPDF
double evaluateNormalizedPDF(const CPose3DQuat &x) const
Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,...
Definition: CPose3DQuatPDFGaussian.cpp:393
CPose3DPDF.h
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::poses::operator<<
std::ostream & operator<<(std::ostream &o, const CPoint< DERIVEDCLASS > &p)
Dumps a point as a string [x,y] or [x,y,z]
Definition: CPoint.h:140
mrpt::poses::CPose3DQuatPDFGaussian::getPoseMean
const CPose3DQuat & getPoseMean() const
Definition: CPose3DQuatPDFGaussian.h:84
mrpt::poses::CPose3DQuatPDFGaussian::operator-=
void operator-=(const CPose3DQuatPDFGaussian &Ap)
Makes: thisPDF = thisPDF - Ap, where "-" is pose inverse composition (both the mean,...
Definition: CPose3DQuatPDFGaussian.cpp:373
mrpt::poses::CPosePDFGaussian
Declares a class that represents a Probability Density function (PDF) of a 2D pose .
Definition: CPosePDFGaussian.h:31
mrpt::math::UNINITIALIZED_QUATERNION
@ UNINITIALIZED_QUATERNION
Definition: CQuaternion.h:24
x
GLenum GLint x
Definition: glext.h:3538



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST