Matcher_Points_DistanceThreshold.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  * ------------------------------------------------------------------------- */
14 #include <mrpt/core/exceptions.h>
15 #include <mrpt/core/round.h>
16 #include <mrpt/version.h>
17 
18 #if defined(MP2P_HAS_TBB)
19 #include <tbb/blocked_range.h>
20 #include <tbb/parallel_reduce.h>
21 #endif
22 
24 
25 using namespace mp2p_icp;
26 
28 {
29  mrpt::system::COutputLogger::setLoggerName("Matcher_Points_DistanceThreshold");
30 }
31 
32 void Matcher_Points_DistanceThreshold::initialize(const mrpt::containers::yaml& params)
33 {
35 
39 }
40 
42  const mrpt::maps::CMetricMap& pcGlobalMap, const mrpt::maps::CPointsMap& pcLocal,
43  const mrpt::poses::CPose3D& localPose, MatchState& ms, const layer_name_t& globalName,
44  const layer_name_t& localName, Pairings& out) const
45 {
46  MRPT_START
47 
49 
50  ASSERT_(pairingsPerPoint >= 1);
51  ASSERT_GT_(threshold, .0);
52  ASSERT_GE_(thresholdAngularDeg, .0);
53 
54  const mrpt::maps::NearestNeighborsCapable& nnGlobal =
55  *mp2p_icp::MapToNN(pcGlobalMap, true /*throw if cannot convert*/);
56 
57  out.potential_pairings += pcLocal.size() * pairingsPerPoint;
58 
59  // Empty maps? Nothing to do
60  if (pcGlobalMap.isEmpty() || pcLocal.empty()) return;
61 
63  pcLocal, localPose, maxLocalPointsPerLayer_, localPointsSampleSeed_);
64 
65  // Try to do matching only if the bounding boxes have some overlap:
66  if (!pcGlobalMap.boundingBox().intersection(
67  {tl.localMin, tl.localMax}, threshold + bounding_box_intersection_check_epsilon_))
68  return;
69 
70  // Prepare output: no correspondences initially:
71  out.paired_pt2pt.reserve(out.paired_pt2pt.size() + pcLocal.size());
72 
73  // Loop for each point in local map:
74  // --------------------------------------------------
75  const float maxDistForCorrespondenceSquared = mrpt::square(threshold);
76  const float angularThresholdFactorSquared = mrpt::square(mrpt::DEG2RAD(thresholdAngularDeg));
77 
78  const auto& lxs = pcLocal.getPointsBufferRef_x();
79  const auto& lys = pcLocal.getPointsBufferRef_y();
80  const auto& lzs = pcLocal.getPointsBufferRef_z();
81  const size_t nLocalPts = lxs.size();
82 
83  // Make sure the 3D kd-trees (if used internally) are up to date, from this
84  // single-thread call before entering into parallelization:
85  nnGlobal.nn_prepare_for_3d_queries();
86 
87  const auto lambdaAddPair = [this, &ms, &globalName, &localName, &lxs, &lys, &lzs](
88  mrpt::tfest::TMatchingPairList& outPairs, const size_t localIdx,
89  const mrpt::math::TPoint3Df& globalPt,
90  const uint64_t globalIdxOrID, const float errSqr)
91  {
92  // Filter out if global alread assigned, in another matcher up the
93  // pipeline, for example.
95  ms.globalPairedBitField.point_layers.at(globalName)[globalIdxOrID])
96  return; // skip, global point already paired.
97 
98  // Save new correspondence:
99  auto& p = outPairs.emplace_back();
100 
101  p.globalIdx = globalIdxOrID;
102  p.localIdx = localIdx;
103  p.global = globalPt;
104  p.local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
105 
106  p.errorSquareAfterTransformation = errSqr;
107 
108  // Mark local & global points as already paired:
110  {
111  ms.localPairedBitField.point_layers[localName].mark_as_set(localIdx);
112  ms.globalPairedBitField.point_layers[globalName].mark_as_set(globalIdxOrID);
113  }
114  };
115 
116 #if defined(MP2P_HAS_TBB)
117  // For the TBB lambdas:
118  // TBB call structure based on the beautiful implementation in KISS-ICP.
119  using Result = mrpt::tfest::TMatchingPairList;
120 
121  auto newPairs = tbb::parallel_reduce(
122  // Range
123  tbb::blocked_range<size_t>{0, nLocalPts},
124  // Identity
125  Result(),
126  // 1st lambda: Parallel computation
127  [&](const tbb::blocked_range<size_t>& r, Result res) -> Result
128  {
129  res.reserve(r.size());
130  std::vector<uint64_t> neighborIndices;
131  std::vector<float> neighborSqrDists;
132  std::vector<mrpt::math::TPoint3Df> neighborPts;
133  for (size_t i = r.begin(); i < r.end(); i++)
134  {
135  const size_t localIdx = tl.idxs.has_value() ? (*tl.idxs)[i] : i;
136 
138  ms.localPairedBitField.point_layers.at(localName)[localIdx])
139  continue; // skip, already paired.
140 
141  // For speed-up:
142  const float lx = tl.x_locals[i], ly = tl.y_locals[i], lz = tl.z_locals[i];
143 
144  const float localNormSqr = mrpt::square(lx) + mrpt::square(ly) + mrpt::square(lz);
145 
146  // Use a KD-tree to look for the nearnest neighbor(s) of
147  // (x_local, y_local, z_local) in the global map.
148  if (pairingsPerPoint == 1)
149  {
150  neighborIndices.resize(1);
151  neighborSqrDists.resize(1);
152  neighborPts.resize(1);
153 
154  if (!nnGlobal.nn_single_search(
155  {lx, ly, lz}, // Look closest to this guy
156  neighborPts[0], neighborSqrDists[0], neighborIndices[0]))
157  {
158  neighborIndices.clear();
159  neighborSqrDists.clear();
160  neighborPts.clear();
161  }
162  }
163  else
164  {
165  // Use nn_radius_search() which provides a maximum search
166  // distance:
167  nnGlobal.nn_radius_search(
168  {lx, ly, lz}, // Look closest to this guy
169  maxDistForCorrespondenceSquared, neighborPts, neighborSqrDists,
170  neighborIndices, pairingsPerPoint);
171  }
172 
173  // Distance below the threshold??
174  for (size_t k = 0; k < neighborIndices.size(); k++)
175  {
176  const auto tentativeErrSqr = neighborSqrDists.at(k);
177 
178  const float finalThresSqr = maxDistForCorrespondenceSquared +
179  angularThresholdFactorSquared * localNormSqr;
180 
181  if (tentativeErrSqr >= finalThresSqr) break; // skip this and the rest.
182 
183  lambdaAddPair(
184  res, localIdx, neighborPts.at(k), neighborIndices.at(k), tentativeErrSqr);
185  }
186  }
187  return res;
188  },
189  // 2nd lambda: Parallel reduction
190  [](Result a, const Result& b) -> Result
191  {
192  a.insert(a.end(), std::make_move_iterator(b.begin()), std::make_move_iterator(b.end()));
193  return a;
194  });
195 
196  out.paired_pt2pt.insert(
197  out.paired_pt2pt.end(), std::make_move_iterator(newPairs.begin()),
198  std::make_move_iterator(newPairs.end()));
199 #else
200 
201  out.paired_pt2pt.reserve(nLocalPts);
202 
203  std::vector<uint64_t> neighborIndices;
204  std::vector<float> neighborSqrDists;
205  std::vector<mrpt::math::TPoint3Df> neighborPts;
206 
207  for (size_t i = 0; i < nLocalPts; i++)
208  {
209  const size_t localIdx = tl.idxs.has_value() ? (*tl.idxs)[i] : i;
210 
212  ms.localPairedBitField.point_layers.at(localName)[localIdx])
213  continue; // skip, already paired.
214 
215  // For speed-up:
216  const float lx = tl.x_locals[i], ly = tl.y_locals[i], lz = tl.z_locals[i];
217 
218  const float localNormSqr = mrpt::square(lx) + mrpt::square(ly) + mrpt::square(lz);
219 
220  // Use a KD-tree to look for the nearnest neighbor(s) of
221  // (x_local, y_local, z_local) in the global map.
222  if (pairingsPerPoint == 1)
223  {
224  neighborIndices.resize(1);
225  neighborSqrDists.resize(1);
226  neighborPts.resize(1);
227 
228  if (!nnGlobal.nn_single_search(
229  {lx, ly, lz}, // Look closest to this guy
230  neighborPts[0], neighborSqrDists[0], neighborIndices[0]))
231  {
232  neighborIndices.clear();
233  neighborSqrDists.clear();
234  neighborPts.clear();
235  }
236  }
237  else
238  {
239  nnGlobal.nn_multiple_search(
240  {lx, ly, lz}, // Look closest to this guy
241  pairingsPerPoint, neighborPts, neighborSqrDists, neighborIndices);
242  }
243 
244  // Distance below the threshold??
245  for (size_t k = 0; k < neighborIndices.size(); k++)
246  {
247  const auto tentativeErrSqr = neighborSqrDists.at(k);
248 
249  const float finalThresSqr =
250  maxDistForCorrespondenceSquared + angularThresholdFactorSquared * localNormSqr;
251 
252  if (tentativeErrSqr >= finalThresSqr) break; // skip this and the rest.
253 
254  lambdaAddPair(
255  out.paired_pt2pt, localIdx, neighborPts.at(k), neighborIndices.at(k),
256  tentativeErrSqr);
257  }
258  }
259 #endif
260 
261  MRPT_END
262 }
mp2p_icp::Matcher_Points_DistanceThreshold::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Points_DistanceThreshold.cpp:32
mp2p_icp::Parameterizable::checkAllParametersAreRealized
void checkAllParametersAreRealized() const
Definition: Parameterizable.cpp:135
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
DECLARE_PARAMETER_OPT
#define DECLARE_PARAMETER_OPT(__yaml, __variable)
Definition: Parameterizable.h:152
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::y_locals
mrpt::aligned_std_vector< float > y_locals
Definition: Matcher_Points_Base.h:100
test.res
res
Definition: test.py:11
mp2p_icp::Matcher_Points_Base::allowMatchAlreadyMatchedGlobalPoints_
bool allowMatchAlreadyMatchedGlobalPoints_
Definition: Matcher_Points_Base.h:56
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_Points_DistanceThreshold::Matcher_Points_DistanceThreshold
Matcher_Points_DistanceThreshold()
Definition: Matcher_Points_DistanceThreshold.cpp:27
mp2p_icp::Matcher_Points_DistanceThreshold::pairingsPerPoint
uint32_t pairingsPerPoint
Definition: Matcher_Points_DistanceThreshold.h:54
mp2p_icp::Matcher_Points_DistanceThreshold::thresholdAngularDeg
double thresholdAngularDeg
Definition: Matcher_Points_DistanceThreshold.h:53
DECLARE_PARAMETER_REQ
#define DECLARE_PARAMETER_REQ(__yaml, __variable)
Definition: Parameterizable.h:162
mp2p_icp::Matcher_Points_DistanceThreshold
Definition: Matcher_Points_DistanceThreshold.h:30
mp2p_icp::Matcher_Points_DistanceThreshold::threshold
double threshold
Definition: Matcher_Points_DistanceThreshold.h:52
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_Points_DistanceThreshold::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_Points_DistanceThreshold.cpp:41
mp2p_icp::Matcher_Points_Base::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Points_Base.cpp:114
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
Matcher_Points_DistanceThreshold.h
Pointcloud matcher: fixed distance thresholds.
mp2p_icp::Matcher_Points_Base::localPointsSampleSeed_
uint64_t localPointsSampleSeed_
Definition: Matcher_Points_Base.h:48
mp2p_icp::MatchState::globalPairedBitField
pointcloud_bitfield_t globalPairedBitField
Like localPairedBitField for the global map.
Definition: Matcher.h:50
mp2p_icp::pointcloud_bitfield_t::point_layers
std::map< layer_name_t, DenseOrSparseBitField > point_layers
Definition: pointcloud_bitfield.h:82
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::Matcher_Points_Base::TransformedLocalPointCloud::x_locals
mrpt::aligned_std_vector< float > x_locals
Definition: Matcher_Points_Base.h:100
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