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



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: bef67d9c5 Mon Apr 15 00:03:11 2019 +0200 at lun abr 15 00:10:13 CEST 2019