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



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020