46 switch (options.methodSelection)
48 case CGridMapAligner::amCorrelation:
49 return AlignPDF_correlation(
50 mm1, mm2, initialEstimationPDF, runningTime, info);
52 case CGridMapAligner::amModifiedRANSAC:
53 case CGridMapAligner::amRobustMatch:
55 return AlignPDF_robustMatch(
56 mm1, mm2, initialEstimationPDF, runningTime, info);
65 bool myVectorOrder(
const pair<size_t, float>& o1,
const pair<size_t, float>& o2)
67 return o1.second < o2.second;
81 options.methodSelection == CGridMapAligner::amRobustMatch ||
82 options.methodSelection == CGridMapAligner::amModifiedRANSAC);
97 std::vector<size_t> idxs1, idxs2;
127 "Metric maps must be of classes COccupancyGridMap2D or " 133 "Different resolutions for m1, m2:\n" 134 "\tres(m1) = %f\n\tres(m2) = %f\n",
155 m_grid_feat_extr.extractFeatures(
156 *m1, *lm1, N1, options.feature_descriptor,
157 options.feature_detector_options);
158 m_grid_feat_extr.extractFeatures(
159 *m2, *lm2, N2, options.feature_descriptor,
160 options.feature_detector_options);
168 const size_t nLM1 = lm1->size();
169 const size_t nLM2 = lm2->size();
173 if (nLM1 < 2 || nLM2 < 2)
185 CImage im1(1, 1, 1), im2(1, 1, 1);
187 unsigned int corrsCount = 0;
188 std::vector<bool> hasCorr(nLM1,
false);
190 const double thres_max = options.threshold_max;
191 const double thres_delta = options.threshold_delta;
194 if (options.debug_show_corrs)
198 std::cerr <<
"Warning: options.debug_show_corrs has no effect " 199 "since MRPT 0.9.1\n";
202 for (
size_t idx1 = 0; idx1 < nLM1; idx1++)
205 vector<pair<size_t, float>> corrs_indiv;
209 vector<float> corrs_indiv_only;
210 corrs_indiv.reserve(nLM2);
211 corrs_indiv_only.reserve(nLM2);
213 for (
size_t idx2 = 0; idx2 < nLM2; idx2++)
217 lm1->landmarks.get(idx1)->features[0]->descriptorDistanceTo(
218 *lm2->landmarks.get(idx2)->features[0]);
220 corrs_indiv.push_back(std::make_pair(idx2, minDist));
221 corrs_indiv_only.push_back(minDist);
231 std::sort(corrs_indiv.begin(), corrs_indiv.end(),
myVectorOrder);
235 const size_t nBestToKeep = corrs_indiv.size();
237 for (
size_t w = 0;
w < nBestToKeep;
w++)
239 if (corrs_indiv[
w].second <= thres_max &&
240 corrs_indiv[
w].second <= (corr_best + thres_delta))
242 idxs1.push_back(idx1);
243 idxs2.push_back(corrs_indiv[
w].
first);
246 idx1, corrs_indiv[
w].
first, corrs_indiv[
w].second));
251 if (options.debug_show_corrs)
253 auxWin->setWindowTitle(
format(
"Corr: %i - rest",
int(idx1)));
255 auxWin->plot(corrs_indiv_only,
".3",
"the_corr");
258 xs[0]=0; xs[1]=corrs_indiv_only.size()+1;
260 ys[0]=ys[1] = corr_best+thres_delta;
261 auxWin->plot(xs,ys,
"g",
"the_thres");
263 if (idx1==0) auxWin->axis_fit();
264 auxWin->waitForKey();
271 if (options.save_feat_coors)
276 std::map<size_t, std::set<size_t>> corrs_by_idx;
277 for (
size_t l = 0; l < idxs1.size(); l++)
278 corrs_by_idx[idxs1[l]].insert(idxs2[l]);
280 for (std::map<
size_t, std::set<size_t>>::
iterator it =
281 corrs_by_idx.begin();
282 it != corrs_by_idx.end(); ++it)
285 lm1->landmarks.get(it->first)
287 ->getFirstDescriptorAsMatrix(descriptor1);
289 im1 =
CImage(descriptor1,
true);
291 const size_t FEAT_W = im1.getWidth();
292 const size_t FEAT_H = im1.getHeight();
293 const size_t nF = it->second.size();
295 CImage img_compose(FEAT_W * 2 + 15, 10 + (5 + FEAT_H) * nF);
298 img_compose.
getHeight() - 1, TColor::black());
305 format(
"grid_feats/_FEAT_MATCH_%03i", (
int)it->first);
307 for (j = 0, it_j = it->second.begin(); j < nF; ++j, ++it_j)
309 fil +=
format(
"_%u", static_cast<unsigned int>(*it_j));
312 lm2->landmarks.get(*it_j)
314 ->getFirstDescriptorAsMatrix(descriptor2);
315 im2 =
CImage(descriptor2,
true);
317 10 + FEAT_W, 5 + j * (FEAT_H + 5), im2);
327 correspondences.clear();
328 for (it1 = idxs1.begin(), it2 = idxs2.begin(); it1 != idxs1.end();
333 mp.
this_x = lm1->landmarks.get(*it1)->pose_mean.x;
334 mp.
this_y = lm1->landmarks.get(*it1)->pose_mean.y;
335 mp.
this_z = lm1->landmarks.get(*it1)->pose_mean.z;
338 mp.
other_x = lm2->landmarks.get(*it2)->pose_mean.x;
339 mp.
other_y = lm2->landmarks.get(*it2)->pose_mean.y;
340 mp.
other_z = lm2->landmarks.get(*it2)->pose_mean.z;
341 correspondences.push_back(mp);
345 hasCorr[*it1] =
true;
350 outInfo.
goodness = (2.0f * corrsCount) / (nLM1 + nLM2);
360 outInfo.
sog1 = pdf_SOG;
361 outInfo.
sog2 = pdf_SOG;
362 outInfo.
sog3 = pdf_SOG;
369 "[CGridMapAligner] Overall estimation(%u corrs, total: " 370 "%u): (%.03f,%.03f,%.03fdeg)\n",
371 corrsCount, (
unsigned)correspondences.size(),
378 using TMapMatchingsToPoseMode =
381 TMapMatchingsToPoseMode sog_modes;
388 if (options.methodSelection == CGridMapAligner::amRobustMatch)
396 const unsigned int min_inliers =
397 options.ransac_minSetSizeRatio * (nLM1 + nLM2) / 2;
403 options.ransac_mahalanobisDistanceThreshold;
410 options.ransac_prob_good_inliers;
415 correspondences, options.ransac_SOG_sigma_m, tfest_params,
424 size_t nB = pdf_SOG->size();
425 outInfo.
sog1 = pdf_SOG;
429 best_mode.
log_w = -std::numeric_limits<double>::max();
431 for (
size_t n = 0;
n < pdf_SOG->size();
n++)
439 pdf_SOG->push_back(best_mode);
440 outInfo.
sog2 = pdf_SOG;
443 "[CGridMapAligner] amRobustMatch: " 444 << nB <<
" SOG modes reduced to " << pdf_SOG->size()
445 <<
" (most-likely) (min.inliers=" << min_inliers <<
")\n");
455 const size_t nCorrs = all_corrs.size();
464 for (
size_t i = 0; i < nLM1; i++)
465 lm1_pnts.
insertPoint(lm1->landmarks.get(i)->pose_mean);
467 for (
size_t i = 0; i < nLM2; i++)
468 lm2_pnts.
insertPoint(lm2->landmarks.get(i)->pose_mean);
472 const size_t minInliersTOaccept =
473 round(options.ransac_minSetSizeRatio * 0.5 * (nLM1 + nLM2));
475 const unsigned int ransac_min_nSimulations =
477 unsigned int ransac_nSimulations =
480 const double probability_find_good_model = 0.9999;
482 const double chi2_thres_dim1 =
484 const double chi2_thres_dim2 =
490 COV_pnt.get_unsafe(0, 0) = COV_pnt.get_unsafe(1, 1) =
491 square(options.ransac_SOG_sigma_m);
501 const unsigned int max_trials =
502 (nCorrs * (nCorrs - 1) / 2) *
505 unsigned int iter = 0;
507 unsigned int trials = 0;
509 while (iter < ransac_nSimulations &&
523 }
while (idx1 == idx2);
526 if (all_corrs[idx1].this_idx == all_corrs[idx2].this_idx ||
527 all_corrs[idx1].this_idx == all_corrs[idx2].other_idx)
529 if (all_corrs[idx1].other_idx == all_corrs[idx2].this_idx ||
530 all_corrs[idx1].other_idx == all_corrs[idx2].other_idx)
537 const double corrs_dist1 =
539 all_corrs[idx1].this_x, all_corrs[idx1].this_y,
540 all_corrs[idx1].this_z, all_corrs[idx2].this_x,
541 all_corrs[idx2].this_y, all_corrs[idx2].this_z);
543 const double corrs_dist2 =
545 all_corrs[idx1].other_x, all_corrs[idx1].other_y,
546 all_corrs[idx1].other_z, all_corrs[idx2].other_x,
547 all_corrs[idx2].other_y, all_corrs[idx2].other_z);
551 const double corrs_dist_chi2 =
553 (8.0 *
square(options.ransac_SOG_sigma_m) *
556 if (corrs_dist_chi2 > chi2_thres_dim1)
continue;
562 bool is_new_hyp =
true;
565 itOldHyps != sog_modes.end(); ++itOldHyps)
567 if (itOldHyps->first.contains(all_corrs[idx1]) &&
568 itOldHyps->first.contains(all_corrs[idx2]))
571 itOldHyps->second.log_w = std::log(
572 std::exp(itOldHyps->second.log_w) + 1.0);
577 if (!is_new_hyp)
continue;
580 tentativeSubSet.push_back(all_corrs[idx1]);
581 tentativeSubSet.push_back(all_corrs[idx2]);
585 std::vector<bool> used_landmarks1(nLM1,
false);
586 std::vector<bool> used_landmarks2(nLM2,
false);
588 used_landmarks1[all_corrs[idx1].this_idx] =
true;
589 used_landmarks1[all_corrs[idx2].this_idx] =
true;
590 used_landmarks2[all_corrs[idx1].other_idx] =
true;
591 used_landmarks2[all_corrs[idx2].other_idx] =
true;
595 bool keep_incorporating =
true;
604 temptPose.
cov *=
square(options.ransac_SOG_sigma_m);
612 const double ccos = cos(temptPose.
mean.
phi());
613 const double ssin = sin(temptPose.
mean.
phi());
616 Hc.get_unsafe(1, 1) = ccos;
617 Hc.get_unsafe(0, 0) = ccos;
618 Hc.get_unsafe(1, 0) = ssin;
619 Hc.get_unsafe(0, 1) = -ssin;
627 vector<float> matches_dist;
628 std::vector<size_t> matches_idx;
634 #define GRIDMAP_USE_PROD_INTEGRAL 636 #ifdef GRIDMAP_USE_PROD_INTEGRAL 637 double best_pair_value = 0;
639 double best_pair_value =
640 std::numeric_limits<double>::max();
642 double best_pair_d2 =
643 std::numeric_limits<double>::max();
644 pair<size_t, size_t> best_pair_ij;
649 CDisplayWindowPlots
win(
"Matches");
651 for (
size_t j = 0; j < nLM2; j++)
653 if (used_landmarks2[j])
continue;
660 pdf_M2_j.
cov.get_unsafe(0, 0) =
661 pdf_M2_j.
cov.get_unsafe(1, 1) =
662 square(options.ransac_SOG_sigma_m);
667 pdf_M2_j.
cov, 2,
"b-",
668 format(
"M2_%u", (
unsigned)j),
true);
671 static const unsigned int N_KDTREE_SEARCHED = 3;
677 N_KDTREE_SEARCHED, matches_idx, matches_dist);
680 for (
size_t u = 0; u < matches_idx.size(); u++)
682 if (used_landmarks1[matches_idx[u]])
continue;
685 Hq.get_unsafe(0, 2) =
686 -p2_j_local.
x * ssin - p2_j_local.
y * ccos;
687 Hq.get_unsafe(1, 2) =
688 p2_j_local.
x * ccos - p2_j_local.
y * ssin;
691 Hc.multiply_HCHt(COV_pnt, pdf_M1_i.
cov);
693 temptPose.
cov, pdf_M1_i.
cov,
true);
696 lm1_pnts.
getPoint(matches_idx[u], px, py);
703 pdf_M1_i.
cov, 2,
"r-",
704 format(
"M1_%u", (
unsigned)matches_idx[u]),
709 #ifdef GRIDMAP_USE_PROD_INTEGRAL 710 const double prod_ij =
715 if (prod_ij > best_pair_value)
717 const double prod_ij =
719 if (prod_ij < best_pair_value)
725 best_pair_value = prod_ij;
726 best_pair_ij.first = matches_idx[u];
727 best_pair_ij.second = j;
752 keep_incorporating =
false;
755 if (best_pair_d2 < chi2_thres_dim2)
764 float p1_i_localx, p1_i_localy;
765 float p2_j_localx, p2_j_localy;
767 best_pair_ij.first, p1_i_localx,
770 best_pair_ij.second, p2_j_localx,
773 used_landmarks1[best_pair_ij.first] =
true;
774 used_landmarks2[best_pair_ij.second] =
true;
776 tentativeSubSet.push_back(
778 best_pair_ij.first, best_pair_ij.second,
779 p1_i_localx, p1_i_localy, 0,
780 p2_j_localx, p2_j_localy, 0
783 keep_incorporating =
true;
787 }
while (keep_incorporating);
790 const size_t ninliers = tentativeSubSet.size();
791 if (ninliers > minInliersTOaccept)
797 newGauss.
cov = temptPose.
cov;
799 sog_modes[tentativeSubSet] = newGauss;
806 if (largestConsensusCorrs.size() < ninliers)
808 largestConsensusCorrs = tentativeSubSet;
813 const double fracinliers =
815 static_cast<double>(
std::min(nLM1, nLM2));
821 pNoOutliers = std::max(
822 std::numeric_limits<double>::epsilon(),
825 1.0 - std::numeric_limits<double>::epsilon(),
828 ransac_nSimulations =
829 log(1 - probability_find_good_model) /
832 if (ransac_nSimulations < ransac_min_nSimulations)
833 ransac_nSimulations = ransac_min_nSimulations;
847 s != sog_modes.end(); ++
s)
849 cout <<
"SOG mode: " <<
s->second.mean
850 <<
" inliers: " <<
s->first.size() << endl;
851 pdf_SOG->push_back(
s->second);
855 if (pdf_SOG->size() > 0) pdf_SOG->normalizeWeights();
859 size_t nB = pdf_SOG->size();
860 outInfo.
sog1 = pdf_SOG;
863 pdf_SOG->mergeModes(options.maxKLd_for_merge,
false);
864 const double merge_clock_tim = merge_clock.
Tac();
866 outInfo.
sog2 = pdf_SOG;
867 size_t nA = pdf_SOG->size();
870 "[CGridMapAligner] amModifiedRANSAC: %u SOG modes " 871 "merged to %u in %.03fsec\n",
872 (
unsigned int)nB, (
unsigned int)nA, merge_clock_tim));
877 if (options.debug_save_map_pairs)
879 static unsigned int NN = 0;
887 " Largest consensus: %u\n",
888 static_cast<unsigned>(largestConsensusCorrs.size()));
889 CEnhancedMetaFile::LINUX_IMG_WIDTH(
891 CEnhancedMetaFile::LINUX_IMG_HEIGHT(
896 s != sog_modes.end(); ++
s)
898 COccupancyGridMap2D::saveAsEMFTwoMapsWithCorrespondences(
899 format(
"__debug_corrsGrid_%05u.emf", NN), m1, m2,
901 COccupancyGridMap2D::saveAsBitmapTwoMapsWithCorrespondences(
902 format(
"__debug_corrsGrid_%05u.png", NN), m1, m2,
917 if (multimap1 && multimap2 && !multimap1->
m_pointsMaps.empty() &&
938 i != pdf_SOG->end(); ++cnt)
941 pnts1.get(), pnts2.get(), (i)->
mean,
nullptr, &icpInfo);
950 const double icp_maha_dist =
953 cout <<
"ICP " << cnt <<
" log-w: " << i->log_w
954 <<
" Goodness: " << 100 * icpInfo.
goodness 955 <<
" D_M= " << icp_maha_dist << endl;
956 cout <<
" final pos: " << icp_est->getMeanVal() << endl;
957 cout <<
" org pos: " << i->mean << endl;
963 if (icpInfo.
goodness > options.min_ICP_goodness &&
964 icp_maha_dist < options.max_ICP_mahadist)
966 icp_est->getMean((i)->
mean);
972 i = pdf_SOG->erase(i);
978 outInfo.
sog3 = pdf_SOG;
980 pdf_SOG->mergeModes(options.maxKLd_for_merge,
false);
982 "[CGridMapAligner] " << pdf_SOG->size()
983 <<
" SOG modes merged after ICP.");
994 "Refactor `info` so it is polymorphic and can use dynamic_cast<> here");
1003 *runningTime = tictac->
Tac();
1052 float phiResolution =
DEG2RAD(0.2f);
1053 float phiMin = -
M_PIf + 0.5f * phiResolution;
1054 float phiMax =
M_PIf;
1059 float pivotPt_x = 0.5f * (m1->getXMax() + m1->getXMin());
1060 float pivotPt_y = 0.5f * (m1->getYMax() + m1->getYMin());
1062 CImage map1_img, map2_img;
1063 float currentMaxCorr = -1e6f;
1065 m1->getAsImage(map1_img);
1068 m1->getXMin(), m1->getXMax(), m1->getYMin(), m1->getYMax(),
1069 m1->getResolution());
1070 size_t map2_lx = map2_mod.
getSizeX();
1071 size_t map2_ly = map2_mod.
getSizeY();
1072 CMatrix outCrossCorr, bestCrossCorr;
1073 float map2width_2 = 0.5f * (map2_mod.
getXMax() - map2_mod.
getXMin());
1075 #ifdef CORRELATION_SHOW_DEBUG 1076 CDisplayWindow*
win =
new CDisplayWindow(
"corr");
1077 CDisplayWindow* win2 =
new CDisplayWindow(
"map2_mod");
1083 for (phi = phiMin; phi < phiMax; phi += phiResolution)
1088 pivotPt_x - cos(phi) * map2width_2,
1089 pivotPt_y - sin(phi) * map2width_2,
1094 for (
unsigned int cy2 = 0; cy2 < map2_ly; cy2++)
1097 for (
unsigned int cx2 = 0; cx2 < map2_lx; cx2++)
1109 map2_img, outCrossCorr, -1, -1, -1, -1,
1114 float corrPeak = outCrossCorr.maxCoeff();
1115 printf(
"phi = %fdeg \tmax corr=%f\n",
RAD2DEG(phi), corrPeak);
1118 if (corrPeak > currentMaxCorr)
1120 currentMaxCorr = corrPeak;
1121 bestCrossCorr = outCrossCorr;
1125 #ifdef CORRELATION_SHOW_DEBUG 1126 outCrossCorr.adjustRange(0, 1);
1127 CImage aux(outCrossCorr,
true);
1128 win->showImage(aux);
1129 win2->showImage(map2_img);
1130 std::this_thread::sleep_for(5ms);
1137 *runningTime = tictac->Tac();
1141 bestCrossCorr.normalize(0, 1);
1142 CImage aux(bestCrossCorr,
true);
1145 #ifdef CORRELATION_SHOW_DEBUG 1151 CMatrix::Index uMax, vMax;
1152 currentMaxCorr = bestCrossCorr.maxCoeff(&uMax, &vMax);
1154 PDF->mean.x(m1->idx2x(uMax));
1155 PDF->mean.y(m1->idx2y(vMax));
1166 CGridMapAligner::TConfigParams::TConfigParams()
1170 feature_detector_options(),
1172 ransac_minSetSizeRatio(0.20f),
1173 ransac_SOG_sigma_m(0.10f),
1175 ransac_chi2_quantile(0.99),
1176 ransac_prob_good_inliers(0.9999),
1177 featsPerSquareMeter(0.015f),
1178 threshold_max(0.15f),
1179 threshold_delta(0.10f),
1180 min_ICP_goodness(0.30f),
1181 max_ICP_mahadist(10.0),
1182 maxKLd_for_merge(0.9),
1184 save_feat_coors(false),
1185 debug_show_corrs(false),
1186 debug_save_map_pairs(false)
1196 "\n----------- [CGridMapAligner::TConfigParams] ------------ \n\n");
1216 feature_detector_options.dumpToTextStream(out);
1228 iniFile.read_enum(section,
"methodSelection", methodSelection);
1231 featsPerSquareMeter,
float,
iniFile, section)
1242 ransac_minSetSizeRatio,
float,
iniFile, section)
1246 ransac_chi2_quantile,
double,
iniFile, section)
1248 ransac_prob_good_inliers,
double,
iniFile, section)
1254 feature_descriptor =
iniFile.read_enum(
1255 section,
"feature_descriptor", feature_descriptor,
true);
1256 feature_detector_options.loadFromConfigFile(
iniFile, section);
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.
double Tac() noexcept
Stops the stopwatch.
CPoint2D mean
The mean value.
double x() const
Common members of all points & poses classes.
double getArea() const
Returns the area of the gridmap, in square meters.
bool createDirectory(const std::string &dirName)
Creates a directory.
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.
double RAD2DEG(const double x)
Radians to degrees.
The struct for each mode:
float getResolution() const
Returns the resolution of the grid map.
ProxyFilterContainerByClass< mrpt::maps::CSimplePointsMap::Ptr, TListMaps > m_pointsMaps
STL-like proxy to access this kind of maps in maps.
double distanceTo(const CPoseOrPoint< OTHERCLASS > &b) const
Returns the Euclidean distance to another pose/point:
#define THROW_EXCEPTION(msg)
virtual 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.
A class for aligning two multi-metric maps (with an occupancy grid maps and a points map...
mrpt::poses::CPosePDF::Ptr Align(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose2D &grossEst, float *runningTime=nullptr, void *info=nullptr)
The method for aligning a pair of metric maps, aligning only 2D + orientation.
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...
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Parameters for se2_l2_robust().
double DEG2RAD(const double x)
Degrees to radians.
int16_t cellType
The type of the map cells:
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...
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)
Not applicable in this class, will launch an exception.
unsigned int ransac_nSimulations
(Default = 0) If set to 0, an adaptive algorithm is used to determine the number of iterations...
A high-performance stopwatch, with typical resolution of nanoseconds.
unsigned int ransac_minSetSize
(Default=3)
mrpt::containers::deepcopy_poly_ptr< mrpt::poses::CPosePDFSOG::Ptr > sog3
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
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.
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...
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...
std::map< KEY, VALUE, std::less< KEY >, mrpt::aligned_allocator_cpp11< std::pair< const KEY, VALUE > >> aligned_std_map
The ICP algorithm return information.
double smallestThresholdDist
The size for threshold such that iterations will stop, since it is considered precise enough...
TConfigParams options
The options employed by the ICP align.
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
GLubyte GLubyte GLubyte GLubyte w
mrpt::system::CTicTac CTicTac
bool verbose
(Default=false)
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.
CListGaussianModes::iterator iterator
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
mrpt::tfest::TMatchingPairList correspondences
All the found correspondences (not consistent)
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.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) 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.
unsigned int ransac_maxSetSize
(Default = 20)
A class for storing a map of 3D probabilistic landmarks.
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.
virtual void filledRectangle(int x0, int y0, int x1, int y1, const mrpt::img::TColor color)
Draws a filled rectangle.
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
unsigned int maxIterations
Maximum number of iterations to run.
bool ransac_algorithmForLandmarks
(Default = true) Use Mahalanobis distance (true) or Euclidean dist (false)
mrpt::math::CMatrixDouble33 cov
GLfloat GLfloat GLfloat GLfloat v3
string iniFile(myDataDir+string("benchmark-options.ini"))
unsigned int getSizeX() const
Returns the horizontal size of grid map in cells count.
ProxyFilterContainerByClass< mrpt::maps::COccupancyGridMap2D::Ptr, TListMaps > m_gridMaps
STL-like proxy to access this kind of maps in maps.
Classes for computer vision, detectors, features, etc.
#define MRPT_LOAD_CONFIG_VAR_NO_DEFAULT( variableName, variableType, configFileObject, sectionNameStr)
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
#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
double ransac_mahalanobisDistanceThreshold
(Default = 3.0)
A class used to store a 2D point.
double ransac_fuseMaxDiffPhi
(Default=0.1degree) (In radians)
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...
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.
#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 ...
unsigned long getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
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.
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...
static cellType p2l(const float p)
Scales a real valued probability in [0,1] to an integer representation of: log(p)-log(1-p) in the val...
Declares a virtual base class for all metric maps storage classes.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
cellType * getRow(int cy)
Access to a "row": mainly used for drawing grid as a bitmap efficiently, do not use it normally...
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
const double & phi() const
Get the phi angle of the 2D pose (in radians)
#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...
GLenum GLenum GLvoid * row
The ICP algorithm return information.
double mean(const CONTAINER &v)
Computes the mean value of a vector.
float idx2y(const size_t cy) const
A matrix of dynamic size.
mrpt::poses::CPosePDFSOG transformation
The output as a set of transformations (sum of Gaussians)
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
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).
mrpt::maps::CLandmarksMap::Ptr landmarks_map2
float getPos(float x, float y) const
Read the real valued [0,1] contents of a cell, given its coordinates.
T distanceBetweenPoints(const T x1, const T y1, const T x2, const T y2)
Returns the distance between 2 points in 2D.
virtual void drawImage(int x, int y, const mrpt::img::CImage &img)
Draws an image as a bitmap at a given position.
GLfloat GLfloat GLfloat v2
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)...
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.
mrpt::containers::deepcopy_poly_ptr< mrpt::poses::CPosePDFSOG::Ptr > sog2
mrpt::tfest::TMatchingPairList largestSubSet
the largest consensus sub-set
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".
unsigned __int32 uint32_t
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
double thresholdDist
Initial threshold distance for two points to become a correspondence.
mrpt::poses::CPose2D noRobustEstimation
The "brute" estimation from using all the available correspondences, provided just for comparison pur...
double log_w
The log-weight.
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.
const Scalar * const_iterator
Output placeholder for se2_l2_robust()
double ransac_fuseMaxDiffXY
(Default = 0.01)
A class for storing images as grayscale or RGB bitmaps.
double probability_find_good_model
(Default = 0.999) See parameter ransac_nSimulations.
double mahalanobisDistanceTo(const CPoint2DPDFGaussian &other) const
Returns the Mahalanobis distance from this PDF to another PDF, that is, it's evaluation at (0...
#define MRPT_LOG_INFO(_STRING)
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
int round(const T value)
Returns the closer integer (int) to x.