Matcher_Point2Line.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/version.h>
18 
20 
21 using namespace mp2p_icp;
22 
24 {
25  mrpt::system::COutputLogger::setLoggerName("Matcher_Point2Line");
26 }
27 
28 void Matcher_Point2Line::initialize(const mrpt::containers::yaml& params)
29 {
31 
32  MCP_LOAD_REQ(params, distanceThreshold);
33  MCP_LOAD_REQ(params, knn);
34  MCP_LOAD_REQ(params, lineEigenThreshold);
35  MCP_LOAD_REQ(params, minimumLinePoints);
36  ASSERT_GE_(minimumLinePoints, 2UL);
37 }
38 
40  const mrpt::maps::CMetricMap& pcGlobalMap,
41  const mrpt::maps::CPointsMap& pcLocal,
42  const mrpt::poses::CPose3D& localPose, MatchState& ms,
43  [[maybe_unused]] const layer_name_t& globalName,
44  const layer_name_t& localName, Pairings& out) const
45 {
46  MRPT_START
47 
48  const mrpt::maps::NearestNeighborsCapable& nnGlobal =
49  *mp2p_icp::MapToNN(pcGlobalMap, true /*throw if cannot convert*/);
50 
51  out.potential_pairings += pcLocal.size();
52 
53  // Empty maps? Nothing to do
54  if (pcGlobalMap.isEmpty() || pcLocal.empty()) return;
55 
57  pcLocal, localPose, maxLocalPointsPerLayer_, localPointsSampleSeed_);
58 
59  // Try to do matching only if the bounding boxes have some overlap:
60  if (!pcGlobalMap.boundingBox().intersection(
61  {tl.localMin, tl.localMax},
63  return;
64 
65  // Prepare output: no correspondences initially:
66  out.paired_pt2pl.reserve(out.paired_pt2pl.size() + pcLocal.size() / 10);
67 
68  // Loop for each point in local map:
69  // --------------------------------------------------
70  const float maxDistForCorrespondenceSquared =
71  mrpt::square(distanceThreshold);
72 
73  const auto& lxs = pcLocal.getPointsBufferRef_x();
74  const auto& lys = pcLocal.getPointsBufferRef_y();
75  const auto& lzs = pcLocal.getPointsBufferRef_z();
76 
77  std::vector<float> kddSqrDist;
78  std::vector<uint64_t> kddIdxs;
79  std::vector<mrpt::math::TPoint3Df> kddPts;
80  std::vector<float> kddXs, kddYs, kddZs;
81 
82  for (size_t i = 0; i < tl.x_locals.size(); i++)
83  {
84  const size_t localIdx = tl.idxs.has_value() ? (*tl.idxs)[i] : i;
85 
87  ms.localPairedBitField.point_layers.at(localName)[localIdx])
88  continue; // skip, already paired.
89 
90  // Don't discard **global** map points if already used by another
91  // matcher, since the assumption of "line" features implies that
92  // many local points may match the *same* "global line", so it's ok
93  // to have multiple-local-to-one-global pairings.
94 
95  // For speed-up:
96  const float lx = tl.x_locals[i], ly = tl.y_locals[i],
97  lz = tl.z_locals[i];
98 
99  // Use a KD-tree to look for the nearnest neighbor(s) of
100  // (x_local, y_local, z_local) in the global map.
101  nnGlobal.nn_multiple_search(
102  {lx, ly, lz}, // Look closest to this guy
103  knn, kddPts, kddSqrDist, kddIdxs);
104 
105  // Filter the list of neighbors by maximum distance threshold:
106 
107  // Faster common case: all points are valid:
108  if (!kddSqrDist.empty() &&
109  kddSqrDist.back() < maxDistForCorrespondenceSquared)
110  {
111  // Nothing to do: all knn points are within the range.
112  }
113  else
114  {
115  for (size_t j = 0; j < kddSqrDist.size(); j++)
116  {
117  if (kddSqrDist[j] > maxDistForCorrespondenceSquared)
118  {
119  kddIdxs.resize(j);
120  kddSqrDist.resize(j);
121  break;
122  }
123  }
124  }
125 
126  // minimum: 2 points to be able to fit a line
127  if (kddIdxs.size() < minimumLinePoints) continue;
128 
129  mp2p_icp::vector_of_points_to_xyz(kddPts, kddXs, kddYs, kddZs);
130 
132  kddXs.data(), kddYs.data(), kddZs.data(), std::nullopt,
133  kddPts.size());
134 
135  // Do these points look like a line?
136 #if 0
137  std::cout << "eig values: " << eig.eigVals[0] << " " << eig.eigVals[1]
138  << " " << eig.eigVals[2]
139  << " eigvec0: " << eig.eigVectors[0].asString() << "\n"
140  << " eigvec1: " << eig.eigVectors[1].asString() << "\n"
141  << " eigvec2: " << eig.eigVectors[2].asString() << "\n";
142 #endif
143 
144  // e0/e{1,2} must be < lineEigenThreshold:
145  if (eig.eigVals[0] > lineEigenThreshold * eig.eigVals[2]) continue;
146  if (eig.eigVals[1] > lineEigenThreshold * eig.eigVals[2]) continue;
147 
148  auto& p = out.paired_pt2ln.emplace_back();
149  p.pt_local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
150 
151  const auto& normal = eig.eigVectors[2];
152  p.ln_global.pBase = {
153  eig.meanCov.mean.x(), eig.meanCov.mean.y(), eig.meanCov.mean.z()};
154  p.ln_global.director = normal.unitarize();
155 
156  // Mark local point as already paired:
157  ms.localPairedBitField.point_layers[localName].mark_as_set(localIdx);
158 
159  } // For each local point
160 
161  MRPT_END
162 }
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:72
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::y_locals
mrpt::aligned_std_vector< float > y_locals
Definition: Matcher_Points_Base.h:100
mp2p_icp::Pairings
Definition: Pairings.h:94
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::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_Point2Line::distanceThreshold
double distanceThreshold
Definition: Matcher_Point2Line.h:52
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::idxs
std::optional< std::vector< std::size_t > > idxs
Definition: Matcher_Points_Base.h:97
Matcher_Point2Line.h
Pointcloud matcher: point to line-fit of nearby points.
mp2p_icp::Matcher_Points_Base::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Points_Base.cpp:120
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:36
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Matcher_Point2Line::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Point2Line.cpp:28
mp2p_icp::Matcher_Points_Base::localPointsSampleSeed_
uint64_t localPointsSampleSeed_
Definition: Matcher_Points_Base.h:48
mp2p_icp::Matcher_Point2Line::Matcher_Point2Line
Matcher_Point2Line()
Definition: Matcher_Point2Line.cpp:23
mp2p_icp::PointCloudEigen::eigVectors
std::array< mrpt::math::TVector3D, 3 > eigVectors
Definition: estimate_points_eigen.h:35
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
mp2p_icp::Matcher_Point2Line::knn
uint32_t knn
Definition: Matcher_Point2Line.h:53
mp2p_icp::pointcloud_bitfield_t::point_layers
std::map< layer_name_t, DenseOrSparseBitField > point_layers
Definition: pointcloud_bitfield.h:82
mp2p_icp::vector_of_points_to_xyz
void vector_of_points_to_xyz(const std::vector< mrpt::math::TPoint3Df > &pts, std::vector< float > &xs, std::vector< float > &ys, std::vector< float > &zs)
Definition: estimate_points_eigen.cpp:116
mp2p_icp::Matcher_Point2Line::lineEigenThreshold
double lineEigenThreshold
Definition: Matcher_Point2Line.h:55
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:46
mp2p_icp::MapToNN
const mrpt::maps::NearestNeighborsCapable * MapToNN(const mrpt::maps::CMetricMap &map, bool throwIfNotImplemented)
Definition: metricmap.cpp:690
mp2p_icp::Matcher_Point2Line::minimumLinePoints
uint32_t minimumLinePoints
Definition: Matcher_Point2Line.h:54
mp2p_icp::PointCloudEigen::eigVals
std::array< double, 3 > eigVals
Definition: estimate_points_eigen.h:37
mp2p_icp::Matcher_Point2Line::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_Point2Line.cpp:39
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:174
mp2p_icp::Matcher_Point2Line
Definition: Matcher_Point2Line.h:30


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Tue Jul 2 2024 02:47:25