29 #include <Eigen/Dense> 50 switch (options.methodSelection)
52 case CGridMapAligner::amCorrelation:
53 return AlignPDF_correlation(
54 mm1, mm2, initialEstimationPDF, infoVal);
56 case CGridMapAligner::amModifiedRANSAC:
57 case CGridMapAligner::amRobustMatch:
59 return AlignPDF_robustMatch(
60 mm1, mm2, initialEstimationPDF, infoVal);
68 if (
auto* o = dynamic_cast<TReturnInfo*>(&info.value().get()); o)
75 const pair<size_t, float>& o1,
const pair<size_t, float>& o2)
77 return o1.second < o2.second;
90 options.methodSelection == CGridMapAligner::amRobustMatch ||
91 options.methodSelection == CGridMapAligner::amModifiedRANSAC);
101 std::vector<size_t> idxs1, idxs2;
102 std::vector<size_t>::iterator it1, it2;
131 "Metric maps must be of classes COccupancyGridMap2D or " 140 "Different resolutions for m1, m2:\n" 141 "\tres(m1) = %f\n\tres(m2) = %f\n",
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);
172 const size_t nLM1 = lm1->size();
173 const size_t nLM2 = lm2->size();
177 if (nLM1 < 2 || nLM2 < 2)
191 unsigned int corrsCount = 0;
192 std::vector<bool> hasCorr(nLM1,
false);
194 const double thres_max = options.threshold_max;
195 const double thres_delta = options.threshold_delta;
198 if (options.debug_show_corrs)
202 std::cerr <<
"Warning: options.debug_show_corrs has no effect " 203 "since MRPT 0.9.1\n";
206 for (
size_t idx1 = 0; idx1 < nLM1; idx1++)
209 vector<pair<size_t, float>> corrs_indiv;
213 vector<float> corrs_indiv_only;
214 corrs_indiv.reserve(nLM2);
215 corrs_indiv_only.reserve(nLM2);
217 for (
size_t idx2 = 0; idx2 < nLM2; idx2++)
221 lm1->landmarks.get(idx1)->features[0].descriptorDistanceTo(
222 lm2->landmarks.get(idx2)->features[0]);
224 corrs_indiv.emplace_back(idx2, minDist);
225 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);
245 idx1, corrs_indiv[w].first, corrs_indiv[w].second);
251 if (options.save_feat_coors)
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]);
260 for (
auto& it : corrs_by_idx)
263 lm1->landmarks.get(it.first)
265 .getFirstDescriptorAsMatrix(descriptor1);
267 im1.setFromMatrix(descriptor1,
true );
269 const size_t FEAT_W = im1.getWidth();
270 const size_t FEAT_H = im1.getHeight();
271 const size_t nF = it.second.size();
273 CImage img_compose(FEAT_W * 2 + 15, 10 + (5 + FEAT_H) * nF);
276 img_compose.
getHeight() - 1, TColor::black());
281 std::set<size_t>::iterator it_j;
283 format(
"grid_feats/_FEAT_MATCH_%03i", (
int)it.first);
285 for (j = 0, it_j = it.second.begin(); j < nF; ++j, ++it_j)
287 fil +=
format(
"_%u", static_cast<unsigned int>(*it_j));
290 lm2->landmarks.get(*it_j)
292 .getFirstDescriptorAsMatrix(descriptor2);
293 im2.setFromMatrix(descriptor2,
true);
295 10 + FEAT_W, 5 + j * (FEAT_H + 5), im2);
305 correspondences.clear();
306 for (it1 = idxs1.begin(), it2 = idxs2.begin(); it1 != idxs1.end();
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;
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);
323 hasCorr[*it1] =
true;
328 outInfo.
goodness = (2.0f * corrsCount) / (nLM1 + nLM2);
338 outInfo.
sog1 = pdf_SOG;
339 outInfo.
sog2 = pdf_SOG;
340 outInfo.
sog3 = pdf_SOG;
346 "[CGridMapAligner] Overall estimation(%u corrs, total: " 347 "%u): (%.03f,%.03f,%.03fdeg)\n",
348 corrsCount, (
unsigned)correspondences.size(),
354 using TMapMatchingsToPoseMode = std::map<
356 TMapMatchingsToPoseMode sog_modes;
363 if (options.methodSelection == CGridMapAligner::amRobustMatch)
371 const unsigned int min_inliers =
372 options.ransac_minSetSizeRatio * (nLM1 + nLM2) / 2;
378 options.ransac_mahalanobisDistanceThreshold;
385 options.ransac_prob_good_inliers;
390 correspondences, options.ransac_SOG_sigma_m, tfest_params,
399 size_t nB = pdf_SOG->size();
400 outInfo.
sog1 = pdf_SOG;
404 best_mode.
log_w = -std::numeric_limits<double>::max();
406 for (
size_t n = 0; n < pdf_SOG->size(); n++)
414 pdf_SOG->push_back(best_mode);
415 outInfo.
sog2 = pdf_SOG;
418 "[CGridMapAligner] amRobustMatch: " 419 << nB <<
" SOG modes reduced to " << pdf_SOG->size()
420 <<
" (most-likely) (min.inliers=" << min_inliers <<
")\n");
430 const size_t nCorrs = all_corrs.size();
439 for (
size_t i = 0; i < nLM1; i++)
440 lm1_pnts.
insertPoint(lm1->landmarks.get(i)->pose_mean);
442 for (
size_t i = 0; i < nLM2; i++)
443 lm2_pnts.
insertPoint(lm2->landmarks.get(i)->pose_mean);
447 const size_t minInliersTOaccept =
448 round(options.ransac_minSetSizeRatio * 0.5 * (nLM1 + nLM2));
450 const unsigned int ransac_min_nSimulations =
452 unsigned int ransac_nSimulations =
455 const double probability_find_good_model = 0.9999;
457 const double chi2_thres_dim1 =
459 const double chi2_thres_dim2 =
465 COV_pnt(0, 0) = COV_pnt(1, 1) =
466 square(options.ransac_SOG_sigma_m);
476 const unsigned int max_trials =
477 (nCorrs * (nCorrs - 1) / 2) *
480 unsigned int iter = 0;
482 unsigned int trials = 0;
484 while (iter < ransac_nSimulations &&
498 }
while (idx1 == idx2);
501 if (all_corrs[idx1].this_idx == all_corrs[idx2].this_idx ||
502 all_corrs[idx1].this_idx == all_corrs[idx2].other_idx)
504 if (all_corrs[idx1].other_idx == all_corrs[idx2].this_idx ||
505 all_corrs[idx1].other_idx == all_corrs[idx2].other_idx)
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);
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);
526 const double corrs_dist_chi2 =
528 (8.0 *
square(options.ransac_SOG_sigma_m) *
531 if (corrs_dist_chi2 > chi2_thres_dim1)
continue;
537 bool is_new_hyp =
true;
538 for (
auto& sog_mode : sog_modes)
540 if (sog_mode.first.contains(all_corrs[idx1]) &&
541 sog_mode.first.contains(all_corrs[idx2]))
544 sog_mode.second.log_w =
545 std::log(std::exp(sog_mode.second.log_w) + 1.0);
550 if (!is_new_hyp)
continue;
553 tentativeSubSet.push_back(all_corrs[idx1]);
554 tentativeSubSet.push_back(all_corrs[idx2]);
558 std::vector<bool> used_landmarks1(nLM1,
false);
559 std::vector<bool> used_landmarks2(nLM2,
false);
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;
568 bool keep_incorporating =
true;
577 temptPose.
cov *=
square(options.ransac_SOG_sigma_m);
583 const double ccos = cos(temptPose.
mean.
phi());
584 const double ssin = sin(temptPose.
mean.
phi());
598 vector<float> matches_dist;
599 std::vector<size_t> matches_idx;
605 #define GRIDMAP_USE_PROD_INTEGRAL 607 #ifdef GRIDMAP_USE_PROD_INTEGRAL 608 double best_pair_value = 0;
610 double best_pair_value =
611 std::numeric_limits<double>::max();
613 double best_pair_d2 =
614 std::numeric_limits<double>::max();
615 pair<size_t, size_t> best_pair_ij;
620 CDisplayWindowPlots
win(
"Matches");
622 for (
size_t j = 0; j < nLM2; j++)
624 if (used_landmarks2[j])
continue;
631 pdf_M2_j.
cov(0, 0) = pdf_M2_j.
cov(1, 1) =
632 square(options.ransac_SOG_sigma_m);
637 pdf_M2_j.
cov, 2,
"b-",
638 format(
"M2_%u", (
unsigned)j),
true);
641 static const unsigned int N_KDTREE_SEARCHED = 3;
647 N_KDTREE_SEARCHED, matches_idx, matches_dist);
650 for (
unsigned long u : matches_idx)
652 if (used_landmarks1[u])
continue;
656 -p2_j_local.
x * ssin - p2_j_local.
y * ccos;
658 p2_j_local.
x * ccos - p2_j_local.
y * ssin;
674 pdf_M1_i.
cov, 2,
"r-",
675 format(
"M1_%u", (
unsigned)matches_idx[u]),
680 #ifdef GRIDMAP_USE_PROD_INTEGRAL 681 const double prod_ij =
684 if (prod_ij > best_pair_value)
686 const double prod_ij =
688 if (prod_ij < best_pair_value)
694 best_pair_value = prod_ij;
695 best_pair_ij.first = u;
696 best_pair_ij.second = j;
713 keep_incorporating =
false;
716 if (best_pair_d2 < chi2_thres_dim2)
725 float p1_i_localx, p1_i_localy;
726 float p2_j_localx, p2_j_localy;
728 best_pair_ij.first, p1_i_localx,
731 best_pair_ij.second, p2_j_localx,
734 used_landmarks1[best_pair_ij.first] =
true;
735 used_landmarks2[best_pair_ij.second] =
true;
737 tentativeSubSet.push_back(
739 best_pair_ij.first, best_pair_ij.second,
740 p1_i_localx, p1_i_localy, 0,
741 p2_j_localx, p2_j_localy, 0
744 keep_incorporating =
true;
748 }
while (keep_incorporating);
751 const size_t ninliers = tentativeSubSet.size();
752 if (ninliers > minInliersTOaccept)
758 newGauss.
cov = temptPose.
cov;
760 sog_modes[tentativeSubSet] = newGauss;
767 if (largestConsensusCorrs.size() < ninliers)
769 largestConsensusCorrs = tentativeSubSet;
774 const double fracinliers =
776 static_cast<double>(std::min(nLM1, nLM2));
782 pNoOutliers = std::max(
783 std::numeric_limits<double>::epsilon(),
785 pNoOutliers = std::min(
786 1.0 - std::numeric_limits<double>::epsilon(),
789 ransac_nSimulations =
790 log(1 - probability_find_good_model) /
793 if (ransac_nSimulations < ransac_min_nSimulations)
794 ransac_nSimulations = ransac_min_nSimulations;
806 for (
auto s = sog_modes.begin(); s != sog_modes.end(); ++s)
809 "SOG mode: " << s->second.mean
810 <<
" inliers: " << s->first.size());
811 pdf_SOG->push_back(s->second);
815 if (pdf_SOG->size() > 0) pdf_SOG->normalizeWeights();
819 size_t nB = pdf_SOG->size();
820 outInfo.
sog1 = pdf_SOG;
823 pdf_SOG->mergeModes(options.maxKLd_for_merge,
false);
824 const double merge_clock_tim = merge_clock.
Tac();
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));
836 if (options.debug_save_map_pairs)
838 static unsigned int NN = 0;
846 "Largest consensus: %u",
847 static_cast<unsigned>(largestConsensusCorrs.size()));
848 CEnhancedMetaFile::LINUX_IMG_WIDTH(
850 CEnhancedMetaFile::LINUX_IMG_HEIGHT(
853 for (
auto s = sog_modes.begin(); s != sog_modes.end(); ++s)
855 COccupancyGridMap2D::saveAsEMFTwoMapsWithCorrespondences(
856 format(
"__debug_corrsGrid_%05u.emf", NN), m1, m2,
858 COccupancyGridMap2D::saveAsBitmapTwoMapsWithCorrespondences(
859 format(
"__debug_corrsGrid_%05u.png", NN), m1, m2,
874 if (multimap1 && multimap2 &&
884 icp.options.maxIterations = 20;
885 icp.options.smallestThresholdDist = 0.05f;
886 icp.options.thresholdDist = 0.75f;
891 for (
auto i = pdf_SOG->begin(); i != pdf_SOG->end(); ++cnt)
894 icp.Align(pnts1.get(), pnts2.get(), (i)->
mean, icpInfo);
903 const double icp_maha_dist =
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());
918 if (icpInfo.
goodness > options.min_ICP_goodness &&
919 icp_maha_dist < options.max_ICP_mahadist)
921 icp_est->getMean((i)->
mean);
927 i = pdf_SOG->erase(i);
933 outInfo.
sog3 = pdf_SOG;
935 pdf_SOG->mergeModes(options.maxKLd_for_merge,
false);
937 "[CGridMapAligner] " << pdf_SOG->size()
938 <<
" SOG modes merged after ICP.");
983 float phiResolution =
DEG2RAD(0.2f);
984 float phiMin = -
M_PIf + 0.5f * phiResolution;
985 float phiMax =
M_PIf;
990 float pivotPt_x = 0.5f * (m1->getXMax() + m1->getXMin());
991 float pivotPt_y = 0.5f * (m1->getYMax() + m1->getYMin());
993 CImage map1_img, map2_img;
994 float currentMaxCorr = -1e6f;
996 m1->getAsImage(map1_img);
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());
1006 #ifdef CORRELATION_SHOW_DEBUG 1007 CDisplayWindow*
win =
new CDisplayWindow(
"corr");
1008 CDisplayWindow* win2 =
new CDisplayWindow(
"map2_mod");
1014 for (phi = phiMin; phi < phiMax; phi += phiResolution)
1019 pivotPt_x - cos(phi) * map2width_2,
1020 pivotPt_y - sin(phi) * map2width_2,
1025 for (
size_t cy2 = 0; cy2 < map2_ly; cy2++)
1028 for (
size_t cx2 = 0; cx2 < map2_lx; cx2++)
1031 *row++ = m2->p2l(m2->getPos(v3.
x(), v3.
y()));
1040 map2_img, outCrossCorr, -1, -1, -1, -1,
1045 float corrPeak = outCrossCorr.
maxCoeff();
1049 if (corrPeak > currentMaxCorr)
1051 currentMaxCorr = corrPeak;
1052 bestCrossCorr = outCrossCorr;
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);
1068 #ifdef CORRELATION_SHOW_DEBUG 1077 std::size_t uMax, vMax;
1078 currentMaxCorr = bestCrossCorr.
maxCoeff(uMax, vMax);
1080 PDF->mean.x(m1->idx2x(uMax));
1081 PDF->mean.y(m1->idx2y(vMax));
1092 CGridMapAligner::TConfigParams::TConfigParams() : feature_detector_options() {}
1098 out <<
"\n----------- [CGridMapAligner::TConfigParams] ------------ \n\n";
1118 feature_detector_options.dumpToTextStream(
out);
1130 iniFile.read_enum(section,
"methodSelection", methodSelection);
1133 featsPerSquareMeter,
float,
iniFile, section)
1144 ransac_minSetSizeRatio,
float,
iniFile, section)
1148 ransac_chi2_quantile,
double,
iniFile, section)
1150 ransac_prob_good_inliers,
double,
iniFile, section)
1156 feature_descriptor =
iniFile.read_enum(
1157 section,
"feature_descriptor", feature_descriptor,
true);
1158 feature_detector_options.loadFromConfigFile(
iniFile, section);
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.
CPoint2D mean
The mean value.
void getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
double getArea() const
Returns the area of the gridmap, in square meters.
A compile-time fixed-size numeric matrix container.
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.
The struct for each mode:
float getResolution() const
Returns the resolution of the grid map.
Template for column vectors of dynamic size, compatible with Eigen.
#define THROW_EXCEPTION(msg)
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)
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().
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...
unsigned int ransac_nSimulations
(Default = 0) If set to 0, an adaptive algorithm is used to determine the number of iterations...
void drawImage(int x, int y, const mrpt::img::CImage &img) override
Draws an image as a bitmap at a given position.
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
const float ransac_mahalanobisDistanceThreshold
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.
T::Ptr mapByClass(size_t ith=0) const
Returns the i'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>>
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:
bool verbose
(Default=false)
#define ASSERT_(f)
Defines an assertion mechanism.
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.
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.
double phi() const
Get the phi angle of the 2D pose (in radians)
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
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.
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
bool ransac_algorithmForLandmarks
(Default = true) Use Mahalanobis distance (true) or Euclidean dist (false)
mrpt::math::CMatrixDouble33 cov
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...
Classes for computer vision, detectors, features, etc.
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
#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...
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
double x() const
Common members of all points & poses classes.
#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)
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...
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".
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...
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.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
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.
The ICP algorithm return information.
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)
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).
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.
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.
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...
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.
Output placeholder for se2_l2_robust()
#define MRPT_LOG_INFO_FMT(_FMT_STRING,...)
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)
void multiply_HCHt(const MAT_H &H, const MAT_C &C, MAT_R &R, bool accumResultInOutput=false)
R = H * C * H^t.
int round(const T value)
Returns the closer integer (int) to x.