15 #include <mrpt/core/exceptions.h>
16 #include <mrpt/core/round.h>
17 #include <mrpt/math/CHistogram.h>
18 #include <mrpt/math/distributions.h>
19 #include <mrpt/version.h>
53 const mrpt::maps::CMetricMap& pcGlobalMap,
const mrpt::maps::CPointsMap& pcLocal,
59 const mrpt::maps::NearestNeighborsCapable& nnGlobal =
65 if (pcGlobalMap.isEmpty() || pcLocal.empty())
return;
71 if (!pcGlobalMap.boundingBox().intersection(
72 {tl.localMin, tl.localMax},
77 out.paired_pt2pt.reserve(
out.paired_pt2pt.size() + pcLocal.size());
83 const auto& lxs = pcLocal.getPointsBufferRef_x();
84 const auto& lys = pcLocal.getPointsBufferRef_y();
85 const auto& lzs = pcLocal.getPointsBufferRef_z();
96 std::optional<float> minSqrErrorForHistogram;
97 std::optional<float> maxSqrErrorForHistogram;
99 const auto lambdaAddPair = [&](
const size_t localIdx,
const mrpt::math::TPoint3Df& globalPt,
100 const uint64_t globalIdxOrID,
const float errSqr)
105 mrpt::tfest::TMatchingPair p;
106 p.globalIdx = globalIdxOrID;
107 p.localIdx = localIdx;
109 p.local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
110 p.errorSquareAfterTransformation = errSqr;
115 const uint32_t nn_search_max_points =
118 for (
size_t i = 0; i < tl.
x_locals.size(); i++)
120 const size_t localIdx = tl.
idxs.has_value() ? (*tl.
idxs)[i] : i;
134 if (nn_search_max_points == 1)
140 if (!nnGlobal.nn_single_search(
151 nnGlobal.nn_radius_search(
154 nn_search_max_points);
161 if (tentativeErrSqr > absoluteMaxDistSqr)
continue;
167 if (maxSqrErrorForHistogram)
169 mrpt::keep_max(*maxSqrErrorForHistogram, tentativeErrSqr);
170 mrpt::keep_min(*minSqrErrorForHistogram, tentativeErrSqr);
174 maxSqrErrorForHistogram = tentativeErrSqr;
175 minSqrErrorForHistogram = tentativeErrSqr;
186 mrpt::math::CHistogram hist(*minSqrErrorForHistogram, *maxSqrErrorForHistogram, 50);
188 for (
const auto& mspl : matchesPerLocal_)
189 for (
size_t i = 0; i < std::min<size_t>(mspl.size(), 2UL); i++)
190 hist.add(mspl[i].errorSquareAfterTransformation);
192 hist.getHistogramNormalized(histXs_, histValues_);
194 double ci_low = 0, ci_high = 0;
195 mrpt::math::confidenceIntervalsFromHistogram(
196 histXs_, histValues_, ci_low, ci_high, 1.0 - confidenceInterval);
199 printf(
"Histograms:\n");
200 for (
auto v : histXs_) printf(
"%.02f ", v);
202 for (
auto v : histValues_) printf(
"%.02f ", v);
205 "[MatcherAdaptive] CI_HIGH: %.03f => threshold=%.03f m nCorrs=%zu\n",
206 ci_high, std::sqrt(ci_high), matchesPerLocal_.size());
211 const double maxCorrDistSqr = std::max(mrpt::square(minimumCorrDist), ci_high);
213 const float maxSqr1to2 = mrpt::square(firstToSecondDistanceMax);
216 for (
const auto& mspl : matchesPerLocal_)
220 if (enableDetectPlanes && mspl.size() >= planeMinimumFoundPoints)
225 for (
const auto& p : mspl)
227 kddXs.push_back(p.global.x);
228 kddYs.push_back(p.global.y);
229 kddZs.push_back(p.global.z);
233 kddXs.data(), kddYs.data(), kddZs.data(), std::nullopt, kddXs.size());
240 const mrpt::math::TPoint3D planeCentroid = {
243 const auto thePlane = mrpt::math::TPlane(planeCentroid, normal);
244 const double ptPlaneDist = std::abs(thePlane.distance(mspl.at(0).local));
246 if (ptPlaneDist < planeMinimumDistance)
248 const auto localIdx = mspl.at(0).localIdx;
251 auto& p =
out.paired_pt2pl.emplace_back();
252 p.pt_local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
253 p.pl_global.centroid = planeCentroid;
255 p.pl_global.plane = thePlane;
258 ms.localPairedBitField.point_layers[localName].mark_as_set(localIdx);
266 for (
size_t i = 0; i < std::min<size_t>(mspl.size(), maxPt2PtCorrespondences); i++)
268 const auto& p = mspl.at(i);
269 const auto globalIdx = p.globalIdx;
271 if (!allowMatchAlreadyMatchedGlobalPoints_ &&
272 ms.globalPairedBitField.point_layers.at(globalName)[globalIdx])
276 if (p.errorSquareAfterTransformation >= maxCorrDistSqr)
continue;
278 if (i != 0 && mspl[i].errorSquareAfterTransformation >
279 mspl[0].errorSquareAfterTransformation * maxSqr1to2)
284 out.paired_pt2pt.emplace_back(p);
287 if (!allowMatchAlreadyMatchedGlobalPoints_)
289 const auto localIdx = p.localIdx;
290 ms.localPairedBitField.point_layers[localName].mark_as_set(localIdx);
302 ms.globalPairedBitField.point_layers[globalName].mark_as_set(