33 std::vector<bool>& alreadySelectedOther
34 #ifdef AVOID_MULTIPLE_CORRESPONDENCES
36 const std::vector<vector_int>& listDuplicatedLandmarksThis
40 ASSERTDEB_(
c.this_idx < alreadySelectedThis.size());
41 ASSERTDEB_(
c.other_idx < alreadySelectedOther.size());
43 #ifndef AVOID_MULTIPLE_CORRESPONDENCES 44 alreadySelectedThis[
c.this_idx] =
true;
45 alreadySelectedOther[
c.other_idx] =
true;
48 listDuplicatedLandmarksThis[
c.this_idx].begin();
49 it1 != listDuplicatedLandmarksThis[
c.this_idx].end(); it1++)
50 alreadySelectedThis[*it1] =
true;
52 listDuplicatedLandmarksOther[
c.other_idx].begin();
53 it2 != listDuplicatedLandmarksOther[
c.other_idx].end(); it2++)
54 alreadySelectedOther[*it2] =
true;
89 const size_t nCorrs = in_correspondences.size();
92 const double MAX_RMSE_TO_END =
99 if (nCorrs <
params.ransac_minSetSize)
108 timlog.
enter(
"ransac.find_max*");
111 unsigned int maxThis = 0, maxOther = 0;
113 matchIt != in_correspondences.end(); ++matchIt)
115 maxThis = max(maxThis, matchIt->this_idx);
116 maxOther = max(maxOther, matchIt->other_idx);
119 timlog.
leave(
"ransac.find_max*");
123 timlog.
enter(
"ransac.count_unique_corrs");
127 std::vector<bool> hasCorrThis(maxThis + 1,
false);
128 std::vector<bool> hasCorrOther(maxOther + 1,
false);
129 unsigned int howManyDifCorrs = 0;
131 matchIt != in_correspondences.end(); ++matchIt)
133 if (!hasCorrThis[matchIt->this_idx] &&
134 !hasCorrOther[matchIt->other_idx])
136 hasCorrThis[matchIt->this_idx] =
true;
137 hasCorrOther[matchIt->other_idx] =
true;
142 timlog.
leave(
"ransac.count_unique_corrs");
150 if (howManyDifCorrs <
params.ransac_minSetSize)
158 #ifdef AVOID_MULTIPLE_CORRESPONDENCES 165 std::vector<vector_int> listDuplicatedLandmarksThis(maxThis + 1);
167 for (k = 0; k < nCorrs - 1; k++)
170 for (
unsigned j = k; j < nCorrs - 1; j++)
172 if (in_correspondences[k].this_x == in_correspondences[j].this_x &&
173 in_correspondences[k].this_y == in_correspondences[j].this_y &&
174 in_correspondences[k].this_z == in_correspondences[j].this_z)
175 duplis.push_back(in_correspondences[j].this_idx);
177 listDuplicatedLandmarksThis[in_correspondences[k].this_idx] = duplis;
180 std::vector<vector_int> listDuplicatedLandmarksOther(maxOther + 1);
181 for (k = 0; k < nCorrs - 1; k++)
184 for (
unsigned j = k; j < nCorrs - 1; j++)
186 if (in_correspondences[k].other_x ==
187 in_correspondences[j].other_x &&
188 in_correspondences[k].other_y ==
189 in_correspondences[j].other_y &&
190 in_correspondences[k].other_z == in_correspondences[j].other_z)
191 duplis.push_back(in_correspondences[j].other_idx);
193 listDuplicatedLandmarksOther[in_correspondences[k].other_idx] = duplis;
197 std::deque<TMatchingPairList> alreadyAddedSubSets;
202 const double ransac_consistency_test_chi2_quantile = 0.99;
203 const double chi2_thres_dim1 =
209 size_t largest_consensus_yet = 0;
210 double largestSubSet_RMSE = std::numeric_limits<double>::max();
213 const bool use_dynamic_iter_number = results.
ransac_iters == 0;
214 if (use_dynamic_iter_number)
217 params.probability_find_good_model > 0 &&
218 params.probability_find_good_model < 1);
224 std::vector<bool> alreadySelectedThis, alreadySelectedOther;
226 if (!
params.ransac_algorithmForLandmarks)
228 alreadySelectedThis.assign(maxThis + 1,
false);
229 alreadySelectedOther.assign(maxOther + 1,
false);
235 std::vector<size_t> corrsIdxs(nCorrs), corrsIdxsPermutation;
236 for (
size_t i = 0; i < nCorrs; i++) corrsIdxs[i] = i;
247 timlog.
enter(
"ransac.permute");
252 timlog.
leave(
"ransac.permute");
258 if (
params.ransac_algorithmForLandmarks)
261 timlog.
enter(
"ransac.reset_selection_marks");
263 alreadySelectedThis.assign(maxThis + 1,
false);
264 alreadySelectedOther.assign(maxOther + 1,
false);
266 timlog.
leave(
"ransac.reset_selection_marks");
279 timlog.
enter(
"ransac.inner_loops");
281 for (
unsigned int j = 0;
282 j < nCorrs && subSet.size() <
params.ransac_maxSetSize; j++)
284 const size_t idx = corrsIdxsPermutation[j];
289 if (alreadySelectedThis[corr_j.
this_idx] ||
294 if (
params.user_individual_compat_callback)
299 if (!
params.user_individual_compat_callback(pm))
303 if (subSet.size() < 2)
309 subSet.push_back(corr_j);
310 markAsPicked(corr_j, alreadySelectedThis, alreadySelectedOther);
312 if (subSet.size() == 2)
320 const double corrs_dist1 =
322 subSet[0].this_x, subSet[0].this_y,
323 subSet[1].this_x, subSet[1].this_y);
325 const double corrs_dist2 =
327 subSet[0].other_x, subSet[0].other_y,
328 subSet[1].other_x, subSet[1].other_y);
332 const double corrs_dist_chi2 =
337 bool is_acceptable = (corrs_dist_chi2 < chi2_thres_dim1);
350 (referenceEstimation.
cov(2, 2) <
358 subSet.erase(subSet.begin() + (subSet.size() - 1));
364 corr_j, alreadySelectedThis, alreadySelectedOther);
371 timlog.
enter(
"ransac.test_consistency");
391 const bool passTest =
392 maha_dist <
params.ransac_mahalanobisDistanceThreshold;
397 subSet.push_back(corr_j);
399 corr_j, alreadySelectedThis, alreadySelectedOther);
404 timlog.
leave(
"ransac.test_consistency");
410 timlog.
leave(
"ransac.inner_loops");
413 const bool has_to_eval_RMSE =
414 (subSet.size() >=
params.ransac_minSetSize);
418 double this_subset_RMSE = 0;
419 if (has_to_eval_RMSE)
430 for (
size_t k = 0; k < subSet.size(); k++)
434 subSet[k].other_x, subSet[k].other_y, gx, gy);
437 mrpt::math::distanceSqrBetweenPoints<double>(
438 subSet[k].this_x, subSet[k].this_y, gx, gy);
440 this_subset_RMSE /= std::max(static_cast<size_t>(1), subSet.size());
444 this_subset_RMSE = std::numeric_limits<double>::max();
450 if (subSet.size() >=
params.ransac_minSetSize)
459 if (!
params.ransac_fuseByCorrsMatch)
467 referenceEstimation.
mean);
468 double diffPhi = fabs(
471 referenceEstimation.
mean.
phi()));
472 if (diffXY <
params.ransac_fuseMaxDiffXY &&
473 diffPhi <
params.ransac_fuseMaxDiffPhi)
491 for (
size_t i = 0; i < alreadyAddedSubSets.size(); i++)
493 if (subSet == alreadyAddedSubSets[i])
501 if (indexFound != -1)
504 if (
params.ransac_algorithmForLandmarks)
515 alreadyAddedSubSets.push_back(subSet);
518 if (
params.ransac_algorithmForLandmarks)
519 newSOGMode.
log_w = 0;
521 newSOGMode.
log_w = log(static_cast<double>(subSet.size()));
523 newSOGMode.
mean = referenceEstimation.
mean;
524 newSOGMode.
cov = referenceEstimation.
cov;
531 const size_t ninliers = subSet.size();
532 if (largest_consensus_yet < ninliers)
534 largest_consensus_yet = ninliers;
537 if (use_dynamic_iter_number)
542 const double fracinliers =
544 static_cast<double>(howManyDifCorrs);
546 1 - pow(fracinliers, static_cast<double>(
549 pNoOutliers = std::max(
550 std::numeric_limits<double>::epsilon(),
553 1.0 - std::numeric_limits<double>::epsilon(),
557 log(1 -
params.probability_find_good_model) /
564 cout <<
"[tfest::RANSAC] Iter #" << iter_idx
566 <<
" pNoOutliers=" << pNoOutliers
567 <<
" #inliers: " << ninliers << endl;
572 if (subSet.size() >=
params.ransac_minSetSize &&
573 this_subset_RMSE < largestSubSet_RMSE)
576 cout <<
"[tfest::RANSAC] Iter #" << iter_idx
577 <<
" Better subset: " << subSet.size()
578 <<
" inliers, RMSE=" << this_subset_RMSE << endl;
581 largestSubSet_RMSE = this_subset_RMSE;
585 if (subSet.size() >=
params.ransac_minSetSize &&
586 this_subset_RMSE < MAX_RMSE_TO_END)
592 timlog.
leave(
"ransac.iter");
597 cout <<
"[tfest::RANSAC] Finished after " << iter_idx
606 printf(
"nCorrs=%u\n", static_cast<unsigned int>(nCorrs));
607 printf(
"Saving '_debug_in_correspondences.txt'...");
608 in_correspondences.
dumpToFile(
"_debug_in_correspondences.txt");
609 printf(
"Ok\n"); printf(
"Saving '_debug_results.transformation.txt'...");
611 "_debug_results.transformation.txt");
A namespace of pseudo-random numbers genrators of diferent distributions.
void normalizeWeights()
Normalize the weights in m_modes such as the maximum log-weight is 0.
void permuteVector(const VEC &in_vector, VEC &out_result)
Returns a random permutation of a vector: all the elements of the input vector are in the output but ...
void clear()
Clear the list of modes.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
CPose2D mean
The mean value.
const float normalizationStd
The struct for each mode:
void saveToTextFile(const std::string &file) const override
Save the density to a text file, with the following format: There is one row per Gaussian "mode"...
double distanceTo(const CPoseOrPoint< OTHERCLASS > &b) const
Returns the Euclidean distance to another pose/point:
#define MRPT_END_WITH_CLEAN_UP(stuff)
A gaussian distribution for 2D points.
void markAsPicked(const TMatchingPair &c, std::vector< bool > &alreadySelectedThis, std::vector< bool > &alreadySelectedOther)
Parameters for se2_l2_robust().
mrpt::utils::TMatchingPairList largestSubSet
the largest consensus sub-set
const TGaussianMode & get(size_t i) const
Access to individual beacons.
bool se2_l2(const mrpt::utils::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...
bool se2_l2_robust(const mrpt::utils::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 ...
const Scalar * const_iterator
void push_back(const TGaussianMode &m)
Inserts a copy of the given mode into the SOG.
void composePoint(const mrpt::math::TPoint2D &l, CPoint2DPDFGaussian &g) const
Returns the PDF of the 2D point with "q"=this pose and "l" a point without uncertainty.
void composePoint(double lx, double ly, double &gx, double &gy) const
An alternative, slightly more efficient way of doing with G and L being 2D points and P this 2D pose...
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
T square(const T x)
Inline function for the square of a number.
This base provides a set of functions for maths stuff.
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
void dumpToFile(const std::string &fileName) const
Saves the correspondences to a text file.
mrpt::math::CMatrixDouble33 cov
double mahalanobisDistanceToPoint(const double x, const double y) const
Returns the Mahalanobis distance from this PDF to some point.
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
unsigned int ransac_iters
Number of actual iterations executed.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
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...
A safe way to call enter() and leave() of a mrpt::utils::CTimeLogger upon construction and destructio...
const double & phi() const
Get the phi angle of the 2D pose (in radians)
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
double leave(const char *func_name)
End of a named section.
mrpt::poses::CPosePDFSOG transformation
The output as a set of transformations (sum of Gaussians)
std::vector< int32_t > vector_int
size_t size() const
Return the number of Gaussian modes.
T distanceBetweenPoints(const T x1, const T y1, const T x2, const T y2)
Returns the distance between 2 points in 2D.
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
void enter(const char *func_name)
Start of a named section.
double log_w
The log-weight.
Functions for estimating the optimal transformation between two frames of references given measuremen...
GLenum const GLfloat * params
For each individual-compatibility (IC) test, the indices of the candidate match between elements in b...
Output placeholder for se2_l2_robust()
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...