MRPT  1.9.9
CGridMapAligner.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, 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 
10 #include "slam-precomp.h" // Precompiled headers
11 
17 #include <mrpt/math/TPose2D.h>
19 #include <mrpt/math/geometry.h>
24 #include <mrpt/random.h>
26 #include <mrpt/slam/CICP.h>
27 #include <mrpt/system/filesystem.h>
28 #include <mrpt/tfest/se2.h>
29 #include <Eigen/Dense>
30 
31 using namespace mrpt::math;
32 using namespace mrpt::slam;
33 using namespace mrpt::maps;
34 using namespace mrpt::poses;
35 using namespace mrpt::random;
36 using namespace mrpt::img;
37 using namespace mrpt::system;
38 using namespace mrpt::vision;
39 using namespace std;
40 
41 CPosePDF::Ptr CGridMapAligner::AlignPDF(
42  const mrpt::maps::CMetricMap* mm1, const mrpt::maps::CMetricMap* mm2,
43  const CPosePDFGaussian& initialEstimationPDF, float* runningTime,
44  void* info)
45 {
47 
48  switch (options.methodSelection)
49  {
50  case CGridMapAligner::amCorrelation:
51  return AlignPDF_correlation(
52  mm1, mm2, initialEstimationPDF, runningTime, info);
53 
54  case CGridMapAligner::amModifiedRANSAC:
55  case CGridMapAligner::amRobustMatch:
56  // The same function has an internal switch for the specific method:
57  return AlignPDF_robustMatch(
58  mm1, mm2, initialEstimationPDF, runningTime, info);
59 
60  default:
61  THROW_EXCEPTION("Wrong value found in 'options.methodSelection'!!");
62  }
63 
64  MRPT_END
65 }
66 
67 bool myVectorOrder(const pair<size_t, float>& o1, const pair<size_t, float>& o2)
68 {
69  return o1.second < o2.second;
70 }
71 
72 /*---------------------------------------------------------------
73  AlignPDF_robustMatch
74 ---------------------------------------------------------------*/
75 CPosePDF::Ptr CGridMapAligner::AlignPDF_robustMatch(
76  const mrpt::maps::CMetricMap* mm1, const mrpt::maps::CMetricMap* mm2,
77  const CPosePDFGaussian& initialEstimationPDF, float* runningTime,
78  void* info)
79 {
81 
82  ASSERT_(
83  options.methodSelection == CGridMapAligner::amRobustMatch ||
84  options.methodSelection == CGridMapAligner::amModifiedRANSAC);
85 
86  TReturnInfo outInfo;
87  mrpt::tfest::TMatchingPairList& correspondences =
88  outInfo.correspondences; // Use directly this placeholder to save 1
89  // variable & 1 copy.
90  mrpt::tfest::TMatchingPairList largestConsensusCorrs;
91 
92  CTicTac* tictac = nullptr;
93 
94  CPose2D grossEst = initialEstimationPDF.mean;
95 
98 
99  std::vector<size_t> idxs1, idxs2;
100  std::vector<size_t>::iterator it1, it2;
101 
102  // Asserts:
103  // -----------------
104  const CMultiMetricMap* multimap1 = nullptr;
105  const CMultiMetricMap* multimap2 = nullptr;
106  const COccupancyGridMap2D* m1 = nullptr;
107  const COccupancyGridMap2D* m2 = nullptr;
108 
109  if (IS_CLASS(*mm1, CMultiMetricMap) && IS_CLASS(*mm2, CMultiMetricMap))
110  {
111  multimap1 = dynamic_cast<const CMultiMetricMap*>(mm1);
112  multimap2 = dynamic_cast<const CMultiMetricMap*>(mm2);
113 
116 
117  m1 = multimap1->mapByClass<COccupancyGridMap2D>().get();
118  m2 = multimap2->mapByClass<COccupancyGridMap2D>().get();
119  }
120  else if (
121  IS_CLASS(*mm1, COccupancyGridMap2D) &&
123  {
124  m1 = dynamic_cast<const COccupancyGridMap2D*>(mm1);
125  m2 = dynamic_cast<const COccupancyGridMap2D*>(mm2);
126  }
127  else
129  "Metric maps must be of classes COccupancyGridMap2D or "
130  "CMultiMetricMap");
131 
132  ASSERT_(m1);
133  ASSERT_(m2);
134 
135  ASSERTMSG_(
136  m1->getResolution() == m2->getResolution(),
137  mrpt::format(
138  "Different resolutions for m1, m2:\n"
139  "\tres(m1) = %f\n\tres(m2) = %f\n",
140  m1->getResolution(), m2->getResolution()));
141 
142  // The algorithm output auxiliar info:
143  // -------------------------------------------------
144  outInfo.goodness = 1.0f;
145 
146  outInfo.landmarks_map1 = lm1;
147  outInfo.landmarks_map2 = lm2;
148 
149  // The PDF to estimate:
150  // ------------------------------------------------------
151  CPosePDFSOG::Ptr pdf_SOG = std::make_shared<CPosePDFSOG>();
152 
153  // Extract features from grid-maps:
154  // ------------------------------------------------------
155  const size_t N1 =
156  std::max(40, mrpt::round(m1->getArea() * options.featsPerSquareMeter));
157  const size_t N2 =
158  std::max(40, mrpt::round(m2->getArea() * options.featsPerSquareMeter));
159 
160  m_grid_feat_extr.extractFeatures(
161  *m1, *lm1, N1, options.feature_descriptor,
162  options.feature_detector_options);
163  m_grid_feat_extr.extractFeatures(
164  *m2, *lm2, N2, options.feature_descriptor,
165  options.feature_detector_options);
166 
167  if (runningTime)
168  {
169  tictac = new CTicTac();
170  tictac->Tic();
171  }
172 
173  const size_t nLM1 = lm1->size();
174  const size_t nLM2 = lm2->size();
175 
176  // At least two landmarks at each map!
177  // ------------------------------------------------------
178  if (nLM1 < 2 || nLM2 < 2)
179  {
180  outInfo.goodness = 0;
181  }
182  else
183  {
184  //#define METHOD_FFT
185  //#define DEBUG_SHOW_CORRELATIONS
186 
187  // Compute correlation between landmarks:
188  // ---------------------------------------------
189  CMatrixFloat CORR(lm1->size(), lm2->size()), auxCorr;
190  CImage im1, im2; // Grayscale
191  CVectorFloat corr;
192  unsigned int corrsCount = 0;
193  std::vector<bool> hasCorr(nLM1, false);
194 
195  const double thres_max = options.threshold_max;
196  const double thres_delta = options.threshold_delta;
197 
198  // CDisplayWindowPlots::Ptr auxWin;
199  if (options.debug_show_corrs)
200  {
201  // auxWin = CDisplayWindowPlots::Ptr( new
202  // CDisplayWindowPlots("Individual corr.") );
203  std::cerr << "Warning: options.debug_show_corrs has no effect "
204  "since MRPT 0.9.1\n";
205  }
206 
207  for (size_t idx1 = 0; idx1 < nLM1; idx1++)
208  {
209  // CVectorFloat corrs_indiv;
210  vector<pair<size_t, float>> corrs_indiv; // (index, distance);
211  // Index is used to
212  // recover the original
213  // index after sorting.
214  vector<float> corrs_indiv_only;
215  corrs_indiv.reserve(nLM2);
216  corrs_indiv_only.reserve(nLM2);
217 
218  for (size_t idx2 = 0; idx2 < nLM2; idx2++)
219  {
220  float minDist;
221  minDist =
222  lm1->landmarks.get(idx1)->features[0].descriptorDistanceTo(
223  lm2->landmarks.get(idx2)->features[0]);
224 
225  corrs_indiv.emplace_back(idx2, minDist);
226  corrs_indiv_only.push_back(minDist);
227  } // end for idx2
228 
229  const double corr_best = mrpt::math::minimum(corrs_indiv_only);
230 
231  // Sort the list and keep the N best features:
232  std::sort(corrs_indiv.begin(), corrs_indiv.end(), myVectorOrder);
233 
234  // const size_t nBestToKeep = std::min( (size_t)30,
235  // corrs_indiv.size() );
236  const size_t nBestToKeep = corrs_indiv.size();
237 
238  for (size_t w = 0; w < nBestToKeep; w++)
239  {
240  if (corrs_indiv[w].second <= thres_max &&
241  corrs_indiv[w].second <= (corr_best + thres_delta))
242  {
243  idxs1.push_back(idx1);
244  idxs2.push_back(corrs_indiv[w].first);
245  outInfo.correspondences_dists_maha.emplace_back(
246  idx1, corrs_indiv[w].first, corrs_indiv[w].second);
247  }
248  }
249  } // end for idx1
250 
251  // Save an image with each feature and its matches:
252  if (options.save_feat_coors)
253  {
255  mrpt::system::createDirectory("grid_feats");
256 
257  std::map<size_t, std::set<size_t>> corrs_by_idx;
258  for (size_t l = 0; l < idxs1.size(); l++)
259  corrs_by_idx[idxs1[l]].insert(idxs2[l]);
260 
261  for (auto& it : corrs_by_idx)
262  {
263  CMatrixFloat descriptor1;
264  lm1->landmarks.get(it.first)
265  ->features[0]
266  .getFirstDescriptorAsMatrix(descriptor1);
267 
268  im1.setFromMatrix(descriptor1, true /*normalized*/);
269 
270  const size_t FEAT_W = im1.getWidth();
271  const size_t FEAT_H = im1.getHeight();
272  const size_t nF = it.second.size();
273 
274  CImage img_compose(FEAT_W * 2 + 15, 10 + (5 + FEAT_H) * nF);
275  img_compose.filledRectangle(
276  0, 0, img_compose.getWidth() - 1,
277  img_compose.getHeight() - 1, TColor::black());
278 
279  img_compose.drawImage(5, 5, im1);
280 
281  size_t j;
282  std::set<size_t>::iterator it_j;
283  string fil =
284  format("grid_feats/_FEAT_MATCH_%03i", (int)it.first);
285 
286  for (j = 0, it_j = it.second.begin(); j < nF; ++j, ++it_j)
287  {
288  fil += format("_%u", static_cast<unsigned int>(*it_j));
289 
290  CMatrixFloat descriptor2;
291  lm2->landmarks.get(*it_j)
292  ->features[0]
293  .getFirstDescriptorAsMatrix(descriptor2);
294  im2.setFromMatrix(descriptor2, true);
295  img_compose.drawImage(
296  10 + FEAT_W, 5 + j * (FEAT_H + 5), im2);
297  }
298  fil += ".png";
299  img_compose.saveToFile(fil);
300  } // end for map
301  }
302 
303  // ------------------------------------------------------------------
304  // Create the list of correspondences from the lists: idxs1 & idxs2
305  // ------------------------------------------------------------------
306  correspondences.clear();
307  for (it1 = idxs1.begin(), it2 = idxs2.begin(); it1 != idxs1.end();
308  ++it1, ++it2)
309  {
311  mp.this_idx = *it1;
312  mp.this_x = lm1->landmarks.get(*it1)->pose_mean.x;
313  mp.this_y = lm1->landmarks.get(*it1)->pose_mean.y;
314  mp.this_z = lm1->landmarks.get(*it1)->pose_mean.z;
315 
316  mp.other_idx = *it2;
317  mp.other_x = lm2->landmarks.get(*it2)->pose_mean.x;
318  mp.other_y = lm2->landmarks.get(*it2)->pose_mean.y;
319  mp.other_z = lm2->landmarks.get(*it2)->pose_mean.z;
320  correspondences.push_back(mp);
321 
322  if (!hasCorr[*it1])
323  {
324  hasCorr[*it1] = true;
325  corrsCount++;
326  }
327  } // end for corres.
328 
329  outInfo.goodness = (2.0f * corrsCount) / (nLM1 + nLM2);
330 
331  // Compute the estimation using ALL the correspondences (NO ROBUST):
332  // ----------------------------------------------------------------------
333  mrpt::math::TPose2D noRobustEst;
334  if (!mrpt::tfest::se2_l2(correspondences, noRobustEst))
335  {
336  // There's no way to match the maps! e.g. no correspondences
337  outInfo.goodness = 0;
338  pdf_SOG->clear();
339  outInfo.sog1 = pdf_SOG;
340  outInfo.sog2 = pdf_SOG;
341  outInfo.sog3 = pdf_SOG;
342  }
343  else
344  {
345  outInfo.noRobustEstimation = mrpt::poses::CPose2D(noRobustEst);
347  "[CGridMapAligner] Overall estimation(%u corrs, total: "
348  "%u): (%.03f,%.03f,%.03fdeg)\n",
349  corrsCount, (unsigned)correspondences.size(),
350  outInfo.noRobustEstimation.x(), outInfo.noRobustEstimation.y(),
351  RAD2DEG(outInfo.noRobustEstimation.phi())));
352 
353  // The list of SOG modes & their corresponding sub-sets of
354  // matchings:
355  using TMapMatchingsToPoseMode = std::map<
357  TMapMatchingsToPoseMode sog_modes;
358 
359  // ---------------------------------------------------------------
360  // Now, we have to choose between the methods:
361  // - CGridMapAligner::amRobustMatch ("normal" RANSAC)
362  // - CGridMapAligner::amModifiedRANSAC
363  // ---------------------------------------------------------------
364  if (options.methodSelection == CGridMapAligner::amRobustMatch)
365  {
366  // ====================================================
367  // METHOD: "Normal" RANSAC
368  // ====================================================
369 
370  // RANSAC over the found correspondences:
371  // -------------------------------------------------
372  const unsigned int min_inliers =
373  options.ransac_minSetSizeRatio * (nLM1 + nLM2) / 2;
374 
375  mrpt::tfest::TSE2RobustParams tfest_params;
376  tfest_params.ransac_minSetSize = min_inliers;
377  tfest_params.ransac_maxSetSize = nLM1 + nLM2;
379  options.ransac_mahalanobisDistanceThreshold;
380  tfest_params.ransac_nSimulations = 0; // 0=auto
381  tfest_params.ransac_fuseByCorrsMatch = true;
382  tfest_params.ransac_fuseMaxDiffXY = 0.01;
383  tfest_params.ransac_fuseMaxDiffPhi = 0.1_deg;
384  tfest_params.ransac_algorithmForLandmarks = true;
385  tfest_params.probability_find_good_model =
386  options.ransac_prob_good_inliers;
387  tfest_params.verbose = false;
388 
389  mrpt::tfest::TSE2RobustResult tfest_result;
391  correspondences, options.ransac_SOG_sigma_m, tfest_params,
392  tfest_result);
393 
394  ASSERT_(pdf_SOG);
395  *pdf_SOG = tfest_result.transformation;
396  largestConsensusCorrs = tfest_result.largestSubSet;
397 
398  // Simplify the SOG by merging close modes:
399  // -------------------------------------------------
400  size_t nB = pdf_SOG->size();
401  outInfo.sog1 = pdf_SOG;
402 
403  // Keep only the most-likely Gaussian mode:
404  CPosePDFSOG::TGaussianMode best_mode;
405  best_mode.log_w = -std::numeric_limits<double>::max();
406 
407  for (size_t n = 0; n < pdf_SOG->size(); n++)
408  {
409  const CPosePDFSOG::TGaussianMode& m = (*pdf_SOG)[n];
410 
411  if (m.log_w > best_mode.log_w) best_mode = m;
412  }
413 
414  pdf_SOG->clear();
415  pdf_SOG->push_back(best_mode);
416  outInfo.sog2 = pdf_SOG;
417 
419  "[CGridMapAligner] amRobustMatch: "
420  << nB << " SOG modes reduced to " << pdf_SOG->size()
421  << " (most-likely) (min.inliers=" << min_inliers << ")\n");
422 
423  } // end of amRobustMatch
424  else
425  {
426  // ====================================================
427  // METHOD: "Modified" RANSAC
428  // ====================================================
429  mrpt::tfest::TMatchingPairList all_corrs = correspondences;
430 
431  const size_t nCorrs = all_corrs.size();
432  ASSERT_(nCorrs >= 2);
433 
434  pdf_SOG->clear(); // Start with 0 Gaussian modes
435 
436  // Build a points-map for exploiting its KD-tree:
437  // ----------------------------------------------------
438  CSimplePointsMap lm1_pnts, lm2_pnts;
439  lm1_pnts.reserve(nLM1);
440  for (size_t i = 0; i < nLM1; i++)
441  lm1_pnts.insertPoint(lm1->landmarks.get(i)->pose_mean);
442  lm2_pnts.reserve(nLM2);
443  for (size_t i = 0; i < nLM2; i++)
444  lm2_pnts.insertPoint(lm2->landmarks.get(i)->pose_mean);
445 
446  // RANSAC loop
447  // ---------------------
448  const size_t minInliersTOaccept =
449  round(options.ransac_minSetSizeRatio * 0.5 * (nLM1 + nLM2));
450  // Set an initial # of iterations:
451  const unsigned int ransac_min_nSimulations =
452  2 * (nLM1 + nLM2); // 1000;
453  unsigned int ransac_nSimulations =
454  10; // It doesn't matter actually, since will be changed in
455  // the first loop
456  const double probability_find_good_model = 0.9999;
457 
458  const double chi2_thres_dim1 =
459  mrpt::math::chi2inv(options.ransac_chi2_quantile, 1);
460  const double chi2_thres_dim2 =
461  mrpt::math::chi2inv(options.ransac_chi2_quantile, 2);
462 
463  // Generic 2x2 covariance matrix for all features in their local
464  // coords:
465  CMatrixDouble22 COV_pnt;
466  COV_pnt(0, 0) = COV_pnt(1, 1) =
467  square(options.ransac_SOG_sigma_m);
468 
469  // The absolute number of trials.
470  // in practice it's only important for a reduced number of
471  // correspondences, to avoid a dead-lock:
472  // It's the binomial coefficient:
473  // / n \ n! n * (n-1)
474  // | | = ----------- = -----------
475  // \ 2 / 2! (n-2)! 2
476  //
477  const unsigned int max_trials =
478  (nCorrs * (nCorrs - 1) / 2) *
479  5; // "*5" is just for safety...
480 
481  unsigned int iter = 0; // Valid iterations (those passing the
482  // first mahalanobis test)
483  unsigned int trials = 0; // counter of all iterations,
484  // including "iter" + failing ones.
485  while (iter < ransac_nSimulations &&
486  trials <
487  max_trials) // ransac_nSimulations can be dynamic
488  {
489  trials++;
490 
491  mrpt::tfest::TMatchingPairList tentativeSubSet;
492 
493  // Pick 2 random correspondences:
494  uint32_t idx1, idx2;
495  idx1 = getRandomGenerator().drawUniform32bit() % nCorrs;
496  do
497  {
498  idx2 = getRandomGenerator().drawUniform32bit() % nCorrs;
499  } while (idx1 == idx2); // Avoid a degenerated case!
500 
501  // Uniqueness of features:
502  if (all_corrs[idx1].this_idx == all_corrs[idx2].this_idx ||
503  all_corrs[idx1].this_idx == all_corrs[idx2].other_idx)
504  continue;
505  if (all_corrs[idx1].other_idx == all_corrs[idx2].this_idx ||
506  all_corrs[idx1].other_idx == all_corrs[idx2].other_idx)
507  continue;
508 
509  // Check the feasibility of this pair "idx1"-"idx2":
510  // The distance between the pair of points in MAP1 must be
511  // very close
512  // to that of their correspondences in MAP2:
513  const double corrs_dist1 =
515  all_corrs[idx1].this_x, all_corrs[idx1].this_y,
516  all_corrs[idx1].this_z, all_corrs[idx2].this_x,
517  all_corrs[idx2].this_y, all_corrs[idx2].this_z);
518 
519  const double corrs_dist2 =
521  all_corrs[idx1].other_x, all_corrs[idx1].other_y,
522  all_corrs[idx1].other_z, all_corrs[idx2].other_x,
523  all_corrs[idx2].other_y, all_corrs[idx2].other_z);
524 
525  // Is is a consistent possibility?
526  // We use a chi2 test (see paper for the derivation)
527  const double corrs_dist_chi2 =
528  square(square(corrs_dist1) - square(corrs_dist2)) /
529  (8.0 * square(options.ransac_SOG_sigma_m) *
530  (square(corrs_dist1) + square(corrs_dist2)));
531 
532  if (corrs_dist_chi2 > chi2_thres_dim1) continue; // Nope
533 
534  iter++; // Do not count iterations if they fail the test
535  // above.
536 
537  // before proceeding with this hypothesis, is it an old one?
538  bool is_new_hyp = true;
539  for (auto& sog_mode : sog_modes)
540  {
541  if (sog_mode.first.contains(all_corrs[idx1]) &&
542  sog_mode.first.contains(all_corrs[idx2]))
543  {
544  // Increment weight:
545  sog_mode.second.log_w =
546  std::log(std::exp(sog_mode.second.log_w) + 1.0);
547  is_new_hyp = false;
548  break;
549  }
550  }
551  if (!is_new_hyp) continue;
552 
553  // Ok, it's a new hypothesis:
554  tentativeSubSet.push_back(all_corrs[idx1]);
555  tentativeSubSet.push_back(all_corrs[idx2]);
556 
557  // Maintain a list of already used landmarks IDs in both
558  // maps to avoid repetitions:
559  std::vector<bool> used_landmarks1(nLM1, false);
560  std::vector<bool> used_landmarks2(nLM2, false);
561 
562  used_landmarks1[all_corrs[idx1].this_idx] = true;
563  used_landmarks1[all_corrs[idx2].this_idx] = true;
564  used_landmarks2[all_corrs[idx1].other_idx] = true;
565  used_landmarks2[all_corrs[idx2].other_idx] = true;
566 
567  // Build the transformation for these temptative
568  // correspondences:
569  bool keep_incorporating = true;
570  CPosePDFGaussian temptPose;
571  do // Incremently incorporate inliers:
572  {
573  if (!mrpt::tfest::se2_l2(tentativeSubSet, temptPose))
574  continue; // Invalid matching...
575 
576  // The computed cov is "normalized", i.e. must be
577  // multiplied by std^2_xy
578  temptPose.cov *= square(options.ransac_SOG_sigma_m);
579 
580  // Find the landmark in MAP2 with the best (maximum)
581  // product-integral:
582  // (i^* , j^*) = arg max_(i,j) \int p_i()p_j()
583  //----------------------------------------------------------------------
584  const double ccos = cos(temptPose.mean.phi());
585  const double ssin = sin(temptPose.mean.phi());
586 
587  CMatrixDouble22 Hc; // Jacobian wrt point_j
588  Hc(1, 1) = ccos;
589  Hc(0, 0) = ccos;
590  Hc(1, 0) = ssin;
591  Hc(0, 1) = -ssin;
592 
594  Hq; // Jacobian wrt transformation q
595  Hq(0, 0) = 1;
596  Hq(1, 1) = 1;
597 
598  TPoint2D p2_j_local;
599  vector<float> matches_dist;
600  std::vector<size_t> matches_idx;
601 
602  CPoint2DPDFGaussian pdf_M2_j;
603  CPoint2DPDFGaussian pdf_M1_i;
604 
605 // Use integral-of-product vs. mahalanobis distances to match:
606 #define GRIDMAP_USE_PROD_INTEGRAL
607 
608 #ifdef GRIDMAP_USE_PROD_INTEGRAL
609  double best_pair_value = 0;
610 #else
611  double best_pair_value =
612  std::numeric_limits<double>::max();
613 #endif
614  double best_pair_d2 =
615  std::numeric_limits<double>::max();
616  pair<size_t, size_t> best_pair_ij;
617 
618  //#define SHOW_CORRS
619 
620 #ifdef SHOW_CORRS
621  CDisplayWindowPlots win("Matches");
622 #endif
623  for (size_t j = 0; j < nLM2; j++)
624  {
625  if (used_landmarks2[j]) continue;
626 
627  lm2_pnts.getPoint(
628  j, p2_j_local); // In local coords.
629  pdf_M2_j.mean = mrpt::poses::CPoint2D(
630  temptPose.mean +
631  p2_j_local); // In (temptative) global coords:
632  pdf_M2_j.cov(0, 0) = pdf_M2_j.cov(1, 1) =
633  square(options.ransac_SOG_sigma_m);
634 
635 #ifdef SHOW_CORRS
636  win.plotEllipse(
637  pdf_M2_j.mean.x(), pdf_M2_j.mean.y(),
638  pdf_M2_j.cov, 2, "b-",
639  format("M2_%u", (unsigned)j), true);
640 #endif
641 
642  static const unsigned int N_KDTREE_SEARCHED = 3;
643 
644  // Look for a few close features which may be
645  // potential matches:
646  lm1_pnts.kdTreeNClosestPoint2DIdx(
647  pdf_M2_j.mean.x(), pdf_M2_j.mean.y(),
648  N_KDTREE_SEARCHED, matches_idx, matches_dist);
649 
650  // And for each one, compute the product-integral:
651  for (unsigned long u : matches_idx)
652  {
653  if (used_landmarks1[u]) continue;
654 
655  // Jacobian wrt transformation q
656  Hq(0, 2) =
657  -p2_j_local.x * ssin - p2_j_local.y * ccos;
658  Hq(1, 2) =
659  p2_j_local.x * ccos - p2_j_local.y * ssin;
660 
661  // COV_j = Hq \Sigma_q Hq^t + Hc Cj Hc^t
662  pdf_M1_i.cov =
663  mrpt::math::multiply_HCHt(Hc, COV_pnt);
664  pdf_M1_i.cov += mrpt::math::multiply_HCHt(
665  Hq, temptPose.cov);
666 
667  float px, py;
668  lm1_pnts.getPoint(u, px, py);
669  pdf_M1_i.mean.x(px);
670  pdf_M1_i.mean.y(py);
671 
672 #ifdef SHOW_CORRS
673  win.plotEllipse(
674  pdf_M1_i.mean.x(), pdf_M1_i.mean.y(),
675  pdf_M1_i.cov, 2, "r-",
676  format("M1_%u", (unsigned)matches_idx[u]),
677  true);
678 #endif
679 
680 // And now compute the product integral:
681 #ifdef GRIDMAP_USE_PROD_INTEGRAL
682  const double prod_ij =
683  pdf_M1_i.productIntegralWith(pdf_M2_j);
684 
685  if (prod_ij > best_pair_value)
686 #else
687  const double prod_ij =
688  pdf_M1_i.mean.distanceTo(pdf_M2_j.mean);
689  if (prod_ij < best_pair_value)
690 #endif
691  {
692  // const double prodint_ij =
693  // pdf_M1_i.productIntegralWith2D(pdf_M2_j);
694 
695  best_pair_value = prod_ij;
696  best_pair_ij.first = u;
697  best_pair_ij.second = j;
698 
699  best_pair_d2 =
700  square(pdf_M1_i.mahalanobisDistanceTo(
701  pdf_M2_j));
702  }
703  } // end for u (closest matches of LM2 in MAP 1)
704 
705 #ifdef SHOW_CORRS
706  win.axis_fit(true);
707  win.waitForKey();
708  win.clear();
709 #endif
710 
711  } // end for each LM2
712 
713  // Stop when the best choice has a bad mahal. dist.
714  keep_incorporating = false;
715 
716  // For the best (i,j), gate by the mahalanobis distance:
717  if (best_pair_d2 < chi2_thres_dim2)
718  {
719  // AND, also, check if the descriptors have some
720  // resemblance!!
721  // ----------------------------------------------------------------
722  // double feat_dist =
723  // lm1->landmarks.get(best_pair_ij.first)->features[0]->descriptorDistanceTo(*lm1->landmarks.get(best_pair_ij.second)->features[0]);
724  // if (feat_dist< options.threshold_max)
725  {
726  float p1_i_localx, p1_i_localy;
727  float p2_j_localx, p2_j_localy;
728  lm1_pnts.getPoint(
729  best_pair_ij.first, p1_i_localx,
730  p1_i_localy);
731  lm2_pnts.getPoint(
732  best_pair_ij.second, p2_j_localx,
733  p2_j_localy); // In local coords.
734 
735  used_landmarks1[best_pair_ij.first] = true;
736  used_landmarks2[best_pair_ij.second] = true;
737 
738  tentativeSubSet.push_back(
740  best_pair_ij.first, best_pair_ij.second,
741  p1_i_localx, p1_i_localy, 0, // MAP1
742  p2_j_localx, p2_j_localy, 0 // MAP2
743  ));
744 
745  keep_incorporating = true;
746  }
747  }
748 
749  } while (keep_incorporating);
750 
751  // Consider this pairing?
752  const size_t ninliers = tentativeSubSet.size();
753  if (ninliers > minInliersTOaccept)
754  {
756  newGauss.log_w = 0; // log(1); //
757  // std::log(static_cast<double>(nCoincidences));
758  newGauss.mean = temptPose.mean;
759  newGauss.cov = temptPose.cov;
760 
761  sog_modes[tentativeSubSet] = newGauss;
762 
763  // cout << "ITER: " << iter << " #inliers: " << ninliers
764  // << " q: " << temptPose.mean << endl;
765  }
766 
767  // Keep the largest consensus & dynamic # of steps:
768  if (largestConsensusCorrs.size() < ninliers)
769  {
770  largestConsensusCorrs = tentativeSubSet;
771 
772  // Update estimate of N, the number of trials to ensure
773  // we pick,
774  // with probability p, a data set with no outliers.
775  const double fracinliers =
776  ninliers /
777  static_cast<double>(std::min(nLM1, nLM2));
778  double pNoOutliers =
779  1 - pow(fracinliers,
780  static_cast<double>(
781  2.0)); // minimumSizeSamplesToFit
782 
783  pNoOutliers = std::max(
784  std::numeric_limits<double>::epsilon(),
785  pNoOutliers); // Avoid division by -Inf
786  pNoOutliers = std::min(
787  1.0 - std::numeric_limits<double>::epsilon(),
788  pNoOutliers); // Avoid division by 0.
789  // Number of
790  ransac_nSimulations =
791  log(1 - probability_find_good_model) /
792  log(pNoOutliers);
793 
794  if (ransac_nSimulations < ransac_min_nSimulations)
795  ransac_nSimulations = ransac_min_nSimulations;
796 
797  // if (verbose)
798  // cout << "[Align] Iter #" << iter << " Est. #iters: "
799  //<< ransac_nSimulations << " pNoOutliers=" <<
800  // pNoOutliers << " #inliers: " << ninliers << endl;
801  }
802 
803  } // end of RANSAC loop
804 
805  // Move SOG modes into pdf_SOG:
806  pdf_SOG->clear();
807  for (auto s = sog_modes.begin(); s != sog_modes.end(); ++s)
808  {
810  "SOG mode: " << s->second.mean
811  << " inliers: " << s->first.size());
812  pdf_SOG->push_back(s->second);
813  }
814 
815  // Normalize:
816  if (pdf_SOG->size() > 0) pdf_SOG->normalizeWeights();
817 
818  // Simplify the SOG by merging close modes:
819  // -------------------------------------------------
820  size_t nB = pdf_SOG->size();
821  outInfo.sog1 = pdf_SOG;
822 
823  CTicTac merge_clock;
824  pdf_SOG->mergeModes(options.maxKLd_for_merge, false);
825  const double merge_clock_tim = merge_clock.Tac();
826 
827  outInfo.sog2 = pdf_SOG;
828  size_t nA = pdf_SOG->size();
830  "[CGridMapAligner] amModifiedRANSAC: %u SOG modes "
831  "merged to %u in %.03fsec\n",
832  (unsigned int)nB, (unsigned int)nA, merge_clock_tim));
833 
834  } // end of amModifiedRANSAC
835 
836  // Save best corrs:
837  if (options.debug_save_map_pairs)
838  {
839  static unsigned int NN = 0;
840  static const COccupancyGridMap2D* lastM1 = nullptr;
841  if (lastM1 != m1)
842  {
843  lastM1 = m1;
844  NN = 0;
845  }
847  "Largest consensus: %u",
848  static_cast<unsigned>(largestConsensusCorrs.size()));
849  CEnhancedMetaFile::LINUX_IMG_WIDTH(
850  m1->getSizeX() + m2->getSizeX() + 50);
851  CEnhancedMetaFile::LINUX_IMG_HEIGHT(
852  max(m1->getSizeY(), m2->getSizeY()) + 50);
853 
854  for (auto s = sog_modes.begin(); s != sog_modes.end(); ++s)
855  {
856  COccupancyGridMap2D::saveAsEMFTwoMapsWithCorrespondences(
857  format("__debug_corrsGrid_%05u.emf", NN), m1, m2,
858  s->first);
859  COccupancyGridMap2D::saveAsBitmapTwoMapsWithCorrespondences(
860  format("__debug_corrsGrid_%05u.png", NN), m1, m2,
861  s->first);
862  ++NN;
863  }
864  }
865 
866  // --------------------------------------------------------------------
867  // At this point:
868  // - "pdf_SOG": has the resulting PDF with the SOG (from whatever
869  // method)
870  // - "largestConsensusCorrs": The 'best' set of correspondences
871  //
872  // Now: If we had a multi-metric map, use the points map to improve
873  // the estimation with ICP.
874  // --------------------------------------------------------------------
875  if (multimap1 && multimap2 &&
876  multimap1->countMapsByClass<CSimplePointsMap>() != 0 &&
877  multimap2->countMapsByClass<CSimplePointsMap>() != 0)
878  {
879  auto pnts1 = multimap1->mapByClass<CSimplePointsMap>();
880  auto pnts2 = multimap2->mapByClass<CSimplePointsMap>();
881 
882  CICP icp;
883  CICP::TReturnInfo icpInfo;
884 
885  icp.options.maxIterations = 20;
886  icp.options.smallestThresholdDist = 0.05f;
887  icp.options.thresholdDist = 0.75f;
888 
889  // Invoke ICP once for each mode in the SOG:
890  size_t cnt = 0;
891  outInfo.icp_goodness_all_sog_modes.clear();
892  for (auto i = pdf_SOG->begin(); i != pdf_SOG->end(); ++cnt)
893  {
894  CPosePDF::Ptr icp_est = icp.Align(
895  pnts1.get(), pnts2.get(), (i)->mean, nullptr, &icpInfo);
896 
897  //(i)->cov(0,0) += square( 0.05 );
898  //(i)->cov(1,1) += square( 0.05 );
899  //(i)->cov(2,2) += square( 0.05_deg );
900 
901  CPosePDFGaussian i_gauss(i->mean, i->cov);
902  CPosePDFGaussian icp_gauss(icp_est->getMeanVal(), i->cov);
903 
904  const double icp_maha_dist =
905  i_gauss.mahalanobisDistanceTo(icp_gauss);
906 
908  "ICP " << cnt << " log-w: " << i->log_w
909  << " Goodness: " << 100 * icpInfo.goodness
910  << " D_M= " << icp_maha_dist);
912  "final pos: " << icp_est->getMeanVal());
913  MRPT_LOG_INFO_STREAM(" org pos: " << i->mean);
914 
915  outInfo.icp_goodness_all_sog_modes.push_back(
916  icpInfo.goodness);
917 
918  // Discard?
919  if (icpInfo.goodness > options.min_ICP_goodness &&
920  icp_maha_dist < options.max_ICP_mahadist)
921  {
922  icp_est->getMean((i)->mean);
923  ++i;
924  }
925  else
926  {
927  // Delete:
928  i = pdf_SOG->erase(i);
929  }
930 
931  } // end for i
932 
933  // Merge:
934  outInfo.sog3 = pdf_SOG;
935 
936  pdf_SOG->mergeModes(options.maxKLd_for_merge, false);
938  "[CGridMapAligner] " << pdf_SOG->size()
939  << " SOG modes merged after ICP.");
940 
941  } // end multimapX
942 
943  } // end of, yes, we have enough correspondences
944 
945  } // end of: yes, there are landmarks in the grid maps!
946 
947  // Copy the output info if requested:
948  // -------------------------------------------------
949  MRPT_TODO(
950  "Refactor `info` so it is polymorphic and can use dynamic_cast<> here");
951  if (info)
952  {
953  auto* info_ = static_cast<TReturnInfo*>(info);
954  *info_ = outInfo;
955  }
956 
957  if (runningTime)
958  {
959  *runningTime = tictac->Tac();
960  delete tictac;
961  }
962 
963  return pdf_SOG;
964 
965  MRPT_END
966 }
967 
968 /*---------------------------------------------------------------
969  AlignPDF_correlation
970 ---------------------------------------------------------------*/
971 CPosePDF::Ptr CGridMapAligner::AlignPDF_correlation(
972  const mrpt::maps::CMetricMap* mm1, const mrpt::maps::CMetricMap* mm2,
973  const CPosePDFGaussian& initialEstimationPDF, float* runningTime,
974  void* info)
975 {
976  MRPT_UNUSED_PARAM(initialEstimationPDF);
977  MRPT_UNUSED_PARAM(info);
978 
979  MRPT_START
980 
981  //#define CORRELATION_SHOW_DEBUG
982 
983  CTicTac* tictac = nullptr;
984 
985  // Asserts:
986  // -----------------
989  const auto* m1 = dynamic_cast<const COccupancyGridMap2D*>(mm1);
990  const auto* m2 = dynamic_cast<const COccupancyGridMap2D*>(mm2);
991 
992  ASSERT_(m1->getResolution() == m2->getResolution());
993 
994  if (runningTime)
995  {
996  tictac = new CTicTac();
997  tictac->Tic();
998  }
999 
1000  // The PDF to estimate:
1001  // ------------------------------------------------------
1002  CPosePDFGaussian::Ptr PDF = std::make_shared<CPosePDFGaussian>();
1003 
1004  // Determine the extension to compute the correlation into:
1005  // ----------------------------------------------------------
1006  float phiResolution = DEG2RAD(0.2f);
1007  float phiMin = -M_PIf + 0.5f * phiResolution;
1008  float phiMax = M_PIf;
1009 
1010  // Compute the difference between maps for each (u,v) pair!
1011  // --------------------------------------------------------------
1012  float phi;
1013  float pivotPt_x = 0.5f * (m1->getXMax() + m1->getXMin());
1014  float pivotPt_y = 0.5f * (m1->getYMax() + m1->getYMin());
1015  COccupancyGridMap2D map2_mod;
1016  CImage map1_img, map2_img;
1017  float currentMaxCorr = -1e6f;
1018 
1019  m1->getAsImage(map1_img);
1020 
1021  map2_mod.setSize(
1022  m1->getXMin(), m1->getXMax(), m1->getYMin(), m1->getYMax(),
1023  m1->getResolution());
1024  size_t map2_lx = map2_mod.getSizeX();
1025  size_t map2_ly = map2_mod.getSizeY();
1026  CMatrixF outCrossCorr, bestCrossCorr;
1027  float map2width_2 = 0.5f * (map2_mod.getXMax() - map2_mod.getXMin());
1028 
1029 #ifdef CORRELATION_SHOW_DEBUG
1030  CDisplayWindow* win = new CDisplayWindow("corr");
1031  CDisplayWindow* win2 = new CDisplayWindow("map2_mod");
1032 #endif
1033 
1034  // --------------------------------------------------------
1035  // Use FFT-based correlation for each orientation:
1036  // --------------------------------------------------------
1037  for (phi = phiMin; phi < phiMax; phi += phiResolution)
1038  {
1039  // Create the displaced map2 grid, for the size of map1:
1040  // --------------------------------------------------------
1041  CPose2D v2(
1042  pivotPt_x - cos(phi) * map2width_2,
1043  pivotPt_y - sin(phi) * map2width_2,
1044  phi); // Rotation point: the centre of img1:
1045  CPoint2D v1, v3;
1046  v2 = CPose2D(0, 0, 0) - v2; // Inverse
1047 
1048  for (size_t cy2 = 0; cy2 < map2_ly; cy2++)
1049  {
1050  COccupancyGridMap2D::cellType* row = map2_mod.getRow(cy2);
1051  for (size_t cx2 = 0; cx2 < map2_lx; cx2++)
1052  {
1053  v3 = v2 + CPoint2D(map2_mod.idx2x(cx2), map2_mod.idx2y(cy2));
1054  *row++ = m2->p2l(m2->getPos(v3.x(), v3.y()));
1055  }
1056  }
1057 
1058  map2_mod.getAsImage(map2_img);
1059  // map2_img.saveToBMP("__debug_map2mod.bmp");
1060 
1061  // Compute the correlation:
1062  map1_img.cross_correlation_FFT(
1063  map2_img, outCrossCorr, -1, -1, -1, -1,
1064  127, // Bias to be substracted
1065  127 // Bias to be substracted
1066  );
1067 
1068  float corrPeak = outCrossCorr.maxCoeff();
1069  MRPT_LOG_INFO_FMT("phi = %fdeg \tmax corr=%f", RAD2DEG(phi), corrPeak);
1070 
1071  // Keep the maximum:
1072  if (corrPeak > currentMaxCorr)
1073  {
1074  currentMaxCorr = corrPeak;
1075  bestCrossCorr = outCrossCorr;
1076  PDF->mean.phi(phi);
1077  }
1078 
1079 #ifdef CORRELATION_SHOW_DEBUG
1080  outCrossCorr.adjustRange(0, 1);
1081  CImage aux(outCrossCorr, true);
1082  win->showImage(aux);
1083  win2->showImage(map2_img);
1084  std::this_thread::sleep_for(5ms);
1085 #endif
1086 
1087  } // end for phi
1088 
1089  if (runningTime)
1090  {
1091  *runningTime = tictac->Tac();
1092  delete tictac;
1093  }
1094 
1095  CImage aux;
1096  aux.setFromMatrix(bestCrossCorr, false /* do normalization [0,1]*/);
1097  aux.saveToFile("_debug_best_corr.png");
1098 
1099 #ifdef CORRELATION_SHOW_DEBUG
1100  delete win;
1101  delete win2;
1102 #endif
1103 
1104  // Transform the best corr matrix peak into coordinates:
1105  std::size_t uMax, vMax;
1106  currentMaxCorr = bestCrossCorr.maxCoeff(uMax, vMax);
1107 
1108  PDF->mean.x(m1->idx2x(uMax));
1109  PDF->mean.y(m1->idx2y(vMax));
1110 
1111  return PDF;
1112 
1113  // Done!
1114  MRPT_END
1115 }
1116 
1117 /*---------------------------------------------------------------
1118  TConfigParams
1119  ---------------------------------------------------------------*/
1120 CGridMapAligner::TConfigParams::TConfigParams() : feature_detector_options() {}
1121 /*---------------------------------------------------------------
1122  dumpToTextStream
1123  ---------------------------------------------------------------*/
1125 {
1126  out << "\n----------- [CGridMapAligner::TConfigParams] ------------ \n\n";
1127 
1128  LOADABLEOPTS_DUMP_VAR(methodSelection, int)
1129  LOADABLEOPTS_DUMP_VAR(featsPerSquareMeter, float)
1130  LOADABLEOPTS_DUMP_VAR(threshold_max, float)
1131  LOADABLEOPTS_DUMP_VAR(threshold_delta, float)
1132  LOADABLEOPTS_DUMP_VAR(min_ICP_goodness, float)
1133  LOADABLEOPTS_DUMP_VAR(max_ICP_mahadist, double)
1134  LOADABLEOPTS_DUMP_VAR(maxKLd_for_merge, float)
1135  LOADABLEOPTS_DUMP_VAR(ransac_minSetSizeRatio, float)
1137  LOADABLEOPTS_DUMP_VAR(ransac_chi2_quantile, double)
1138  LOADABLEOPTS_DUMP_VAR(ransac_prob_good_inliers, double)
1139  LOADABLEOPTS_DUMP_VAR(ransac_SOG_sigma_m, float)
1140  LOADABLEOPTS_DUMP_VAR(save_feat_coors, bool)
1141  LOADABLEOPTS_DUMP_VAR(debug_show_corrs, bool)
1142  LOADABLEOPTS_DUMP_VAR(debug_save_map_pairs, bool)
1143 
1144  LOADABLEOPTS_DUMP_VAR(feature_descriptor, int)
1145 
1146  feature_detector_options.dumpToTextStream(out);
1147 
1148  out << "\n";
1149 }
1150 
1151 /*---------------------------------------------------------------
1152  loadFromConfigFile
1153  ---------------------------------------------------------------*/
1155  const mrpt::config::CConfigFileBase& iniFile, const std::string& section)
1156 {
1157  methodSelection =
1158  iniFile.read_enum(section, "methodSelection", methodSelection);
1159 
1161  featsPerSquareMeter, float, iniFile, section)
1162  MRPT_LOAD_CONFIG_VAR(ransac_SOG_sigma_m, float, iniFile, section)
1163 
1164  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(threshold_max, float, iniFile, section)
1165  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(threshold_delta, float, iniFile, section)
1166 
1167  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(min_ICP_goodness, float, iniFile, section)
1168  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(max_ICP_mahadist, double, iniFile, section)
1169 
1170  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(maxKLd_for_merge, float, iniFile, section)
1172  ransac_minSetSizeRatio, float, iniFile, section)
1176  ransac_chi2_quantile, double, iniFile, section)
1178  ransac_prob_good_inliers, double, iniFile, section)
1179 
1180  MRPT_LOAD_CONFIG_VAR(save_feat_coors, bool, iniFile, section)
1181  MRPT_LOAD_CONFIG_VAR(debug_show_corrs, bool, iniFile, section)
1182  MRPT_LOAD_CONFIG_VAR(debug_save_map_pairs, bool, iniFile, section)
1183 
1184  feature_descriptor = iniFile.read_enum(
1185  section, "feature_descriptor", feature_descriptor, true);
1186  feature_detector_options.loadFromConfigFile(iniFile, section);
1187 }
1188 
1190  const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2,
1191  const CPose3DPDFGaussian& initialEstimationPDF, float* runningTime,
1192  void* info)
1193 {
1194  MRPT_UNUSED_PARAM(m1);
1195  MRPT_UNUSED_PARAM(m2);
1196  MRPT_UNUSED_PARAM(initialEstimationPDF);
1197  MRPT_UNUSED_PARAM(runningTime);
1198  MRPT_UNUSED_PARAM(info);
1199  THROW_EXCEPTION("Align3D method not applicable to gridmap-aligner");
1200 }
Scalar maxCoeff() const
Maximum value in the matrix/vector.
A namespace of pseudo-random numbers generators of diferent distributions.
uint32_t drawUniform32bit()
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, in the whole range of 32-bit integers.
float getXMax() const
Returns the "x" coordinate of right side of grid map.
std::size_t countMapsByClass() const
Count how many maps exist of the given class (or derived class)
double Tac() noexcept
Stops the stopwatch.
Definition: CTicTac.cpp:86
double x
X,Y coordinates.
Definition: TPoint2D.h:23
void getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
Definition: CPointsMap.cpp:194
double getArea() const
Returns the area of the gridmap, in square meters.
A compile-time fixed-size numeric matrix container.
Definition: CMatrixFixed.h:33
bool createDirectory(const std::string &dirName)
Creates a directory.
Definition: filesystem.cpp:161
#define MRPT_START
Definition: exceptions.h:241
double productIntegralWith(const CPoint2DPDFGaussian &p) const
Computes the "correspondence likelihood" of this PDF with another one: This is implemented as the int...
CPose2D mean
The mean value.
std::vector< TPairPlusDistance > correspondences_dists_maha
Mahalanobis distance for each potential correspondence.
The struct for each mode:
Definition: CPosePDFSOG.h:41
float getResolution() const
Returns the resolution of the grid map.
Template for column vectors of dynamic size, compatible with Eigen.
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
void reserve(size_t newLength) override
Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory.
A gaussian distribution for 2D points.
std::string std::string format(std::string_view fmt, ARGS &&... args)
Definition: format.h:26
bool se2_l2(const mrpt::tfest::TMatchingPairList &in_correspondences, mrpt::math::TPose2D &out_transformation, mrpt::math::CMatrixDouble33 *out_estimateCovariance=nullptr)
Least-squares (L2 norm) solution to finding the optimal SE(2) (x,y,yaw) between two reference frames...
Definition: se2_l2.cpp:46
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Definition: CICP.h:64
GLint * first
Definition: glext.h:3833
Parameters for se2_l2_robust().
Definition: se2.h:73
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
GLenum GLsizei n
Definition: glext.h:5136
This file implements several operations that operate element-wise on individual or pairs of container...
bool ransac_fuseByCorrsMatch
(Default = true) If true, the weight of Gaussian modes will be increased when an exact match in the s...
Definition: se2.h:92
unsigned int ransac_nSimulations
(Default = 0) If set to 0, an adaptive algorithm is used to determine the number of iterations...
Definition: se2.h:85
void drawImage(int x, int y, const mrpt::img::CImage &img) override
Draws an image as a bitmap at a given position.
Definition: CImage.cpp:1171
A high-performance stopwatch, with typical resolution of nanoseconds.
unsigned int ransac_minSetSize
(Default=3)
Definition: se2.h:76
mrpt::containers::deepcopy_poly_ptr< mrpt::poses::CPosePDFSOG::Ptr > sog3
const float ransac_mahalanobisDistanceThreshold
bool myVectorOrder(const pair< size_t, float > &o1, const pair< size_t, float > &o2)
size_t getHeight() const override
Returns the height of the image in pixels.
Definition: CImage.cpp:878
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
void insertPoint(float x, float y, float z=0)
Provides a way to insert (append) individual points into the map: the missing fields of child classes...
Definition: CPointsMap.h:644
STL namespace.
double mahalanobisDistanceTo(const CPosePDFGaussian &theOther)
Computes the Mahalanobis distance between the centers of two Gaussians.
void kdTreeNClosestPoint2DIdx(float x0, float y0, size_t knn, std::vector< size_t > &out_idx, std::vector< float > &out_dist_sqr) const
KD Tree-based search for the N closest point to some given 2D coordinates and returns their indexes...
GLdouble s
Definition: glext.h:3682
The ICP algorithm return information.
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4199
double distanceTo(const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const
Returns the Euclidean distance to another pose/point:
Definition: CPoseOrPoint.h:214
mrpt::system::CTicTac CTicTac
Definition: utils/CTicTac.h:5
mrpt::poses::CPose3DPDF::Ptr Align3DPDF(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=nullptr, void *info=nullptr) override
Not applicable in this class, will launch an exception.
bool verbose
(Default=false)
Definition: se2.h:111
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
Definition: CICP.h:197
mrpt::tfest::TMatchingPairList correspondences
All the found correspondences (not consistent)
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
size_t getWidth() const override
Returns the width of the image in pixels.
Definition: CImage.cpp:847
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
bool se2_l2_robust(const mrpt::tfest::TMatchingPairList &in_correspondences, const double in_normalizationStd, const TSE2RobustParams &in_ransac_params, TSE2RobustResult &out_results)
Robust least-squares (L2 norm) solution to finding the optimal SE(2) (x,y,yaw) between two reference ...
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
Definition: CObject.h:102
unsigned int ransac_maxSetSize
(Default = 20)
Definition: se2.h:78
A class for storing a map of 3D probabilistic landmarks.
Definition: CLandmarksMap.h:74
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
float getXMin() const
Returns the "x" coordinate of left side of grid map.
T square(const T x)
Inline function for the square of a number.
constexpr double DEG2RAD(const double x)
Degrees to radians.
virtual void filledRectangle(int x0, int y0, int x1, int y1, const mrpt::img::TColor color)
Draws a filled rectangle.
Definition: CCanvas.cpp:217
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
A list of TMatchingPair.
Definition: TMatchingPair.h:70
bool ransac_algorithmForLandmarks
(Default = true) Use Mahalanobis distance (true) or Euclidean dist (false)
Definition: se2.h:99
mrpt::math::CMatrixDouble33 cov
Definition: CPosePDFSOG.h:45
GLfloat GLfloat GLfloat GLfloat v3
Definition: glext.h:4125
#define M_PIf
Definition: common.h:61
string iniFile(myDataDir+string("benchmark-options.ini"))
unsigned int getSizeX() const
Returns the horizontal size of grid map in cells count.
void setFromMatrix(const MAT &m, bool matrix_is_normalized=true)
Set the image from a matrix, interpreted as grayscale intensity values, in the range [0...
Definition: img/CImage.h:832
Classes for computer vision, detectors, features, etc.
Definition: CDifodo.h:17
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
Definition: CObject.h:146
#define MRPT_LOAD_CONFIG_VAR_NO_DEFAULT( variableName, variableType, configFileObject, sectionNameStr)
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
Definition: exceptions.h:108
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:143
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
Use: MRPT_LOG_DEBUG_STREAM("Var=" << value << " foo=" << foo_var);
mrpt::gui::CDisplayWindow3D::Ptr win
GLsizei const GLchar ** string
Definition: glext.h:4116
double ransac_mahalanobisDistanceThreshold
(Default = 3.0)
Definition: se2.h:80
A class used to store a 2D point.
Definition: CPoint2D.h:32
double ransac_fuseMaxDiffPhi
(Default=0.1degree) (In radians)
Definition: se2.h:96
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
Definition: TMatchingPair.h:31
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
void cross_correlation_FFT(const CImage &in_img, math::CMatrixFloat &out_corr, int u_search_ini=-1, int v_search_ini=-1, int u_search_size=-1, int v_search_size=-1, float biasThisImg=0, float biasInImg=0) const
Computes the correlation matrix between this image and another one.
Definition: CImage.cpp:1385
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
CONTAINER::Scalar minimum(const CONTAINER &v)
mrpt::maps::CLandmarksMap::Ptr landmarks_map1
The landmarks of each map (the indices of these landmarks correspond to those in "correspondences") ...
A class for storing an occupancy grid map.
void getAsImage(mrpt::img::CImage &img, bool verticalFlip=false, bool forceRGB=false, bool tricolor=false) const
Returns the grid as a 8-bit graylevel image, where each pixel is a cell (output image is RGB only if ...
std::vector< double > icp_goodness_all_sog_modes
The ICP goodness of all potential SOG modes at the stage "sog2", thus before the removing of "bad" IC...
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrixF.h:22
virtual const mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
#define MRPT_TODO(x)
Definition: common.h:129
double chi2inv(double P, unsigned int dim=1)
The "quantile" of the Chi-Square distribution, for dimension "dim" and probability 0<P<1 (the inverse...
Definition: math.cpp:42
GLfloat GLfloat v1
Definition: glext.h:4121
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:52
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
mrpt::vision::TStereoCalibResults out
cellType * getRow(int cy)
Access to a "row": mainly used for drawing grid as a bitmap efficiently, do not use it normally...
T::Ptr mapByClass(const size_t &ith=0) const
Returns the i&#39;th map of a given class (or of a derived class), or empty smart pointer if there is no ...
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:86
GLenum GLenum GLvoid * row
Definition: glext.h:3580
constexpr double RAD2DEG(const double x)
Radians to degrees.
#define MRPT_END
Definition: exceptions.h:245
The ICP algorithm return information.
Definition: CICP.h:190
Lightweight 2D pose.
Definition: TPose2D.h:22
double mean(const CONTAINER &v)
Computes the mean value of a vector.
float idx2y(const size_t cy) const
mrpt::poses::CPosePDFSOG transformation
The output as a set of transformations (sum of Gaussians)
Definition: se2.h:133
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
OccGridCellTraits::cellType cellType
The type of the map cells:
bool deleteFilesInDirectory(const std::string &s, bool deleteDirectoryAsWell=false)
Delete all the files in a given directory (nothing done if directory does not exists, or path is a file).
Definition: filesystem.cpp:218
mrpt::maps::CLandmarksMap::Ptr landmarks_map2
T distanceBetweenPoints(const T x1, const T y1, const T x2, const T y2)
Returns the distance between 2 points in 2D.
Definition: geometry.h:942
GLfloat GLfloat GLfloat v2
Definition: glext.h:4123
bool saveToFile(const std::string &fileName, int jpeg_quality=95) const
Save the image to a file, whose format is determined from the extension (internally uses OpenCV)...
Definition: CImage.cpp:337
void setSize(float x_min, float x_max, float y_min, float y_max, float resolution, float default_value=0.5f)
Change the size of gridmap, erasing all its previous contents.
void Tic() noexcept
Starts the stopwatch.
Definition: CTicTac.cpp:75
mrpt::containers::deepcopy_poly_ptr< mrpt::poses::CPosePDFSOG::Ptr > sog2
mrpt::tfest::TMatchingPairList largestSubSet
the largest consensus sub-set
Definition: se2.h:135
This class stores any customizable set of metric maps.
unsigned int getSizeY() const
Returns the vertical size of grid map in cells count.
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
Lightweight 2D point.
Definition: TPoint2D.h:31
mrpt::poses::CPose2D noRobustEstimation
The "brute" estimation from using all the available correspondences, provided just for comparison pur...
This template class provides the basic functionality for a general 2D any-size, resizable container o...
mrpt::containers::deepcopy_poly_ptr< mrpt::poses::CPosePDFSOG::Ptr > sog1
The different SOG densities at different steps of the algorithm:
mrpt::math::CMatrixDouble22 cov
The 2x2 covariance matrix.
Output placeholder for se2_l2_robust()
Definition: se2.h:130
#define MRPT_LOG_INFO_FMT(_FMT_STRING,...)
double ransac_fuseMaxDiffXY
(Default = 0.01)
Definition: se2.h:94
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:147
double probability_find_good_model
(Default = 0.999) See parameter ransac_nSimulations.
Definition: se2.h:103
double mahalanobisDistanceTo(const CPoint2DPDFGaussian &other) const
Returns the Mahalanobis distance from this PDF to another PDF, that is, it&#39;s evaluation at (0...
#define MRPT_LOG_INFO(_STRING)
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
Definition: common.h:186
void multiply_HCHt(const MAT_H &H, const MAT_C &C, MAT_R &R, bool accumResultInOutput=false)
R = H * C * H^t.
Definition: ops_matrices.h:28
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:24



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 4363012a5 Tue Nov 19 10:55:26 2019 +0100 at mar nov 19 11:00:13 CET 2019