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-2021 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 auto* pcGlobalPtr =
49  dynamic_cast<const mrpt::maps::CPointsMap*>(&pcGlobalMap);
50  if (!pcGlobalPtr)
51  THROW_EXCEPTION_FMT(
52  "This class only supports global maps of point cloud types, but "
53  "found type '%s'",
54  pcGlobalMap.GetRuntimeClass()->className);
55  const auto& pcGlobal = *pcGlobalPtr;
56 
57  // Empty maps? Nothing to do
58  if (pcGlobal.empty() || pcLocal.empty()) return;
59 
61  pcLocal, localPose, maxLocalPointsPerLayer_, localPointsSampleSeed_);
62 
63  // Try to do matching only if the bounding boxes have some overlap:
64  if (!pcGlobal.boundingBox().intersection({tl.localMin, tl.localMax}))
65  return;
66 
67  // Prepare output: no correspondences initially:
68  out.paired_pt2pl.reserve(out.paired_pt2pl.size() + pcLocal.size() / 10);
69 
70  // Loop for each point in local map:
71  // --------------------------------------------------
72  const float maxDistForCorrespondenceSquared =
73  mrpt::square(distanceThreshold);
74 
75  const auto& gxs = pcGlobal.getPointsBufferRef_x();
76  const auto& gys = pcGlobal.getPointsBufferRef_y();
77  const auto& gzs = pcGlobal.getPointsBufferRef_z();
78 
79  const auto& lxs = pcLocal.getPointsBufferRef_x();
80  const auto& lys = pcLocal.getPointsBufferRef_y();
81  const auto& lzs = pcLocal.getPointsBufferRef_z();
82 
83  std::vector<float> kddSqrDist;
84  std::vector<size_t> kddIdxs;
85 
86  for (size_t i = 0; i < tl.x_locals.size(); i++)
87  {
88  const size_t localIdx = tl.idxs.has_value() ? (*tl.idxs)[i] : i;
89 
91  ms.localPairedBitField.point_layers.at(localName).at(localIdx))
92  continue; // skip, already paired.
93 
94  // Don't discard **global** map points if already used by another
95  // matcher, since the assumption of "line" features implies that
96  // many local points may match the *same* "global line", so it's ok
97  // to have multiple-local-to-one-global pairings.
98 
99  // For speed-up:
100  const float lx = tl.x_locals[i], ly = tl.y_locals[i],
101  lz = tl.z_locals[i];
102 
103  // Use a KD-tree to look for the nearnest neighbor of:
104  // (x_local, y_local, z_local)
105  // In "this" (global/reference) points map.
106 
107  pcGlobal.kdTreeNClosestPoint3DIdx(
108  lx, ly, lz, // Look closest to this guy
109  knn, // This max number of matches
110  kddIdxs, kddSqrDist);
111 
112  // Filter the list of neighbors by maximum distance threshold:
113 
114  // Faster common case: all points are valid:
115  if (!kddSqrDist.empty() &&
116  kddSqrDist.back() < maxDistForCorrespondenceSquared)
117  {
118  // Nothing to do: all knn points are within the range.
119  }
120  else
121  {
122  for (size_t j = 0; j < kddSqrDist.size(); j++)
123  {
124  if (kddSqrDist[j] > maxDistForCorrespondenceSquared)
125  {
126  kddIdxs.resize(j);
127  kddSqrDist.resize(j);
128  break;
129  }
130  }
131  }
132 
133  // minimum: 2 points to be able to fit a line
134  if (kddIdxs.size() < minimumLinePoints) continue;
135 
137  gxs.data(), gys.data(), gzs.data(), kddIdxs);
138 
139  // Do these points look like a line?
140 #if 0
141  std::cout << "eig values: " << eig.eigVals[0] << " " << eig.eigVals[1]
142  << " " << eig.eigVals[2]
143  << " eigvec0: " << eig.eigVectors[0].asString() << "\n"
144  << " eigvec1: " << eig.eigVectors[1].asString() << "\n"
145  << " eigvec2: " << eig.eigVectors[2].asString() << "\n";
146 #endif
147 
148  // e0/e{1,2} must be < lineEigenThreshold:
149  if (eig.eigVals[0] > lineEigenThreshold * eig.eigVals[2]) continue;
150  if (eig.eigVals[1] > lineEigenThreshold * eig.eigVals[2]) continue;
151 
152  auto& p = out.paired_pt2ln.emplace_back();
153  p.pt_local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
154 
155  const auto& normal = eig.eigVectors[2];
156  p.ln_global.pBase = {
157  eig.meanCov.mean.x(), eig.meanCov.mean.y(), eig.meanCov.mean.z()};
158  p.ln_global.director = normal.unitarize();
159 
160  // Mark local point as already paired:
161  ms.localPairedBitField.point_layers[localName].at(localIdx) = true;
162 
163  } // For each local point
164 
165  MRPT_END
166 }
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud
Definition: Matcher_Points_Base.h:82
mp2p_icp::Matcher
Definition: Matcher.h:70
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::y_locals
mrpt::aligned_std_vector< float > y_locals
Definition: Matcher_Points_Base.h:92
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::Matcher_Points_Base::allowMatchAlreadyMatchedPoints_
bool allowMatchAlreadyMatchedPoints_
Definition: Matcher_Points_Base.h:52
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
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:89
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:123
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::z_locals
mrpt::aligned_std_vector< float > z_locals
Definition: Matcher_Points_Base.h:92
mp2p_icp::MatchState
Definition: Matcher.h:34
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::pointcloud_bitfield_t::point_layers
std::map< layer_name_t, std::vector< bool > > point_layers
Definition: metricmap.h:223
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::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::PointCloudEigen::eigVectors
std::array< mrpt::math::TVector3D, 3 > eigVectors
Definition: estimate_points_eigen.h:33
mp2p_icp::Matcher_Point2Line::knn
uint32_t knn
Definition: Matcher_Point2Line.h:53
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:30
mp2p_icp::PointCloudEigen::meanCov
mrpt::poses::CPointPDFGaussian meanCov
Definition: estimate_points_eigen.h:32
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:44
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(metric_map_t, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp
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:35
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:92
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:173
mp2p_icp::Matcher_Point2Line
Definition: Matcher_Point2Line.h:30


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:03