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-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 
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,
45 {
47 
48  TReturnInfo infoVal;
49 
50  switch (options.methodSelection)
51  {
52  case CGridMapAligner::amCorrelation:
53  return AlignPDF_correlation(
54  mm1, mm2, initialEstimationPDF, infoVal);
55 
56  case CGridMapAligner::amModifiedRANSAC:
57  case CGridMapAligner::amRobustMatch:
58  // The same function has an internal switch for the specific method:
59  return AlignPDF_robustMatch(
60  mm1, mm2, initialEstimationPDF, infoVal);
61 
62  default:
63  THROW_EXCEPTION("Wrong value found in 'options.methodSelection'!!");
64  }
65 
66  // Copy the output info if requested:
67  if (info)
68  if (auto* o = dynamic_cast<TReturnInfo*>(&info.value().get()); o)
69  *o = infoVal;
70 
71  MRPT_END
72 }
73 
74 static bool myVectorOrder(
75  const pair<size_t, float>& o1, const pair<size_t, float>& o2)
76 {
77  return o1.second < o2.second;
78 }
79 
80 /*---------------------------------------------------------------
81  AlignPDF_robustMatch
82 ---------------------------------------------------------------*/
83 CPosePDF::Ptr CGridMapAligner::AlignPDF_robustMatch(
84  const mrpt::maps::CMetricMap* mm1, const mrpt::maps::CMetricMap* mm2,
85  const CPosePDFGaussian& initialEstimationPDF, TReturnInfo& outInfo)
86 {
88 
89  ASSERT_(
90  options.methodSelection == CGridMapAligner::amRobustMatch ||
91  options.methodSelection == CGridMapAligner::amModifiedRANSAC);
92 
93  mrpt::tfest::TMatchingPairList& correspondences =
94  outInfo.correspondences; // Use directly this placeholder to save 1
95  // variable & 1 copy.
96  mrpt::tfest::TMatchingPairList largestConsensusCorrs;
97 
100 
101  std::vector<size_t> idxs1, idxs2;
102  std::vector<size_t>::iterator it1, it2;
103 
104  // Asserts:
105  // -----------------
106  const CMultiMetricMap* multimap1 = nullptr;
107  const CMultiMetricMap* multimap2 = nullptr;
108  const COccupancyGridMap2D* m1 = nullptr;
109  const COccupancyGridMap2D* m2 = nullptr;
110 
111  if (IS_CLASS(*mm1, CMultiMetricMap) && IS_CLASS(*mm2, CMultiMetricMap))
112  {
113  multimap1 = dynamic_cast<const CMultiMetricMap*>(mm1);
114  multimap2 = dynamic_cast<const CMultiMetricMap*>(mm2);
115 
118 
119  m1 = multimap1->mapByClass<COccupancyGridMap2D>().get();
120  m2 = multimap2->mapByClass<COccupancyGridMap2D>().get();
121  }
122  else if (
123  IS_CLASS(*mm1, COccupancyGridMap2D) &&
125  {
126  m1 = dynamic_cast<const COccupancyGridMap2D*>(mm1);
127  m2 = dynamic_cast<const COccupancyGridMap2D*>(mm2);
128  }
129  else
131  "Metric maps must be of classes COccupancyGridMap2D or "
132  "CMultiMetricMap");
133 
134  ASSERT_(m1);
135  ASSERT_(m2);
136 
137  ASSERTMSG_(
138  m1->getResolution() == m2->getResolution(),
139  mrpt::format(
140  "Different resolutions for m1, m2:\n"
141  "\tres(m1) = %f\n\tres(m2) = %f\n",
142  m1->getResolution(), m2->getResolution()));
143 
144  // The algorithm output auxiliar info:
145  // -------------------------------------------------
146  outInfo.goodness = 1.0f;
147 
148  outInfo.landmarks_map1 = lm1;
149  outInfo.landmarks_map2 = lm2;
150 
151  // The PDF to estimate:
152  // ------------------------------------------------------
153  CPosePDFSOG::Ptr pdf_SOG = std::make_shared<CPosePDFSOG>();
154 
155  // Extract features from grid-maps:
156  // ------------------------------------------------------
157  const size_t N1 =
158  std::max(40, mrpt::round(m1->getArea() * options.featsPerSquareMeter));
159  const size_t N2 =
160  std::max(40, mrpt::round(m2->getArea() * options.featsPerSquareMeter));
161 
162  m_grid_feat_extr.extractFeatures(
163  *m1, *lm1, N1, options.feature_descriptor,
164  options.feature_detector_options);
165  m_grid_feat_extr.extractFeatures(
166  *m2, *lm2, N2, options.feature_descriptor,
167  options.feature_detector_options);
168 
169  mrpt::system::CTicTac tictac;
170  tictac.Tic();
171 
172  const size_t nLM1 = lm1->size();
173  const size_t nLM2 = lm2->size();
174 
175  // At least two landmarks at each map!
176  // ------------------------------------------------------
177  if (nLM1 < 2 || nLM2 < 2)
178  {
179  outInfo.goodness = 0;
180  }
181  else
182  {
183  //#define METHOD_FFT
184  //#define DEBUG_SHOW_CORRELATIONS
185 
186  // Compute correlation between landmarks:
187  // ---------------------------------------------
188  CMatrixFloat CORR(lm1->size(), lm2->size()), auxCorr;
189  CImage im1, im2; // Grayscale
190  CVectorFloat corr;
191  unsigned int corrsCount = 0;
192  std::vector<bool> hasCorr(nLM1, false);
193 
194  const double thres_max = options.threshold_max;
195  const double thres_delta = options.threshold_delta;
196 
197  // CDisplayWindowPlots::Ptr auxWin;
198  if (options.debug_show_corrs)
199  {
200  // auxWin = CDisplayWindowPlots::Ptr( new
201  // CDisplayWindowPlots("Individual corr.") );
202  std::cerr << "Warning: options.debug_show_corrs has no effect "
203  "since MRPT 0.9.1\n";
204  }
205 
206  for (size_t idx1 = 0; idx1 < nLM1; idx1++)
207  {
208  // CVectorFloat corrs_indiv;
209  vector<pair<size_t, float>> corrs_indiv; // (index, distance);
210  // Index is used to
211  // recover the original
212  // index after sorting.
213  vector<float> corrs_indiv_only;
214  corrs_indiv.reserve(nLM2);
215  corrs_indiv_only.reserve(nLM2);
216 
217  for (size_t idx2 = 0; idx2 < nLM2; idx2++)
218  {
219  float minDist;
220  minDist =
221  lm1->landmarks.get(idx1)->features[0].descriptorDistanceTo(
222  lm2->landmarks.get(idx2)->features[0]);
223 
224  corrs_indiv.emplace_back(idx2, minDist);
225  corrs_indiv_only.push_back(minDist);
226  } // end for idx2
227 
228  const double corr_best = mrpt::math::minimum(corrs_indiv_only);
229 
230  // Sort the list and keep the N best features:
231  std::sort(corrs_indiv.begin(), corrs_indiv.end(), myVectorOrder);
232 
233  // const size_t nBestToKeep = std::min( (size_t)30,
234  // corrs_indiv.size() );
235  const size_t nBestToKeep = corrs_indiv.size();
236 
237  for (size_t w = 0; w < nBestToKeep; w++)
238  {
239  if (corrs_indiv[w].second <= thres_max &&
240  corrs_indiv[w].second <= (corr_best + thres_delta))
241  {
242  idxs1.push_back(idx1);
243  idxs2.push_back(corrs_indiv[w].first);
244  outInfo.correspondences_dists_maha.emplace_back(
245  idx1, corrs_indiv[w].first, corrs_indiv[w].second);
246  }
247  }
248  } // end for idx1
249 
250  // Save an image with each feature and its matches:
251  if (options.save_feat_coors)
252  {
254  mrpt::system::createDirectory("grid_feats");
255 
256  std::map<size_t, std::set<size_t>> corrs_by_idx;
257  for (size_t l = 0; l < idxs1.size(); l++)
258  corrs_by_idx[idxs1[l]].insert(idxs2[l]);
259 
260  for (auto& it : corrs_by_idx)
261  {
262  CMatrixFloat descriptor1;
263  lm1->landmarks.get(it.first)
264  ->features[0]
265  .getFirstDescriptorAsMatrix(descriptor1);
266 
267  im1.setFromMatrix(descriptor1, true /*normalized*/);
268 
269  const size_t FEAT_W = im1.getWidth();
270  const size_t FEAT_H = im1.getHeight();
271  const size_t nF = it.second.size();
272 
273  CImage img_compose(FEAT_W * 2 + 15, 10 + (5 + FEAT_H) * nF);
274  img_compose.filledRectangle(
275  0, 0, img_compose.getWidth() - 1,
276  img_compose.getHeight() - 1, TColor::black());
277 
278  img_compose.drawImage(5, 5, im1);
279 
280  size_t j;
281  std::set<size_t>::iterator it_j;
282  string fil =
283  format("grid_feats/_FEAT_MATCH_%03i", (int)it.first);
284 
285  for (j = 0, it_j = it.second.begin(); j < nF; ++j, ++it_j)
286  {
287  fil += format("_%u", static_cast<unsigned int>(*it_j));
288 
289  CMatrixFloat descriptor2;
290  lm2->landmarks.get(*it_j)
291  ->features[0]
292  .getFirstDescriptorAsMatrix(descriptor2);
293  im2.setFromMatrix(descriptor2, true);
294  img_compose.drawImage(
295  10 + FEAT_W, 5 + j * (FEAT_H + 5), im2);
296  }
297  fil += ".png";
298  img_compose.saveToFile(fil);
299  } // end for map
300  }
301 
302  // ------------------------------------------------------------------
303  // Create the list of correspondences from the lists: idxs1 & idxs2
304  // ------------------------------------------------------------------
305  correspondences.clear();
306  for (it1 = idxs1.begin(), it2 = idxs2.begin(); it1 != idxs1.end();
307  ++it1, ++it2)
308  {
310  mp.this_idx = *it1;
311  mp.this_x = lm1->landmarks.get(*it1)->pose_mean.x;
312  mp.this_y = lm1->landmarks.get(*it1)->pose_mean.y;
313  mp.this_z = lm1->landmarks.get(*it1)->pose_mean.z;
314 
315  mp.other_idx = *it2;
316  mp.other_x = lm2->landmarks.get(*it2)->pose_mean.x;
317  mp.other_y = lm2->landmarks.get(*it2)->pose_mean.y;
318  mp.other_z = lm2->landmarks.get(*it2)->pose_mean.z;
319  correspondences.push_back(mp);
320 
321  if (!hasCorr[*it1])
322  {
323  hasCorr[*it1] = true;
324  corrsCount++;
325  }
326  } // end for corres.
327 
328  outInfo.goodness = (2.0f * corrsCount) / (nLM1 + nLM2);
329 
330  // Compute the estimation using ALL the correspondences (NO ROBUST):
331  // ----------------------------------------------------------------------
332  mrpt::math::TPose2D noRobustEst;
333  if (!mrpt::tfest::se2_l2(correspondences, noRobustEst))
334  {
335  // There's no way to match the maps! e.g. no correspondences
336  outInfo.goodness = 0;
337  pdf_SOG->clear();
338  outInfo.sog1 = pdf_SOG;
339  outInfo.sog2 = pdf_SOG;
340  outInfo.sog3 = pdf_SOG;
341  }
342  else
343  {
344  outInfo.noRobustEstimation = mrpt::poses::CPose2D(noRobustEst);
346  "[CGridMapAligner] Overall estimation(%u corrs, total: "
347  "%u): (%.03f,%.03f,%.03fdeg)\n",
348  corrsCount, (unsigned)correspondences.size(),
349  outInfo.noRobustEstimation.x(), outInfo.noRobustEstimation.y(),
350  RAD2DEG(outInfo.noRobustEstimation.phi())));
351 
352  // The list of SOG modes & their corresponding sub-sets of
353  // matchings:
354  using TMapMatchingsToPoseMode = std::map<
356  TMapMatchingsToPoseMode sog_modes;
357 
358  // ---------------------------------------------------------------
359  // Now, we have to choose between the methods:
360  // - CGridMapAligner::amRobustMatch ("normal" RANSAC)
361  // - CGridMapAligner::amModifiedRANSAC
362  // ---------------------------------------------------------------
363  if (options.methodSelection == CGridMapAligner::amRobustMatch)
364  {
365  // ====================================================
366  // METHOD: "Normal" RANSAC
367  // ====================================================
368 
369  // RANSAC over the found correspondences:
370  // -------------------------------------------------
371  const unsigned int min_inliers =
372  options.ransac_minSetSizeRatio * (nLM1 + nLM2) / 2;
373 
374  mrpt::tfest::TSE2RobustParams tfest_params;
375  tfest_params.ransac_minSetSize = min_inliers;
376  tfest_params.ransac_maxSetSize = nLM1 + nLM2;
378  options.ransac_mahalanobisDistanceThreshold;
379  tfest_params.ransac_nSimulations = 0; // 0=auto
380  tfest_params.ransac_fuseByCorrsMatch = true;
381  tfest_params.ransac_fuseMaxDiffXY = 0.01;
382  tfest_params.ransac_fuseMaxDiffPhi = 0.1_deg;
383  tfest_params.ransac_algorithmForLandmarks = true;
384  tfest_params.probability_find_good_model =
385  options.ransac_prob_good_inliers;
386  tfest_params.verbose = false;
387 
388  mrpt::tfest::TSE2RobustResult tfest_result;
390  correspondences, options.ransac_SOG_sigma_m, tfest_params,
391  tfest_result);
392 
393  ASSERT_(pdf_SOG);
394  *pdf_SOG = tfest_result.transformation;
395  largestConsensusCorrs = tfest_result.largestSubSet;
396 
397  // Simplify the SOG by merging close modes:
398  // -------------------------------------------------
399  size_t nB = pdf_SOG->size();
400  outInfo.sog1 = pdf_SOG;
401 
402  // Keep only the most-likely Gaussian mode:
403  CPosePDFSOG::TGaussianMode best_mode;
404  best_mode.log_w = -std::numeric_limits<double>::max();
405 
406  for (size_t n = 0; n < pdf_SOG->size(); n++)
407  {
408  const CPosePDFSOG::TGaussianMode& m = (*pdf_SOG)[n];
409 
410  if (m.log_w > best_mode.log_w) best_mode = m;
411  }
412 
413  pdf_SOG->clear();
414  pdf_SOG->push_back(best_mode);
415  outInfo.sog2 = pdf_SOG;
416 
418  "[CGridMapAligner] amRobustMatch: "
419  << nB << " SOG modes reduced to " << pdf_SOG->size()
420  << " (most-likely) (min.inliers=" << min_inliers << ")\n");
421 
422  } // end of amRobustMatch
423  else
424  {
425  // ====================================================
426  // METHOD: "Modified" RANSAC
427  // ====================================================
428  mrpt::tfest::TMatchingPairList all_corrs = correspondences;
429 
430  const size_t nCorrs = all_corrs.size();
431  ASSERT_(nCorrs >= 2);
432 
433  pdf_SOG->clear(); // Start with 0 Gaussian modes
434 
435  // Build a points-map for exploiting its KD-tree:
436  // ----------------------------------------------------
437  CSimplePointsMap lm1_pnts, lm2_pnts;
438  lm1_pnts.reserve(nLM1);
439  for (size_t i = 0; i < nLM1; i++)
440  lm1_pnts.insertPoint(lm1->landmarks.get(i)->pose_mean);
441  lm2_pnts.reserve(nLM2);
442  for (size_t i = 0; i < nLM2; i++)
443  lm2_pnts.insertPoint(lm2->landmarks.get(i)->pose_mean);
444 
445  // RANSAC loop
446  // ---------------------
447  const size_t minInliersTOaccept =
448  round(options.ransac_minSetSizeRatio * 0.5 * (nLM1 + nLM2));
449  // Set an initial # of iterations:
450  const unsigned int ransac_min_nSimulations =
451  2 * (nLM1 + nLM2); // 1000;
452  unsigned int ransac_nSimulations =
453  10; // It doesn't matter actually, since will be changed in
454  // the first loop
455  const double probability_find_good_model = 0.9999;
456 
457  const double chi2_thres_dim1 =
458  mrpt::math::chi2inv(options.ransac_chi2_quantile, 1);
459  const double chi2_thres_dim2 =
460  mrpt::math::chi2inv(options.ransac_chi2_quantile, 2);
461 
462  // Generic 2x2 covariance matrix for all features in their local
463  // coords:
464  CMatrixDouble22 COV_pnt;
465  COV_pnt(0, 0) = COV_pnt(1, 1) =
466  square(options.ransac_SOG_sigma_m);
467 
468  // The absolute number of trials.
469  // in practice it's only important for a reduced number of
470  // correspondences, to avoid a dead-lock:
471  // It's the binomial coefficient:
472  // / n \ n! n * (n-1)
473  // | | = ----------- = -----------
474  // \ 2 / 2! (n-2)! 2
475  //
476  const unsigned int max_trials =
477  (nCorrs * (nCorrs - 1) / 2) *
478  5; // "*5" is just for safety...
479 
480  unsigned int iter = 0; // Valid iterations (those passing the
481  // first mahalanobis test)
482  unsigned int trials = 0; // counter of all iterations,
483  // including "iter" + failing ones.
484  while (iter < ransac_nSimulations &&
485  trials <
486  max_trials) // ransac_nSimulations can be dynamic
487  {
488  trials++;
489 
490  mrpt::tfest::TMatchingPairList tentativeSubSet;
491 
492  // Pick 2 random correspondences:
493  uint32_t idx1, idx2;
494  idx1 = getRandomGenerator().drawUniform32bit() % nCorrs;
495  do
496  {
497  idx2 = getRandomGenerator().drawUniform32bit() % nCorrs;
498  } while (idx1 == idx2); // Avoid a degenerated case!
499 
500  // Uniqueness of features:
501  if (all_corrs[idx1].this_idx == all_corrs[idx2].this_idx ||
502  all_corrs[idx1].this_idx == all_corrs[idx2].other_idx)
503  continue;
504  if (all_corrs[idx1].other_idx == all_corrs[idx2].this_idx ||
505  all_corrs[idx1].other_idx == all_corrs[idx2].other_idx)
506  continue;
507 
508  // Check the feasibility of this pair "idx1"-"idx2":
509  // The distance between the pair of points in MAP1 must be
510  // very close
511  // to that of their correspondences in MAP2:
512  const double corrs_dist1 =
514  all_corrs[idx1].this_x, all_corrs[idx1].this_y,
515  all_corrs[idx1].this_z, all_corrs[idx2].this_x,
516  all_corrs[idx2].this_y, all_corrs[idx2].this_z);
517 
518  const double corrs_dist2 =
520  all_corrs[idx1].other_x, all_corrs[idx1].other_y,
521  all_corrs[idx1].other_z, all_corrs[idx2].other_x,
522  all_corrs[idx2].other_y, all_corrs[idx2].other_z);
523 
524  // Is is a consistent possibility?
525  // We use a chi2 test (see paper for the derivation)
526  const double corrs_dist_chi2 =
527  square(square(corrs_dist1) - square(corrs_dist2)) /
528  (8.0 * square(options.ransac_SOG_sigma_m) *
529  (square(corrs_dist1) + square(corrs_dist2)));
530 
531  if (corrs_dist_chi2 > chi2_thres_dim1) continue; // Nope
532 
533  iter++; // Do not count iterations if they fail the test
534  // above.
535 
536  // before proceeding with this hypothesis, is it an old one?
537  bool is_new_hyp = true;
538  for (auto& sog_mode : sog_modes)
539  {
540  if (sog_mode.first.contains(all_corrs[idx1]) &&
541  sog_mode.first.contains(all_corrs[idx2]))
542  {
543  // Increment weight:
544  sog_mode.second.log_w =
545  std::log(std::exp(sog_mode.second.log_w) + 1.0);
546  is_new_hyp = false;
547  break;
548  }
549  }
550  if (!is_new_hyp) continue;
551 
552  // Ok, it's a new hypothesis:
553  tentativeSubSet.push_back(all_corrs[idx1]);
554  tentativeSubSet.push_back(all_corrs[idx2]);
555 
556  // Maintain a list of already used landmarks IDs in both
557  // maps to avoid repetitions:
558  std::vector<bool> used_landmarks1(nLM1, false);
559  std::vector<bool> used_landmarks2(nLM2, false);
560 
561  used_landmarks1[all_corrs[idx1].this_idx] = true;
562  used_landmarks1[all_corrs[idx2].this_idx] = true;
563  used_landmarks2[all_corrs[idx1].other_idx] = true;
564  used_landmarks2[all_corrs[idx2].other_idx] = true;
565 
566  // Build the transformation for these temptative
567  // correspondences:
568  bool keep_incorporating = true;
569  CPosePDFGaussian temptPose;
570  do // Incremently incorporate inliers:
571  {
572  if (!mrpt::tfest::se2_l2(tentativeSubSet, temptPose))
573  continue; // Invalid matching...
574 
575  // The computed cov is "normalized", i.e. must be
576  // multiplied by std^2_xy
577  temptPose.cov *= square(options.ransac_SOG_sigma_m);
578 
579  // Find the landmark in MAP2 with the best (maximum)
580  // product-integral:
581  // (i^* , j^*) = arg max_(i,j) \int p_i()p_j()
582  //----------------------------------------------------------------------
583  const double ccos = cos(temptPose.mean.phi());
584  const double ssin = sin(temptPose.mean.phi());
585 
586  CMatrixDouble22 Hc; // Jacobian wrt point_j
587  Hc(1, 1) = ccos;
588  Hc(0, 0) = ccos;
589  Hc(1, 0) = ssin;
590  Hc(0, 1) = -ssin;
591 
593  Hq; // Jacobian wrt transformation q
594  Hq(0, 0) = 1;
595  Hq(1, 1) = 1;
596 
597  TPoint2D p2_j_local;
598  vector<float> matches_dist;
599  std::vector<size_t> matches_idx;
600 
601  CPoint2DPDFGaussian pdf_M2_j;
602  CPoint2DPDFGaussian pdf_M1_i;
603 
604 // Use integral-of-product vs. mahalanobis distances to match:
605 #define GRIDMAP_USE_PROD_INTEGRAL
606 
607 #ifdef GRIDMAP_USE_PROD_INTEGRAL
608  double best_pair_value = 0;
609 #else
610  double best_pair_value =
611  std::numeric_limits<double>::max();
612 #endif
613  double best_pair_d2 =
614  std::numeric_limits<double>::max();
615  pair<size_t, size_t> best_pair_ij;
616 
617  //#define SHOW_CORRS
618 
619 #ifdef SHOW_CORRS
620  CDisplayWindowPlots win("Matches");
621 #endif
622  for (size_t j = 0; j < nLM2; j++)
623  {
624  if (used_landmarks2[j]) continue;
625 
626  lm2_pnts.getPoint(
627  j, p2_j_local); // In local coords.
628  pdf_M2_j.mean = mrpt::poses::CPoint2D(
629  temptPose.mean +
630  p2_j_local); // In (temptative) global coords:
631  pdf_M2_j.cov(0, 0) = pdf_M2_j.cov(1, 1) =
632  square(options.ransac_SOG_sigma_m);
633 
634 #ifdef SHOW_CORRS
635  win.plotEllipse(
636  pdf_M2_j.mean.x(), pdf_M2_j.mean.y(),
637  pdf_M2_j.cov, 2, "b-",
638  format("M2_%u", (unsigned)j), true);
639 #endif
640 
641  static const unsigned int N_KDTREE_SEARCHED = 3;
642 
643  // Look for a few close features which may be
644  // potential matches:
645  lm1_pnts.kdTreeNClosestPoint2DIdx(
646  pdf_M2_j.mean.x(), pdf_M2_j.mean.y(),
647  N_KDTREE_SEARCHED, matches_idx, matches_dist);
648 
649  // And for each one, compute the product-integral:
650  for (unsigned long u : matches_idx)
651  {
652  if (used_landmarks1[u]) continue;
653 
654  // Jacobian wrt transformation q
655  Hq(0, 2) =
656  -p2_j_local.x * ssin - p2_j_local.y * ccos;
657  Hq(1, 2) =
658  p2_j_local.x * ccos - p2_j_local.y * ssin;
659 
660  // COV_j = Hq \Sigma_q Hq^t + Hc Cj Hc^t
661  pdf_M1_i.cov =
662  mrpt::math::multiply_HCHt(Hc, COV_pnt);
663  pdf_M1_i.cov += mrpt::math::multiply_HCHt(
664  Hq, temptPose.cov);
665 
666  float px, py;
667  lm1_pnts.getPoint(u, px, py);
668  pdf_M1_i.mean.x(px);
669  pdf_M1_i.mean.y(py);
670 
671 #ifdef SHOW_CORRS
672  win.plotEllipse(
673  pdf_M1_i.mean.x(), pdf_M1_i.mean.y(),
674  pdf_M1_i.cov, 2, "r-",
675  format("M1_%u", (unsigned)matches_idx[u]),
676  true);
677 #endif
678 
679 // And now compute the product integral:
680 #ifdef GRIDMAP_USE_PROD_INTEGRAL
681  const double prod_ij =
682  pdf_M1_i.productIntegralWith(pdf_M2_j);
683 
684  if (prod_ij > best_pair_value)
685 #else
686  const double prod_ij =
687  pdf_M1_i.mean.distanceTo(pdf_M2_j.mean);
688  if (prod_ij < best_pair_value)
689 #endif
690  {
691  // const double prodint_ij =
692  // pdf_M1_i.productIntegralWith2D(pdf_M2_j);
693 
694  best_pair_value = prod_ij;
695  best_pair_ij.first = u;
696  best_pair_ij.second = j;
697 
698  best_pair_d2 =
699  square(pdf_M1_i.mahalanobisDistanceTo(
700  pdf_M2_j));
701  }
702  } // end for u (closest matches of LM2 in MAP 1)
703 
704 #ifdef SHOW_CORRS
705  win.axis_fit(true);
706  win.waitForKey();
707  win.clear();
708 #endif
709 
710  } // end for each LM2
711 
712  // Stop when the best choice has a bad mahal. dist.
713  keep_incorporating = false;
714 
715  // For the best (i,j), gate by the mahalanobis distance:
716  if (best_pair_d2 < chi2_thres_dim2)
717  {
718  // AND, also, check if the descriptors have some
719  // resemblance!!
720  // ----------------------------------------------------------------
721  // double feat_dist =
722  // lm1->landmarks.get(best_pair_ij.first)->features[0]->descriptorDistanceTo(*lm1->landmarks.get(best_pair_ij.second)->features[0]);
723  // if (feat_dist< options.threshold_max)
724  {
725  float p1_i_localx, p1_i_localy;
726  float p2_j_localx, p2_j_localy;
727  lm1_pnts.getPoint(
728  best_pair_ij.first, p1_i_localx,
729  p1_i_localy);
730  lm2_pnts.getPoint(
731  best_pair_ij.second, p2_j_localx,
732  p2_j_localy); // In local coords.
733 
734  used_landmarks1[best_pair_ij.first] = true;
735  used_landmarks2[best_pair_ij.second] = true;
736 
737  tentativeSubSet.push_back(
739  best_pair_ij.first, best_pair_ij.second,
740  p1_i_localx, p1_i_localy, 0, // MAP1
741  p2_j_localx, p2_j_localy, 0 // MAP2
742  ));
743 
744  keep_incorporating = true;
745  }
746  }
747 
748  } while (keep_incorporating);
749 
750  // Consider this pairing?
751  const size_t ninliers = tentativeSubSet.size();
752  if (ninliers > minInliersTOaccept)
753  {
755  newGauss.log_w = 0; // log(1); //
756  // std::log(static_cast<double>(nCoincidences));
757  newGauss.mean = temptPose.mean;
758  newGauss.cov = temptPose.cov;
759 
760  sog_modes[tentativeSubSet] = newGauss;
761 
762  // cout << "ITER: " << iter << " #inliers: " << ninliers
763  // << " q: " << temptPose.mean << endl;
764  }
765 
766  // Keep the largest consensus & dynamic # of steps:
767  if (largestConsensusCorrs.size() < ninliers)
768  {
769  largestConsensusCorrs = tentativeSubSet;
770 
771  // Update estimate of N, the number of trials to ensure
772  // we pick,
773  // with probability p, a data set with no outliers.
774  const double fracinliers =
775  ninliers /
776  static_cast<double>(std::min(nLM1, nLM2));
777  double pNoOutliers =
778  1 - pow(fracinliers,
779  static_cast<double>(
780  2.0)); // minimumSizeSamplesToFit
781 
782  pNoOutliers = std::max(
783  std::numeric_limits<double>::epsilon(),
784  pNoOutliers); // Avoid division by -Inf
785  pNoOutliers = std::min(
786  1.0 - std::numeric_limits<double>::epsilon(),
787  pNoOutliers); // Avoid division by 0.
788  // Number of
789  ransac_nSimulations =
790  log(1 - probability_find_good_model) /
791  log(pNoOutliers);
792 
793  if (ransac_nSimulations < ransac_min_nSimulations)
794  ransac_nSimulations = ransac_min_nSimulations;
795 
796  // if (verbose)
797  // cout << "[Align] Iter #" << iter << " Est. #iters: "
798  //<< ransac_nSimulations << " pNoOutliers=" <<
799  // pNoOutliers << " #inliers: " << ninliers << endl;
800  }
801 
802  } // end of RANSAC loop
803 
804  // Move SOG modes into pdf_SOG:
805  pdf_SOG->clear();
806  for (auto s = sog_modes.begin(); s != sog_modes.end(); ++s)
807  {
809  "SOG mode: " << s->second.mean
810  << " inliers: " << s->first.size());
811  pdf_SOG->push_back(s->second);
812  }
813 
814  // Normalize:
815  if (pdf_SOG->size() > 0) pdf_SOG->normalizeWeights();
816 
817  // Simplify the SOG by merging close modes:
818  // -------------------------------------------------
819  size_t nB = pdf_SOG->size();
820  outInfo.sog1 = pdf_SOG;
821 
822  CTicTac merge_clock;
823  pdf_SOG->mergeModes(options.maxKLd_for_merge, false);
824  const double merge_clock_tim = merge_clock.Tac();
825 
826  outInfo.sog2 = pdf_SOG;
827  size_t nA = pdf_SOG->size();
829  "[CGridMapAligner] amModifiedRANSAC: %u SOG modes "
830  "merged to %u in %.03fsec\n",
831  (unsigned int)nB, (unsigned int)nA, merge_clock_tim));
832 
833  } // end of amModifiedRANSAC
834 
835  // Save best corrs:
836  if (options.debug_save_map_pairs)
837  {
838  static unsigned int NN = 0;
839  static const COccupancyGridMap2D* lastM1 = nullptr;
840  if (lastM1 != m1)
841  {
842  lastM1 = m1;
843  NN = 0;
844  }
846  "Largest consensus: %u",
847  static_cast<unsigned>(largestConsensusCorrs.size()));
848  CEnhancedMetaFile::LINUX_IMG_WIDTH(
849  m1->getSizeX() + m2->getSizeX() + 50);
850  CEnhancedMetaFile::LINUX_IMG_HEIGHT(
851  max(m1->getSizeY(), m2->getSizeY()) + 50);
852 
853  for (auto s = sog_modes.begin(); s != sog_modes.end(); ++s)
854  {
855  COccupancyGridMap2D::saveAsEMFTwoMapsWithCorrespondences(
856  format("__debug_corrsGrid_%05u.emf", NN), m1, m2,
857  s->first);
858  COccupancyGridMap2D::saveAsBitmapTwoMapsWithCorrespondences(
859  format("__debug_corrsGrid_%05u.png", NN), m1, m2,
860  s->first);
861  ++NN;
862  }
863  }
864 
865  // --------------------------------------------------------------------
866  // At this point:
867  // - "pdf_SOG": has the resulting PDF with the SOG (from whatever
868  // method)
869  // - "largestConsensusCorrs": The 'best' set of correspondences
870  //
871  // Now: If we had a multi-metric map, use the points map to improve
872  // the estimation with ICP.
873  // --------------------------------------------------------------------
874  if (multimap1 && multimap2 &&
875  multimap1->countMapsByClass<CSimplePointsMap>() != 0 &&
876  multimap2->countMapsByClass<CSimplePointsMap>() != 0)
877  {
878  auto pnts1 = multimap1->mapByClass<CSimplePointsMap>();
879  auto pnts2 = multimap2->mapByClass<CSimplePointsMap>();
880 
881  CICP icp;
882  CICP::TReturnInfo icpInfo;
883 
884  icp.options.maxIterations = 20;
885  icp.options.smallestThresholdDist = 0.05f;
886  icp.options.thresholdDist = 0.75f;
887 
888  // Invoke ICP once for each mode in the SOG:
889  size_t cnt = 0;
890  outInfo.icp_goodness_all_sog_modes.clear();
891  for (auto i = pdf_SOG->begin(); i != pdf_SOG->end(); ++cnt)
892  {
893  CPosePDF::Ptr icp_est =
894  icp.Align(pnts1.get(), pnts2.get(), (i)->mean, icpInfo);
895 
896  //(i)->cov(0,0) += square( 0.05 );
897  //(i)->cov(1,1) += square( 0.05 );
898  //(i)->cov(2,2) += square( 0.05_deg );
899 
900  CPosePDFGaussian i_gauss(i->mean, i->cov);
901  CPosePDFGaussian icp_gauss(icp_est->getMeanVal(), i->cov);
902 
903  const double icp_maha_dist =
904  i_gauss.mahalanobisDistanceTo(icp_gauss);
905 
907  "ICP " << cnt << " log-w: " << i->log_w
908  << " Goodness: " << 100 * icpInfo.goodness
909  << " D_M= " << icp_maha_dist);
911  "final pos: " << icp_est->getMeanVal());
912  MRPT_LOG_INFO_STREAM(" org pos: " << i->mean);
913 
914  outInfo.icp_goodness_all_sog_modes.push_back(
915  icpInfo.goodness);
916 
917  // Discard?
918  if (icpInfo.goodness > options.min_ICP_goodness &&
919  icp_maha_dist < options.max_ICP_mahadist)
920  {
921  icp_est->getMean((i)->mean);
922  ++i;
923  }
924  else
925  {
926  // Delete:
927  i = pdf_SOG->erase(i);
928  }
929 
930  } // end for i
931 
932  // Merge:
933  outInfo.sog3 = pdf_SOG;
934 
935  pdf_SOG->mergeModes(options.maxKLd_for_merge, false);
937  "[CGridMapAligner] " << pdf_SOG->size()
938  << " SOG modes merged after ICP.");
939 
940  } // end multimapX
941 
942  } // end of, yes, we have enough correspondences
943 
944  } // end of: yes, there are landmarks in the grid maps!
945 
946  outInfo.executionTime = tictac.Tac();
947 
948  return pdf_SOG;
949 
950  MRPT_END
951 }
952 
953 /*---------------------------------------------------------------
954  AlignPDF_correlation
955 ---------------------------------------------------------------*/
956 CPosePDF::Ptr CGridMapAligner::AlignPDF_correlation(
957  const mrpt::maps::CMetricMap* mm1, const mrpt::maps::CMetricMap* mm2,
958  [[maybe_unused]] const CPosePDFGaussian& initialEstimationPDF,
959  TReturnInfo& outInfo)
960 {
961  MRPT_START
962 
963  //#define CORRELATION_SHOW_DEBUG
964 
965  mrpt::system::CTicTac tictac;
966  tictac.Tic();
967 
968  // Asserts:
969  // -----------------
972  const auto* m1 = dynamic_cast<const COccupancyGridMap2D*>(mm1);
973  const auto* m2 = dynamic_cast<const COccupancyGridMap2D*>(mm2);
974 
975  ASSERT_EQUAL_(m1->getResolution(), m2->getResolution());
976 
977  // The PDF to estimate:
978  // ------------------------------------------------------
979  CPosePDFGaussian::Ptr PDF = std::make_shared<CPosePDFGaussian>();
980 
981  // Determine the extension to compute the correlation into:
982  // ----------------------------------------------------------
983  float phiResolution = DEG2RAD(0.2f);
984  float phiMin = -M_PIf + 0.5f * phiResolution;
985  float phiMax = M_PIf;
986 
987  // Compute the difference between maps for each (u,v) pair!
988  // --------------------------------------------------------------
989  float phi;
990  float pivotPt_x = 0.5f * (m1->getXMax() + m1->getXMin());
991  float pivotPt_y = 0.5f * (m1->getYMax() + m1->getYMin());
992  COccupancyGridMap2D map2_mod;
993  CImage map1_img, map2_img;
994  float currentMaxCorr = -1e6f;
995 
996  m1->getAsImage(map1_img);
997 
998  map2_mod.setSize(
999  m1->getXMin(), m1->getXMax(), m1->getYMin(), m1->getYMax(),
1000  m1->getResolution());
1001  size_t map2_lx = map2_mod.getSizeX();
1002  size_t map2_ly = map2_mod.getSizeY();
1003  CMatrixF outCrossCorr, bestCrossCorr;
1004  float map2width_2 = 0.5f * (map2_mod.getXMax() - map2_mod.getXMin());
1005 
1006 #ifdef CORRELATION_SHOW_DEBUG
1007  CDisplayWindow* win = new CDisplayWindow("corr");
1008  CDisplayWindow* win2 = new CDisplayWindow("map2_mod");
1009 #endif
1010 
1011  // --------------------------------------------------------
1012  // Use FFT-based correlation for each orientation:
1013  // --------------------------------------------------------
1014  for (phi = phiMin; phi < phiMax; phi += phiResolution)
1015  {
1016  // Create the displaced map2 grid, for the size of map1:
1017  // --------------------------------------------------------
1018  CPose2D v2(
1019  pivotPt_x - cos(phi) * map2width_2,
1020  pivotPt_y - sin(phi) * map2width_2,
1021  phi); // Rotation point: the centre of img1:
1022  CPoint2D v1, v3;
1023  v2 = CPose2D(0, 0, 0) - v2; // Inverse
1024 
1025  for (size_t cy2 = 0; cy2 < map2_ly; cy2++)
1026  {
1027  COccupancyGridMap2D::cellType* row = map2_mod.getRow(cy2);
1028  for (size_t cx2 = 0; cx2 < map2_lx; cx2++)
1029  {
1030  v3 = v2 + CPoint2D(map2_mod.idx2x(cx2), map2_mod.idx2y(cy2));
1031  *row++ = m2->p2l(m2->getPos(v3.x(), v3.y()));
1032  }
1033  }
1034 
1035  map2_mod.getAsImage(map2_img);
1036  // map2_img.saveToBMP("__debug_map2mod.bmp");
1037 
1038  // Compute the correlation:
1039  map1_img.cross_correlation_FFT(
1040  map2_img, outCrossCorr, -1, -1, -1, -1,
1041  127, // Bias to be substracted
1042  127 // Bias to be substracted
1043  );
1044 
1045  float corrPeak = outCrossCorr.maxCoeff();
1046  MRPT_LOG_INFO_FMT("phi = %fdeg \tmax corr=%f", RAD2DEG(phi), corrPeak);
1047 
1048  // Keep the maximum:
1049  if (corrPeak > currentMaxCorr)
1050  {
1051  currentMaxCorr = corrPeak;
1052  bestCrossCorr = outCrossCorr;
1053  PDF->mean.phi(phi);
1054  }
1055 
1056 #ifdef CORRELATION_SHOW_DEBUG
1057  outCrossCorr.adjustRange(0, 1);
1058  CImage aux(outCrossCorr, true);
1059  win->showImage(aux);
1060  win2->showImage(map2_img);
1061  std::this_thread::sleep_for(5ms);
1062 #endif
1063 
1064  } // end for phi
1065 
1066  outInfo.executionTime = tictac.Tac();
1067 
1068 #ifdef CORRELATION_SHOW_DEBUG
1069  CImage aux;
1070  aux.setFromMatrix(bestCrossCorr, false /* do normalization [0,1]*/);
1071  aux.saveToFile("_debug_best_corr.png");
1072  delete win;
1073  delete win2;
1074 #endif
1075 
1076  // Transform the best corr matrix peak into coordinates:
1077  std::size_t uMax, vMax;
1078  currentMaxCorr = bestCrossCorr.maxCoeff(uMax, vMax);
1079 
1080  PDF->mean.x(m1->idx2x(uMax));
1081  PDF->mean.y(m1->idx2y(vMax));
1082 
1083  return PDF;
1084 
1085  // Done!
1086  MRPT_END
1087 }
1088 
1089 /*---------------------------------------------------------------
1090  TConfigParams
1091  ---------------------------------------------------------------*/
1092 CGridMapAligner::TConfigParams::TConfigParams() : feature_detector_options() {}
1093 /*---------------------------------------------------------------
1094  dumpToTextStream
1095  ---------------------------------------------------------------*/
1097 {
1098  out << "\n----------- [CGridMapAligner::TConfigParams] ------------ \n\n";
1099 
1100  LOADABLEOPTS_DUMP_VAR(methodSelection, int)
1101  LOADABLEOPTS_DUMP_VAR(featsPerSquareMeter, float)
1102  LOADABLEOPTS_DUMP_VAR(threshold_max, float)
1103  LOADABLEOPTS_DUMP_VAR(threshold_delta, float)
1104  LOADABLEOPTS_DUMP_VAR(min_ICP_goodness, float)
1105  LOADABLEOPTS_DUMP_VAR(max_ICP_mahadist, double)
1106  LOADABLEOPTS_DUMP_VAR(maxKLd_for_merge, float)
1107  LOADABLEOPTS_DUMP_VAR(ransac_minSetSizeRatio, float)
1109  LOADABLEOPTS_DUMP_VAR(ransac_chi2_quantile, double)
1110  LOADABLEOPTS_DUMP_VAR(ransac_prob_good_inliers, double)
1111  LOADABLEOPTS_DUMP_VAR(ransac_SOG_sigma_m, float)
1112  LOADABLEOPTS_DUMP_VAR(save_feat_coors, bool)
1113  LOADABLEOPTS_DUMP_VAR(debug_show_corrs, bool)
1114  LOADABLEOPTS_DUMP_VAR(debug_save_map_pairs, bool)
1115 
1116  LOADABLEOPTS_DUMP_VAR(feature_descriptor, int)
1117 
1118  feature_detector_options.dumpToTextStream(out);
1119 
1120  out << "\n";
1121 }
1122 
1123 /*---------------------------------------------------------------
1124  loadFromConfigFile
1125  ---------------------------------------------------------------*/
1127  const mrpt::config::CConfigFileBase& iniFile, const std::string& section)
1128 {
1129  methodSelection =
1130  iniFile.read_enum(section, "methodSelection", methodSelection);
1131 
1133  featsPerSquareMeter, float, iniFile, section)
1134  MRPT_LOAD_CONFIG_VAR(ransac_SOG_sigma_m, float, iniFile, section)
1135 
1136  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(threshold_max, float, iniFile, section)
1137  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(threshold_delta, float, iniFile, section)
1138 
1139  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(min_ICP_goodness, float, iniFile, section)
1140  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(max_ICP_mahadist, double, iniFile, section)
1141 
1142  MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(maxKLd_for_merge, float, iniFile, section)
1144  ransac_minSetSizeRatio, float, iniFile, section)
1148  ransac_chi2_quantile, double, iniFile, section)
1150  ransac_prob_good_inliers, double, iniFile, section)
1151 
1152  MRPT_LOAD_CONFIG_VAR(save_feat_coors, bool, iniFile, section)
1153  MRPT_LOAD_CONFIG_VAR(debug_show_corrs, bool, iniFile, section)
1154  MRPT_LOAD_CONFIG_VAR(debug_save_map_pairs, bool, iniFile, section)
1155 
1156  feature_descriptor = iniFile.read_enum(
1157  section, "feature_descriptor", feature_descriptor, true);
1158  feature_detector_options.loadFromConfigFile(iniFile, section);
1159 }
1160 
1162  [[maybe_unused]] const mrpt::maps::CMetricMap* m1,
1163  [[maybe_unused]] const mrpt::maps::CMetricMap* m2,
1164  [[maybe_unused]] const CPose3DPDFGaussian& initialEstimationPDF,
1165  [[maybe_unused]] mrpt::optional_ref<TMetricMapAlignmentResult> outInfo)
1166 {
1167  THROW_EXCEPTION("Align3D method not applicable to CGridMapAligner");
1168 }
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
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:192
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
T x
X,Y coordinates.
Definition: TPoint2D.h:25
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:92
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Definition: CICP.h:64
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.
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:1142
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
size_t getHeight() const override
Returns the height of the image in pixels.
Definition: CImage.cpp:849
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:639
STL namespace.
double mahalanobisDistanceTo(const CPosePDFGaussian &theOther)
Computes the Mahalanobis distance between the centers of two Gaussians.
T::Ptr mapByClass(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 ...
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...
std::optional< std::reference_wrapper< T > > optional_ref
Shorter name for std::optional<std::reference_wrapper<T>>
Definition: optional_ref.h:20
The ICP algorithm return information.
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
double distanceTo(const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const
Returns the Euclidean distance to another pose/point:
Definition: CPoseOrPoint.h:214
bool verbose
(Default=false)
Definition: se2.h:111
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
static bool myVectorOrder(const pair< size_t, float > &o1, const pair< size_t, float > &o2)
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:818
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.
double phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:86
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
Definition: exceptions.h:137
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:205
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
#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:844
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)
double goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
Definition: CICP.h:200
#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
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:1435
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
return_t square(const num_t x)
Inline function for the square of a number.
#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.
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
mrpt::poses::CPose3DPDF::Ptr Align3DPDF(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt) override
Not applicable in this class, will launch an exception if used.
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...
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:902
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:330
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.
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:148
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)
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: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020