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,
54 const mrpt::maps::CPointsMap& pcLocal,
55 const mrpt::poses::CPose3D& localPose,
MatchState& ms,
61 const mrpt::maps::NearestNeighborsCapable& nnGlobal =
67 if (pcGlobalMap.isEmpty() || pcLocal.empty())
return;
73 if (!pcGlobalMap.boundingBox().intersection(
74 {tl.localMin, tl.localMax},
79 out.paired_pt2pt.reserve(
out.paired_pt2pt.size() + pcLocal.size());
85 const auto& lxs = pcLocal.getPointsBufferRef_x();
86 const auto& lys = pcLocal.getPointsBufferRef_y();
87 const auto& lzs = pcLocal.getPointsBufferRef_z();
98 std::optional<float> minSqrErrorForHistogram;
99 std::optional<float> maxSqrErrorForHistogram;
101 const auto lambdaAddPair =
102 [&](
const size_t localIdx,
const mrpt::math::TPoint3Df& globalPt,
103 const uint64_t globalIdxOrID,
const float errSqr)
108 mrpt::tfest::TMatchingPair p;
109 p.globalIdx = globalIdxOrID;
110 p.localIdx = localIdx;
112 p.local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
113 p.errorSquareAfterTransformation = errSqr;
118 const uint32_t nn_search_max_points =
121 for (
size_t i = 0; i < tl.
x_locals.size(); i++)
123 const size_t localIdx = tl.
idxs.has_value() ? (*tl.
idxs)[i] : i;
138 if (nn_search_max_points == 1)
144 if (!nnGlobal.nn_single_search(
155 nnGlobal.nn_radius_search(
165 if (tentativeErrSqr > absoluteMaxDistSqr)
continue;
171 if (maxSqrErrorForHistogram)
173 mrpt::keep_max(*maxSqrErrorForHistogram, tentativeErrSqr);
174 mrpt::keep_min(*minSqrErrorForHistogram, tentativeErrSqr);
178 maxSqrErrorForHistogram = tentativeErrSqr;
179 minSqrErrorForHistogram = tentativeErrSqr;
192 mrpt::math::CHistogram hist(
193 *minSqrErrorForHistogram, *maxSqrErrorForHistogram, 50);
195 for (
const auto& mspl : matchesPerLocal_)
196 for (
size_t i = 0; i < std::min<size_t>(mspl.size(), 2UL); i++)
197 hist.add(mspl[i].errorSquareAfterTransformation);
199 hist.getHistogramNormalized(histXs_, histValues_);
201 double ci_low = 0, ci_high = 0;
202 mrpt::math::confidenceIntervalsFromHistogram(
203 histXs_, histValues_, ci_low, ci_high, 1.0 - confidenceInterval);
206 printf(
"Histograms:\n");
207 for (
auto v : histXs_) printf(
"%.02f ", v);
209 for (
auto v : histValues_) printf(
"%.02f ", v);
212 "[MatcherAdaptive] CI_HIGH: %.03f => threshold=%.03f m nCorrs=%zu\n",
213 ci_high, std::sqrt(ci_high), matchesPerLocal_.size());
218 const double maxCorrDistSqr =
219 std::max(mrpt::square(minimumCorrDist), ci_high);
221 const float maxSqr1to2 = mrpt::square(firstToSecondDistanceMax);
224 for (
const auto& mspl : matchesPerLocal_)
228 if (enableDetectPlanes && mspl.size() >= planeMinimumFoundPoints)
233 for (
const auto& p : mspl)
235 kddXs.push_back(p.global.x);
236 kddYs.push_back(p.global.y);
237 kddZs.push_back(p.global.z);
241 kddXs.data(), kddYs.data(), kddZs.data(), std::nullopt,
249 const mrpt::math::TPoint3D planeCentroid = {
253 const auto thePlane = mrpt::math::TPlane(planeCentroid, normal);
254 const double ptPlaneDist =
255 std::abs(thePlane.distance(mspl.at(0).local));
257 if (ptPlaneDist < planeMinimumDistance)
259 const auto localIdx = mspl.at(0).localIdx;
262 auto& p =
out.paired_pt2pl.emplace_back();
263 p.pt_local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
264 p.pl_global.centroid = planeCentroid;
266 p.pl_global.plane = thePlane;
269 ms.localPairedBitField.point_layers[localName].mark_as_set(
279 i < std::min<size_t>(mspl.size(), maxPt2PtCorrespondences); i++)
281 const auto& p = mspl.at(i);
282 const auto globalIdx = p.globalIdx;
284 if (!allowMatchAlreadyMatchedGlobalPoints_ &&
285 ms.globalPairedBitField.point_layers.at(globalName)[globalIdx])
289 if (p.errorSquareAfterTransformation >= maxCorrDistSqr)
continue;
292 mspl[i].errorSquareAfterTransformation >
293 mspl[0].errorSquareAfterTransformation * maxSqr1to2)
298 out.paired_pt2pt.emplace_back(p);
301 if (!allowMatchAlreadyMatchedGlobalPoints_)
303 const auto localIdx = p.localIdx;
304 ms.localPairedBitField.point_layers[localName].mark_as_set(
317 ms.globalPairedBitField.point_layers[globalName].mark_as_set(