Main MRPT website > C++ reference for MRPT 1.9.9
CPosePDFGaussian.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, 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 
10 #include "base-precomp.h" // Precompiled headers
11 
14 #include <mrpt/poses/CPose3DPDF.h>
15 #include <mrpt/poses/CPose3D.h>
16 #include <mrpt/math/CMatrix.h>
18 #include <mrpt/math/wrap2pi.h>
19 #include <mrpt/system/os.h>
20 #include <mrpt/utils/CStream.h>
21 
22 #include <mrpt/random.h>
23 
24 using namespace mrpt;
25 using namespace mrpt::utils;
26 using namespace mrpt::poses;
27 using namespace mrpt::math;
28 using namespace mrpt::random;
29 using namespace mrpt::system;
30 
31 using namespace std;
32 
34 
35 /*---------------------------------------------------------------
36  Constructor
37  ---------------------------------------------------------------*/
39 /*---------------------------------------------------------------
40  Constructor
41  ---------------------------------------------------------------*/
42 CPosePDFGaussian::CPosePDFGaussian(
43  const CPose2D& init_Mean, const CMatrixDouble33& init_Cov)
44  : mean(init_Mean), cov(init_Cov)
45 {
46 }
47 
48 /*---------------------------------------------------------------
49  Constructor
50  ---------------------------------------------------------------*/
52  : mean(init_Mean), cov()
53 {
54  cov.zeros();
55 }
56 
57 /*---------------------------------------------------------------
58  writeToStream
59  ---------------------------------------------------------------*/
61  mrpt::utils::CStream& out, int* version) const
62 {
63  if (version)
64  *version = 2;
65  else
66  {
67  out << mean;
68  out << cov(0, 0) << cov(1, 1) << cov(2, 2);
69  out << cov(0, 1) << cov(0, 2) << cov(1, 2);
70  }
71 }
72 
73 /*---------------------------------------------------------------
74  readFromStream
75  ---------------------------------------------------------------*/
77 {
78  switch (version)
79  {
80  case 2:
81  {
82  double x;
83  in >> mean;
84 
85  in >> x;
86  cov(0, 0) = x;
87  in >> x;
88  cov(1, 1) = x;
89  in >> x;
90  cov(2, 2) = x;
91 
92  in >> x;
93  cov(1, 0) = x;
94  cov(0, 1) = x;
95  in >> x;
96  cov(2, 0) = x;
97  cov(0, 2) = x;
98  in >> x;
99  cov(1, 2) = x;
100  cov(2, 1) = x;
101  }
102  break;
103  case 1:
104  {
105  float x;
106  in >> mean;
107 
108  in >> x;
109  cov(0, 0) = x;
110  in >> x;
111  cov(1, 1) = x;
112  in >> x;
113  cov(2, 2) = x;
114 
115  in >> x;
116  cov(1, 0) = x;
117  cov(0, 1) = x;
118  in >> x;
119  cov(2, 0) = x;
120  cov(0, 2) = x;
121  in >> x;
122  cov(1, 2) = x;
123  cov(2, 1) = x;
124  }
125  break;
126  case 0:
127  {
128  CMatrix auxCov;
129  in >> mean >> auxCov;
130  cov = auxCov.cast<double>();
131  }
132  break;
133  default:
135  };
136 }
137 
138 /*---------------------------------------------------------------
139  copyFrom
140  ---------------------------------------------------------------*/
142 {
143  if (this == &o) return; // It may be used sometimes
144 
145  // Convert to gaussian pdf:
146  o.getMean(mean);
147  o.getCovariance(cov);
148 }
149 
150 /*---------------------------------------------------------------
151  copyFrom 3D
152  ---------------------------------------------------------------*/
154 {
155  // Convert to gaussian pdf:
156  mean = CPose2D(o.getMeanVal());
157  CMatrixDouble66 C;
158  o.getCovariance(C);
159 
160  // Clip to 3x3:
161  C(2, 0) = C(0, 2) = C(0, 3);
162  C(2, 1) = C(1, 2) = C(1, 3);
163  C(2, 2) = C(3, 3);
164  cov = C.block(0, 0, 3, 3);
165 }
166 
167 /*---------------------------------------------------------------
168 
169  ---------------------------------------------------------------*/
171 {
172  FILE* f = os::fopen(file.c_str(), "wt");
173  if (!f) return;
174 
175  os::fprintf(f, "%f %f %f\n", mean.x(), mean.y(), mean.phi());
176 
177  os::fprintf(f, "%f %f %f\n", cov(0, 0), cov(0, 1), cov(0, 2));
178  os::fprintf(f, "%f %f %f\n", cov(1, 0), cov(1, 1), cov(1, 2));
179  os::fprintf(f, "%f %f %f\n", cov(2, 0), cov(2, 1), cov(2, 2));
180 
181  os::fclose(f);
182 }
183 
184 /*---------------------------------------------------------------
185  changeCoordinatesReference
186  ---------------------------------------------------------------*/
188  const CPose3D& newReferenceBase_)
189 {
190  const CPose2D newReferenceBase = CPose2D(newReferenceBase_);
191 
192  // The mean:
193  mean.composeFrom(newReferenceBase, mean);
194 
195  // The covariance:
196  rotateCov(newReferenceBase.phi());
197 }
198 
199 /*---------------------------------------------------------------
200  changeCoordinatesReference
201  ---------------------------------------------------------------*/
203  const CPose2D& newReferenceBase)
204 {
205  // The mean:
206  mean.composeFrom(newReferenceBase, mean);
207  // The covariance:
208  rotateCov(newReferenceBase.phi());
209 }
210 
211 /*---------------------------------------------------------------
212  changeCoordinatesReference
213  ---------------------------------------------------------------*/
214 void CPosePDFGaussian::rotateCov(const double ang)
215 {
216  const double ccos = cos(ang);
217  const double ssin = sin(ang);
218 
219  alignas(16)
220  const double rot_vals[] = {ccos, -ssin, 0., ssin, ccos, 0., 0., 0., 1.};
221 
222  const CMatrixFixedNumeric<double, 3, 3> rot(rot_vals);
223  cov = (rot * cov * rot.adjoint()).eval();
224 }
225 
226 /*---------------------------------------------------------------
227  drawSingleSample
228  ---------------------------------------------------------------*/
230 {
231  MRPT_START
232 
235 
236  outPart.x(mean.x() + v[0]);
237  outPart.y(mean.y() + v[1]);
238  outPart.phi(mean.phi() + v[2]);
239 
240  // Range -pi,pi
241  outPart.normalizePhi();
242 
244  cov.saveToTextFile("__DEBUG_EXC_DUMP_drawSingleSample_COV.txt"););
245 }
246 
247 /*---------------------------------------------------------------
248  drawManySamples
249  ---------------------------------------------------------------*/
251  size_t N, std::vector<CVectorDouble>& outSamples) const
252 {
253  MRPT_START
254 
255  std::vector<CVectorDouble> rndSamples;
256 
258  outSamples.resize(N);
259  for (unsigned int i = 0; i < N; i++)
260  {
261  outSamples[i].resize(3);
262  outSamples[i][0] = mean.x() + rndSamples[i][0];
263  outSamples[i][1] = mean.y() + rndSamples[i][1];
264  outSamples[i][2] = mean.phi() + rndSamples[i][2];
265 
266  wrapToPiInPlace(outSamples[i][2]);
267  }
268 
269  MRPT_END
270 }
271 
272 /*---------------------------------------------------------------
273  bayesianFusion
274  ---------------------------------------------------------------*/
276  const CPosePDF& p1_, const CPosePDF& p2_,
277  const double& minMahalanobisDistToDrop)
278 {
279  MRPT_START
280 
281  MRPT_UNUSED_PARAM(minMahalanobisDistToDrop); // Not used in this class!
282 
285 
286  const CPosePDFGaussian* p1 = static_cast<const CPosePDFGaussian*>(&p1_);
287  const CPosePDFGaussian* p2 = static_cast<const CPosePDFGaussian*>(&p2_);
288 
289  CMatrixDouble33 C1 = p1->cov;
290  CMatrixDouble33 C2 = p2->cov;
291 
292  CMatrixDouble33 C1_inv;
293  C1.inv(C1_inv);
294 
295  CMatrixDouble33 C2_inv;
296  C2.inv(C2_inv);
297 
298  CMatrixDouble31 x1 = CMatrixDouble31(p1->mean);
300 
301  CMatrixDouble33 auxC = C1_inv + C2_inv;
302  auxC.inv(this->cov);
303  this->assureSymmetry();
304 
305  CMatrixDouble31 x = this->cov * (C1_inv * x1 + C2_inv * x2);
306 
307  this->mean.x(x(0, 0));
308  this->mean.y(x(1, 0));
309  this->mean.phi(x(2, 0));
310  this->mean.normalizePhi();
311 
312  MRPT_END
313 }
314 
315 /*---------------------------------------------------------------
316  inverse
317  ---------------------------------------------------------------*/
319 {
321  CPosePDFGaussian* out = static_cast<CPosePDFGaussian*>(&o);
322 
323  // The mean:
324  out->mean = CPose2D(0, 0, 0) - mean;
325 
326  // The covariance:
327  const double ccos = ::cos(mean.phi());
328  const double ssin = ::sin(mean.phi());
329 
330  // jacobian:
331  alignas(16) const double H_values[] = {
332  -ccos, -ssin, mean.x() * ssin - mean.y() * ccos,
333  ssin, -ccos, mean.x() * ccos + mean.y() * ssin,
334  0, 0, -1};
335  const CMatrixFixedNumeric<double, 3, 3> H(H_values);
336 
337  out->cov.noalias() =
338  (H * cov * H.adjoint()).eval(); // o.cov = H * cov * Ht
339 }
340 
341 /*---------------------------------------------------------------
342  +=
343  ---------------------------------------------------------------*/
345 {
346  mean = mean + Ap;
347  rotateCov(Ap.phi());
348 }
349 
350 /*---------------------------------------------------------------
351  evaluatePDF
352  ---------------------------------------------------------------*/
354 {
357 
358  return math::normalPDF(X, MU, this->cov);
359 }
360 
361 /*---------------------------------------------------------------
362  evaluateNormalizedPDF
363  ---------------------------------------------------------------*/
365 {
368 
369  return math::normalPDF(X, MU, this->cov) /
370  math::normalPDF(MU, MU, this->cov);
371 }
372 
373 /*---------------------------------------------------------------
374  assureSymmetry
375  ---------------------------------------------------------------*/
377 {
378  // Differences, when they exist, appear in the ~15'th significant
379  // digit, so... just take one of them arbitrarily!
380  cov(0, 1) = cov(1, 0);
381  cov(0, 2) = cov(2, 0);
382  cov(1, 2) = cov(2, 1);
383 }
384 
385 /*---------------------------------------------------------------
386  mahalanobisDistanceTo
387  ---------------------------------------------------------------*/
389 {
390  MRPT_START
391 
393  MU -= CArrayDouble<3>(theOther.mean);
394 
395  wrapToPiInPlace(MU[2]);
396 
397  if (MU[0] == 0 && MU[1] == 0 && MU[2] == 0)
398  return 0; // This is the ONLY case where we know the result, whatever
399  // COVs are.
400 
401  CMatrixDouble33 COV_ = cov;
402  COV_ += theOther.cov;
403 
405  COV_.inv_fast(COV_inv);
406 
407  // (~MU) * (!COV_) * MU
408  return std::sqrt(mrpt::math::multiply_HCHt_scalar(MU, COV_inv));
409 
410  MRPT_END
411 }
412 
413 /*---------------------------------------------------------------
414  operator <<
415  ---------------------------------------------------------------*/
417  std::ostream& out, const CPosePDFGaussian& obj)
418 {
419  out << "Mean: " << obj.mean << "\n";
420  out << "Covariance:\n" << obj.cov << "\n";
421 
422  return out;
423 }
424 
425 /*---------------------------------------------------------------
426  operator +
427  ---------------------------------------------------------------*/
430 {
433  return ret;
434 }
435 
436 /*---------------------------------------------------------------
437  assureMinCovariance
438  ---------------------------------------------------------------*/
440  const double& minStdXY, const double& minStdPhi)
441 {
442  cov(0, 0) = max(cov(0, 0), square(minStdXY));
443  cov(1, 1) = max(cov(1, 1), square(minStdXY));
444  cov(2, 2) = max(cov(2, 2), square(minStdPhi));
445 }
446 
447 /*---------------------------------------------------------------
448  inverseComposition
449  Set 'this' = 'x' - 'ref', computing the mean using the "-"
450  operator and the covariances through the corresponding Jacobians.
451  ---------------------------------------------------------------*/
453  const CPosePDFGaussian& xv, const CPosePDFGaussian& xi)
454 {
455  // COV:
456  double cpi = cos(xi.mean.phi());
457  double spi = sin(xi.mean.phi());
458 
459  // jacob: dh_xv
460  CMatrixDouble33 dh_xv;
461 
462  dh_xv(0, 0) = cpi;
463  dh_xv(0, 1) = spi;
464  dh_xv(1, 0) = -spi;
465  dh_xv(1, 1) = cpi;
466  dh_xv(2, 2) = 1;
467 
468  // jacob: dh_xi
469  CMatrixDouble33 dh_xi;
470 
471  double xv_xi = xv.mean.x() - xi.mean.x();
472  double yv_yi = xv.mean.y() - xi.mean.y();
473 
474  dh_xi(0, 0) = -cpi;
475  dh_xi(0, 1) = -spi;
476  dh_xi(0, 2) = -xv_xi * spi + yv_yi * cpi;
477  dh_xi(1, 0) = spi;
478  dh_xi(1, 1) = -cpi;
479  dh_xi(1, 2) = -xv_xi * cpi - yv_yi * spi;
480  dh_xi(2, 2) = -1;
481 
482  // Build the cov:
483  // Y = dh_xv * XV * dh_xv^T + dh_xi * XI * dh_xi^T
484  dh_xv.multiply_HCHt(xv.cov, this->cov);
485  dh_xi.multiply_HCHt(xi.cov, this->cov, true); // Accum. result
486 
487  // Mean:
488  mean = xv.mean - xi.mean;
489 }
490 
491 /*---------------------------------------------------------------
492  inverseComposition
493  Set \f$ this = x1 \ominus x0 \f$ , computing the mean using
494  the "-" operator and the covariances through the corresponding
495  Jacobians (Given the 3x3 cross-covariance matrix of variables x0 and x0).
496  ---------------------------------------------------------------*/
498  const CPosePDFGaussian& x1, const CPosePDFGaussian& x0,
499  const CMatrixDouble33& COV_01)
500 {
501  double cp0 = cos(x0.mean.phi());
502  double sp0 = sin(x0.mean.phi());
503 
504  // jacob: dh_x1
505  CMatrixDouble33 dh_x1;
506 
507  dh_x1(0, 0) = cp0;
508  dh_x1(0, 1) = sp0;
509  dh_x1(1, 0) = -sp0;
510  dh_x1(1, 1) = cp0;
511  dh_x1(2, 2) = 1;
512 
513  // jacob: dh_x0
514  CMatrixDouble33 dh_x0;
515 
516  double xv_xi = x1.mean.x() - x0.mean.x();
517  double yv_yi = x1.mean.y() - x0.mean.y();
518 
519  dh_x0(0, 0) = -cp0;
520  dh_x0(0, 1) = -sp0;
521  dh_x0(0, 2) = -xv_xi * sp0 + yv_yi * cp0;
522  dh_x0(1, 0) = sp0;
523  dh_x0(1, 1) = -cp0;
524  dh_x0(1, 2) = -xv_xi * cp0 - yv_yi * sp0;
525  dh_x0(2, 2) = -1;
526 
527  // Build the cov:
528  // Y = dh_xv * XV * dh_xv^T + dh_xi * XI * dh_xi^T + A + At
529  // being A = dh_dx0 * COV01 * dh_dx1^t
530  dh_x0.multiply_HCHt(x0.cov, this->cov);
531  dh_x1.multiply_HCHt(x1.cov, this->cov, true); // Accum. result
532 
533  CMatrixDouble33 M;
534  M.multiply_ABCt(dh_x0, COV_01, dh_x1);
535 
536  this->cov.add_AAt(M);
537 
538  // mean
539  mean = x1.mean - x0.mean;
540 }
541 
542 /*---------------------------------------------------------------
543  +=
544  ---------------------------------------------------------------*/
546 {
547  // COV:
548  const CMatrixDouble33 OLD_COV = this->cov;
550 
552  this->mean, // x
553  Ap.mean, // u
554  df_dx, df_du);
555 
556  // this->cov = H1*this->cov*~H1 + H2*Ap.cov*~H2;
557  df_dx.multiply_HCHt(OLD_COV, cov);
558  df_du.multiply_HCHt(Ap.cov, cov, true); // Accumulate result
559 
560  // MEAN:
561  this->mean = this->mean + Ap.mean;
562 }
563 
564 /** Returns the PDF of the 2D point \f$ g = q \oplus l\f$ with "q"=this pose and
565  * "l" a point without uncertainty */
567  const mrpt::math::TPoint2D& l, CPoint2DPDFGaussian& g) const
568 {
569  // Mean:
570  double gx, gy;
571  mean.composePoint(l.x, l.y, gx, gy);
572  g.mean.x(gx);
573  g.mean.y(gy);
574 
575  // COV:
578  this->mean, // x
579  this->mean, // u
580  df_dx, df_du,
581  true, // Eval df_dx
582  false // Eval df_du (not needed)
583  );
584 
585  const CMatrixFixedNumeric<double, 2, 3> dp_dx = df_dx.block<2, 3>(0, 0);
586  g.cov = dp_dx * this->cov * dp_dx.transpose();
587 }
588 
590  const CPosePDFGaussian& p1, const CPosePDFGaussian& p2)
591 {
592  return p1.mean == p2.mean && p1.cov == p2.cov;
593 }
594 
596  const CPosePDFGaussian& a, const CPosePDFGaussian& b)
597 {
599  res += b;
600  return res;
601 }
602 
604  const CPosePDFGaussian& a, const CPosePDFGaussian& b)
605 {
607  res.inverseComposition(a, b);
608  return res;
609 }
A namespace of pseudo-random numbers genrators of diferent distributions.
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:135
void copyFrom(const CPosePDF &o) override
Copy operator, translating if necesary (for example, between particles and gaussian representations) ...
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
CPose2D mean
The mean value.
void writeToStream(mrpt::utils::CStream &out, int *getVersion) const override
Introduces a pure virtual method responsible for writing to a CStream.
double x
X,Y coordinates.
#define MRPT_END_WITH_CLEAN_UP(stuff)
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
Definition: math_frwds.h:30
A gaussian distribution for 2D points.
int void fclose(FILE *f)
An OS-independent version of fclose.
Definition: os.cpp:272
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
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:377
TDATA getMeanVal() const
Returns the mean, or mathematical expectation of the probability density distribution (PDF)...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:42
MAT_C::Scalar multiply_HCHt_scalar(const VECTOR_H &H, const MAT_C &C)
r (a scalar) = H * C * H^t (with a vector H and a symmetric matrix C)
Definition: ops_matrices.h:69
void getCovariance(mrpt::math::CMatrixDouble &cov) const
Returns the estimate of the covariance matrix (STATE_LEN x STATE_LEN covariance matrix) ...
STL namespace.
double mahalanobisDistanceTo(const CPosePDFGaussian &theOther)
Computes the Mahalanobis distance between the centers of two Gaussians.
void composePoint(const mrpt::math::TPoint2D &l, CPoint2DPDFGaussian &g) const
Returns the PDF of the 2D point with "q"=this pose and "l" a point without uncertainty.
void composePoint(double lx, double ly, double &gx, double &gy) const
An alternative, slightly more efficient way of doing with G and L being 2D points and P this 2D pose...
Definition: CPose2D.cpp:188
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
T square(const T x)
Inline function for the square of a number.
Definition: bits.h:55
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
void wrapToPiInPlace(T &a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Definition: wrap2pi.h:64
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
void changeCoordinatesReference(const CPose3D &newReferenceBase) override
this = p (+) this.
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
Definition: CObject.h:85
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
#define MRPT_END
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
CPosePDFGaussian()
Default constructor.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
void drawGaussianMultivariateMany(VECTOR_OF_VECTORS &ret, size_t desiredSamples, const COVMATRIX &cov, const typename VECTOR_OF_VECTORS::value_type *mean=nullptr)
Generate a given number of multidimensional random samples according to a given covariance matrix...
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:328
void saveToTextFile(const std::string &file) const override
Save PDF&#39;s particles to a text file, containing the 2D pose in the first line, then the covariance ma...
double evaluatePDF(const CPose2D &x) const
Evaluates the PDF at a given point.
GLubyte g
Definition: glext.h:6279
GLubyte GLubyte b
Definition: glext.h:6279
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 1x3 vectors, where each row contains a (x,y,phi) datum.
double evaluateNormalizedPDF(const CPose2D &x) const
Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,1].
virtual void getMean(TDATA &mean_point) const =0
Returns the mean, or mathematical expectation of the probability density distribution (PDF)...
GLsizei const GLchar ** string
Definition: glext.h:4101
void inverseComposition(const CPosePDFGaussian &x, const CPosePDFGaussian &ref)
Set , computing the mean using the "-" operator and the covariances through the corresponding Jacobi...
Declares a class that represents a probability density function (pdf) of a 2D pose (x...
Definition: CPosePDF.h:41
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
Definition: os.cpp:405
virtual const mrpt::utils::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
#define MRPT_START
const GLdouble * v
Definition: glext.h:3678
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void assureMinCovariance(const double &minStdXY, const double &minStdPhi)
Substitutes the diagonal elements if (square) they are below some given minimum values (Use this befo...
bool operator==(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
Definition: CPoint.h:163
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:40
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
static void jacobiansPoseComposition(const CPose2D &x, const CPose2D &u, mrpt::math::CMatrixDouble33 &df_dx, mrpt::math::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:
Definition: CPosePDF.cpp:32
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:91
void composeFrom(const CPose2D &A, const CPose2D &B)
Makes .
Definition: CPose2D.cpp:124
void readFromStream(mrpt::utils::CStream &in, int version) override
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
GLuint in
Definition: glext.h:7274
#define ASSERT_(f)
void assureSymmetry()
Assures the symmetry of the covariance matrix (eventually certain operations in the math-coprocessor ...
FILE * fopen(const char *fileName, const char *mode) noexcept
An OS-independent version of fopen.
Definition: os.cpp:254
Eigen::Matrix< typename MATRIX::Scalar, MATRIX::ColsAtCompileTime, MATRIX::ColsAtCompileTime > cov(const MATRIX &v)
Computes the covariance matrix from a list of samples in an NxM matrix, where each row is a sample...
Definition: ops_matrices.h:148
GLuint res
Definition: glext.h:7268
void drawGaussianMultivariate(std::vector< T > &out_result, const mrpt::math::CMatrixTemplateNumeric< T > &cov, const std::vector< T > *mean=nullptr)
Generate multidimensional random samples according to a given covariance matrix.
GLenum GLint x
Definition: glext.h:3538
void operator+=(const CPose2D &Ap)
Makes: thisPDF = thisPDF + Ap, where "+" is pose composition (both the mean, and the covariance matri...
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:25
void rotateCov(const double ang)
Rotate the covariance matrix by replacing it by , where .
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
Lightweight 2D point.
double normalPDF(double x, double mu, double std)
Evaluates the univariate normal (Gaussian) distribution at a given point "x".
Definition: math.cpp:989
GLubyte GLubyte GLubyte a
Definition: glext.h:6279
void drawSingleSample(CPose2D &outPart) const override
Draws a single sample from the distribution.
Declares a class that represents a Probability Density Function (PDF) of a 3D pose (6D actually)...
Definition: CPose3DPDF.h:42
EIGEN_STRONG_INLINE double mean() const
Computes the mean of the entire matrix.
void normalizePhi()
Forces "phi" to be in the range [-pi,pi];.
Definition: CPose2D.cpp:305
CMatrixFixedNumeric< double, 3, 1 > CMatrixDouble31
Definition: eigen_frwds.h:60
void inverse(CPosePDF &o) const override
Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF.
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:137
void bayesianFusion(const CPosePDF &p1, const CPosePDF &p2, const double &minMahalanobisDistToDrop=0) override
Bayesian fusion of two points gauss.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019