Matcher_Adaptive.cpp
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
15 #include <mrpt/core/exceptions.h>
16 #include <mrpt/core/round.h>
17 #include <mrpt/math/CHistogram.h> // CHistogram
18 #include <mrpt/math/distributions.h> // confidenceIntervalsFromHistogram()
19 #include <mrpt/version.h>
20 
22 
23 using namespace mp2p_icp;
24 
25 void Matcher_Adaptive::initialize(const mrpt::containers::yaml& params)
26 {
28 
29  MCP_LOAD_REQ(params, confidenceInterval);
30  MCP_LOAD_REQ(params, firstToSecondDistanceMax);
31 
32  MCP_LOAD_REQ(params, absoluteMaxSearchDistance);
33  MCP_LOAD_OPT(params, minimumCorrDist);
34 
35  MCP_LOAD_REQ(params, enableDetectPlanes);
36 
37  MCP_LOAD_OPT(params, planeSearchPoints);
38  MCP_LOAD_OPT(params, planeMinimumFoundPoints);
39  MCP_LOAD_OPT(params, planeEigenThreshold);
40  MCP_LOAD_OPT(params, maxPt2PtCorrespondences);
41  MCP_LOAD_OPT(params, planeMinimumDistance);
42 
43  ASSERT_LT_(confidenceInterval, 1.0);
44  ASSERT_GT_(confidenceInterval, 0.0);
45 
47  ASSERT_GE_(planeMinimumFoundPoints, 3);
48 
49  ASSERT_GT_(planeEigenThreshold, 0.0);
50 }
51 
53  const mrpt::maps::CMetricMap& pcGlobalMap, const mrpt::maps::CPointsMap& pcLocal,
54  const mrpt::poses::CPose3D& localPose, MatchState& ms, const layer_name_t& globalName,
55  const layer_name_t& localName, Pairings& out) const
56 {
57  MRPT_START
58 
59  const mrpt::maps::NearestNeighborsCapable& nnGlobal =
60  *mp2p_icp::MapToNN(pcGlobalMap, true /*throw if cannot convert*/);
61 
62  out.potential_pairings += pcLocal.size() * maxPt2PtCorrespondences;
63 
64  // Empty maps? Nothing to do
65  if (pcGlobalMap.isEmpty() || pcLocal.empty()) return;
66 
68  pcLocal, localPose, maxLocalPointsPerLayer_, localPointsSampleSeed_);
69 
70  // Try to do matching only if the bounding boxes have some overlap:
71  if (!pcGlobalMap.boundingBox().intersection(
72  {tl.localMin, tl.localMax},
73  /* threshold?? */ +bounding_box_intersection_check_epsilon_))
74  return;
75 
76  // Prepare output: no correspondences initially:
77  out.paired_pt2pt.reserve(out.paired_pt2pt.size() + pcLocal.size());
78 
79  // Loop for each point in local map:
80  // --------------------------------------------------
81  const float absoluteMaxDistSqr = mrpt::square(absoluteMaxSearchDistance);
82 
83  const auto& lxs = pcLocal.getPointsBufferRef_x();
84  const auto& lys = pcLocal.getPointsBufferRef_y();
85  const auto& lzs = pcLocal.getPointsBufferRef_z();
86 
87  // In order to find the closest association for each global point, we must
88  // first build this temporary list of *potential* associations, indexed by
89  // global point indices, and sorted by errSqr:
90 
91  // List of all 1st and 2nd closest pairings to each
92  matchesPerLocal_.clear();
93  matchesPerLocal_.resize(tl.x_locals.size());
94 
95  // Calculate limits for the histogram:
96  std::optional<float> minSqrErrorForHistogram;
97  std::optional<float> maxSqrErrorForHistogram;
98 
99  const auto lambdaAddPair = [&](const size_t localIdx, const mrpt::math::TPoint3Df& globalPt,
100  const uint64_t globalIdxOrID, const float errSqr)
101  {
102  auto& ps = matchesPerLocal_.at(localIdx);
103  if (ps.size() >= MAX_CORRS_PER_LOCAL) return;
104 
105  mrpt::tfest::TMatchingPair p;
106  p.globalIdx = globalIdxOrID;
107  p.localIdx = localIdx;
108  p.global = globalPt;
109  p.local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
110  p.errorSquareAfterTransformation = errSqr;
111 
112  ps.push_back(p);
113  };
114 
115  const uint32_t nn_search_max_points =
117 
118  for (size_t i = 0; i < tl.x_locals.size(); i++)
119  {
120  const size_t localIdx = tl.idxs.has_value() ? (*tl.idxs)[i] : i;
121 
123  ms.localPairedBitField.point_layers.at(localName)[localIdx])
124  {
125  // skip, already paired, e.g. by another Matcher in the pipeline
126  // before me:
127  continue;
128  }
129 
130  const float lx = tl.x_locals[i], ly = tl.y_locals[i], lz = tl.z_locals[i];
131 
132  // Use a KD-tree to look for the nearnest neighbor(s) of
133  // (x_local, y_local, z_local) in the global map:
134  if (nn_search_max_points == 1)
135  {
136  neighborSqrDists_.resize(1);
137  neighborIndices_.resize(1);
138  neighborPts_.resize(1);
139 
140  if (!nnGlobal.nn_single_search(
141  {lx, ly, lz}, // Look closest to this guy
143  {
144  neighborPts_.clear();
145  neighborSqrDists_.clear();
146  neighborIndices_.clear();
147  }
148  }
149  else
150  {
151  nnGlobal.nn_radius_search(
152  {lx, ly, lz}, // Look closest to this guy
153  absoluteMaxDistSqr, neighborPts_, neighborSqrDists_, neighborIndices_,
154  nn_search_max_points);
155  }
156 
157  for (size_t k = 0; k < neighborIndices_.size(); k++)
158  {
159  const auto tentativeErrSqr = neighborSqrDists_.at(k);
160 
161  if (tentativeErrSqr > absoluteMaxDistSqr) continue;
162 
163  if (k <= 1)
164  {
165  // keep max of 1st and 2nd closest point errors for the
166  // histogram:
167  if (maxSqrErrorForHistogram)
168  {
169  mrpt::keep_max(*maxSqrErrorForHistogram, tentativeErrSqr);
170  mrpt::keep_min(*minSqrErrorForHistogram, tentativeErrSqr);
171  }
172  else
173  {
174  maxSqrErrorForHistogram = tentativeErrSqr;
175  minSqrErrorForHistogram = tentativeErrSqr;
176  }
177  }
178 
179  lambdaAddPair(localIdx, neighborPts_.at(k), neighborIndices_.at(k), tentativeErrSqr);
180  }
181 
182  } // For each local point
183 
184  // Now, estimate the probability distribution (histogram) of the
185  // 1st/2nd points:
186  mrpt::math::CHistogram hist(*minSqrErrorForHistogram, *maxSqrErrorForHistogram, 50);
187 
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);
191 
192  hist.getHistogramNormalized(histXs_, histValues_);
193 
194  double ci_low = 0, ci_high = 0;
195  mrpt::math::confidenceIntervalsFromHistogram(
196  histXs_, histValues_, ci_low, ci_high, 1.0 - confidenceInterval);
197 
198 #if 0
199  printf("Histograms:\n");
200  for (auto v : histXs_) printf("%.02f ", v);
201  printf("\n");
202  for (auto v : histValues_) printf("%.02f ", v);
203  printf("\n");
204  printf(
205  "[MatcherAdaptive] CI_HIGH: %.03f => threshold=%.03f m nCorrs=%zu\n",
206  ci_high, std::sqrt(ci_high), matchesPerLocal_.size());
207 #endif
208 
209  // Take the confidence interval limit as the definitive maximum squared
210  // distance for correspondences:
211  const double maxCorrDistSqr = std::max(mrpt::square(minimumCorrDist), ci_high);
212 
213  const float maxSqr1to2 = mrpt::square(firstToSecondDistanceMax);
214 
215  // Now, process candidates pairing and store them in `out.paired_pt2pt`:
216  for (const auto& mspl : matchesPerLocal_)
217  {
218  // Check for a potential plane?
219  // minimum: 3 points to be able to fit a plane
220  if (enableDetectPlanes && mspl.size() >= planeMinimumFoundPoints)
221  {
222  kddXs.clear();
223  kddYs.clear();
224  kddZs.clear();
225  for (const auto& p : mspl)
226  {
227  kddXs.push_back(p.global.x);
228  kddYs.push_back(p.global.y);
229  kddZs.push_back(p.global.z);
230  }
231 
233  kddXs.data(), kddYs.data(), kddZs.data(), std::nullopt, kddXs.size());
234 
235  // e0/e2 must be < planeEigenThreshold:
236  if (eig.eigVals[0] < planeEigenThreshold * eig.eigVals[2] &&
237  eig.eigVals[0] < planeEigenThreshold * eig.eigVals[1])
238  {
239  const auto& normal = eig.eigVectors[0];
240  const mrpt::math::TPoint3D planeCentroid = {
241  eig.meanCov.mean.x(), eig.meanCov.mean.y(), eig.meanCov.mean.z()};
242 
243  const auto thePlane = mrpt::math::TPlane(planeCentroid, normal);
244  const double ptPlaneDist = std::abs(thePlane.distance(mspl.at(0).local));
245 
246  if (ptPlaneDist < planeMinimumDistance)
247  {
248  const auto localIdx = mspl.at(0).localIdx;
249 
250  // OK, all conditions pass: add the new pairing:
251  auto& p = out.paired_pt2pl.emplace_back();
252  p.pt_local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
253  p.pl_global.centroid = planeCentroid;
254 
255  p.pl_global.plane = thePlane;
256 
257  // Mark local point as already paired:
258  ms.localPairedBitField.point_layers[localName].mark_as_set(localIdx);
259 
260  // all good with this local point:
261  continue;
262  }
263  }
264  }
265 
266  for (size_t i = 0; i < std::min<size_t>(mspl.size(), maxPt2PtCorrespondences); i++)
267  {
268  const auto& p = mspl.at(i);
269  const auto globalIdx = p.globalIdx;
270 
271  if (!allowMatchAlreadyMatchedGlobalPoints_ &&
272  ms.globalPairedBitField.point_layers.at(globalName)[globalIdx])
273  continue; // skip, global point already paired.
274 
275  // too large error for the adaptive threshold?
276  if (p.errorSquareAfterTransformation >= maxCorrDistSqr) continue;
277 
278  if (i != 0 && mspl[i].errorSquareAfterTransformation >
279  mspl[0].errorSquareAfterTransformation * maxSqr1to2)
280  {
281  break;
282  }
283 
284  out.paired_pt2pt.emplace_back(p);
285 
286  // Mark local & global points as already paired:
287  if (!allowMatchAlreadyMatchedGlobalPoints_)
288  {
289  const auto localIdx = p.localIdx;
290  ms.localPairedBitField.point_layers[localName].mark_as_set(localIdx);
291  }
292  }
293  }
294 
295  // Update adaptive maximum range:
296  // absoluteMaxSearchDistance = std::sqrt(ci_high) + minimumCorrDist;
297 
298 // Now, mark global idxs as used. It's done after the loop above
299 // to allow multiple local -> global pairs with the same global.
300 #if 0
301  // Mark local & global points as already paired:
302  ms.globalPairedBitField.point_layers[globalName].mark_as_set(
303  globalIdx);
304 #endif
305 
306  MRPT_END
307 }
mp2p_icp::Matcher_Adaptive::confidenceInterval
double confidenceInterval
Definition: Matcher_Adaptive.h:58
mp2p_icp::Matcher_Adaptive::planeMinimumDistance
double planeMinimumDistance
Definition: Matcher_Adaptive.h:65
mp2p_icp::Matcher_Adaptive::planeSearchPoints
uint32_t planeSearchPoints
Definition: Matcher_Adaptive.h:63
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Matcher_Points_Base::bounding_box_intersection_check_epsilon_
double bounding_box_intersection_check_epsilon_
Definition: Matcher_Points_Base.h:63
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud
Definition: Matcher_Points_Base.h:90
mp2p_icp::Matcher
Definition: Matcher.h:73
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::y_locals
mrpt::aligned_std_vector< float > y_locals
Definition: Matcher_Points_Base.h:100
mp2p_icp::Matcher_Adaptive::maxPt2PtCorrespondences
uint32_t maxPt2PtCorrespondences
Definition: Matcher_Adaptive.h:62
mp2p_icp::Pairings
Definition: Pairings.h:76
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
mp2p_icp::Matcher_Points_Base::allowMatchAlreadyMatchedPoints_
bool allowMatchAlreadyMatchedPoints_
Definition: Matcher_Points_Base.h:52
mp2p_icp::Matcher_Adaptive::minimumCorrDist
double minimumCorrDist
Definition: Matcher_Adaptive.h:67
Matcher_Adaptive.h
Pointcloud matcher: smart adaptive matcher.
mp2p_icp::Matcher_Adaptive::neighborIndices_
std::vector< uint64_t > neighborIndices_
Definition: Matcher_Adaptive.h:70
mp2p_icp::estimate_points_eigen
PointCloudEigen estimate_points_eigen(const float *xs, const float *ys, const float *zs, mrpt::optional_ref< const std::vector< size_t >> indices, std::optional< size_t > totalCount=std::nullopt)
Definition: estimate_points_eigen.cpp:19
mp2p_icp::Matcher_Adaptive::planeEigenThreshold
double planeEigenThreshold
Definition: Matcher_Adaptive.h:66
mp2p_icp::Matcher_Adaptive::MAX_CORRS_PER_LOCAL
constexpr static size_t MAX_CORRS_PER_LOCAL
Definition: Matcher_Adaptive.h:76
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::idxs
std::optional< std::vector< std::size_t > > idxs
Definition: Matcher_Points_Base.h:97
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp::Matcher_Adaptive::planeMinimumFoundPoints
uint32_t planeMinimumFoundPoints
Definition: Matcher_Adaptive.h:64
mp2p_icp::Matcher_Points_Base::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Points_Base.cpp:114
mp2p_icp::Matcher_Adaptive::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Adaptive.cpp:25
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::z_locals
mrpt::aligned_std_vector< float > z_locals
Definition: Matcher_Points_Base.h:100
mp2p_icp::MatchState
Definition: Matcher.h:37
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Matcher_Adaptive::firstToSecondDistanceMax
double firstToSecondDistanceMax
Definition: Matcher_Adaptive.h:59
mp2p_icp::Matcher_Adaptive::implMatchOneLayer
void implMatchOneLayer(const mrpt::maps::CMetricMap &pcGlobal, const mrpt::maps::CPointsMap &pcLocal, const mrpt::poses::CPose3D &localPose, MatchState &ms, const layer_name_t &globalName, const layer_name_t &localName, Pairings &out) const override
Definition: Matcher_Adaptive.cpp:52
mp2p_icp::Matcher_Points_Base::localPointsSampleSeed_
uint64_t localPointsSampleSeed_
Definition: Matcher_Points_Base.h:48
mp2p_icp::PointCloudEigen::eigVectors
std::array< mrpt::math::TVector3D, 3 > eigVectors
Definition: estimate_points_eigen.h:35
mp2p_icp::Matcher_Adaptive::enableDetectPlanes
bool enableDetectPlanes
Definition: Matcher_Adaptive.h:61
mp2p_icp::Matcher_Adaptive::absoluteMaxSearchDistance
double absoluteMaxSearchDistance
Definition: Matcher_Adaptive.h:60
mp2p_icp::pointcloud_bitfield_t::point_layers
std::map< layer_name_t, DenseOrSparseBitField > point_layers
Definition: pointcloud_bitfield.h:82
mp2p_icp::Matcher_Adaptive::matchesPerLocal_
std::vector< mrpt::containers::vector_with_small_size_optimization< mrpt::tfest::TMatchingPair, MAX_CORRS_PER_LOCAL > > matchesPerLocal_
Definition: Matcher_Adaptive.h:80
mp2p_icp::Matcher_Adaptive::neighborPts_
std::vector< mrpt::math::TPoint3Df > neighborPts_
Definition: Matcher_Adaptive.h:72
mp2p_icp::Matcher_Adaptive
Definition: Matcher_Adaptive.h:31
mp2p_icp::PointCloudEigen
Output of estimate_points_eigen()
Definition: estimate_points_eigen.h:32
mp2p_icp::PointCloudEigen::meanCov
mrpt::poses::CPointPDFGaussian meanCov
Definition: estimate_points_eigen.h:34
mp2p_icp::Matcher_Points_Base::maxLocalPointsPerLayer_
uint64_t maxLocalPointsPerLayer_
Definition: Matcher_Points_Base.h:47
mp2p_icp::MatchState::localPairedBitField
pointcloud_bitfield_t localPairedBitField
Definition: Matcher.h:47
mp2p_icp::MapToNN
const mrpt::maps::NearestNeighborsCapable * MapToNN(const mrpt::maps::CMetricMap &map, bool throwIfNotImplemented)
Definition: metricmap.cpp:658
mp2p_icp::PointCloudEigen::eigVals
std::array< double, 3 > eigVals
sorted in ascending order
Definition: estimate_points_eigen.h:36
mp2p_icp::Matcher_Adaptive::neighborSqrDists_
std::vector< float > neighborSqrDists_
Definition: Matcher_Adaptive.h:71
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::x_locals
mrpt::aligned_std_vector< float > x_locals
Definition: Matcher_Points_Base.h:100
estimate_points_eigen.h
Calculate eigenvectors and eigenvalues from a set of points.
mp2p_icp::Matcher_Points_Base::transform_local_to_global
static TransformedLocalPointCloud transform_local_to_global(const mrpt::maps::CPointsMap &pcLocal, const mrpt::poses::CPose3D &localPose, const std::size_t maxLocalPoints=0, const uint64_t localPointsSampleSeed=0)
Definition: Matcher_Points_Base.cpp:163


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:49