Matcher_Point2Plane.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_Point2Plane");
26 }
27 
28 void Matcher_Point2Plane::initialize(const mrpt::containers::yaml& params)
29 {
31 
32  MCP_LOAD_REQ(params, distanceThreshold);
33  MCP_LOAD_REQ(params, searchRadius);
34  MCP_LOAD_REQ(params, knn);
35  MCP_LOAD_REQ(params, planeEigenThreshold);
36  MCP_LOAD_REQ(params, minimumPlanePoints);
37  ASSERT_GE_(minimumPlanePoints, 3UL);
38 
39  MCP_LOAD_OPT(params, localPointMustFitPlaneToo);
40  MCP_LOAD_OPT(params, localToGlobalPlaneMinAbsCosine);
41 }
42 
43 // Filter the list of neighbors by maximum distance threshold:
44 static void filterListByMaxDist(
45  std::vector<size_t>& kddIdxs, std::vector<float>& kddSqrDist,
46  const float maxDistForCorrespondenceSquared)
47 {
48  // Faster common case: all points are valid:
49  if (!kddSqrDist.empty() &&
50  kddSqrDist.back() < maxDistForCorrespondenceSquared)
51  {
52  // Nothing to do: all knn points are within the range.
53  }
54  else
55  {
56  for (size_t j = 0; j < kddSqrDist.size(); j++)
57  {
58  if (kddSqrDist[j] > maxDistForCorrespondenceSquared)
59  {
60  kddIdxs.resize(j);
61  kddSqrDist.resize(j);
62  break;
63  }
64  }
65  }
66 }
67 
69  const mrpt::maps::CMetricMap& pcGlobalMap,
70  const mrpt::maps::CPointsMap& pcLocal,
71  const mrpt::poses::CPose3D& localPose, MatchState& ms,
72  [[maybe_unused]] const layer_name_t& globalName,
73  const layer_name_t& localName, Pairings& out) const
74 {
75  MRPT_START
76 
77  const auto* pcGlobalPtr =
78  dynamic_cast<const mrpt::maps::CPointsMap*>(&pcGlobalMap);
79  if (!pcGlobalPtr)
80  THROW_EXCEPTION_FMT(
81  "This class only supports global maps of point cloud types, but "
82  "found type '%s'",
83  pcGlobalMap.GetRuntimeClass()->className);
84  const auto& pcGlobal = *pcGlobalPtr;
85 
86  // Empty maps? Nothing to do
87  if (pcGlobal.empty() || pcLocal.empty()) return;
88 
90  pcLocal, localPose, maxLocalPointsPerLayer_, localPointsSampleSeed_);
91 
92  // Try to do matching only if the bounding boxes have some overlap:
93  if (!pcGlobal.boundingBox().intersection({tl.localMin, tl.localMax}))
94  return;
95 
96  // Prepare output: no correspondences initially:
97  out.paired_pt2pl.reserve(out.paired_pt2pl.size() + pcLocal.size() / 10);
98 
99  // Loop for each point in local map:
100  // --------------------------------------------------
101  const float maxDistForCorrespondenceSquared = mrpt::square(searchRadius);
102 
103  const auto& gxs = pcGlobal.getPointsBufferRef_x();
104  const auto& gys = pcGlobal.getPointsBufferRef_y();
105  const auto& gzs = pcGlobal.getPointsBufferRef_z();
106 
107  const auto& lxs = pcLocal.getPointsBufferRef_x();
108  const auto& lys = pcLocal.getPointsBufferRef_y();
109  const auto& lzs = pcLocal.getPointsBufferRef_z();
110 
111  std::vector<float> kddSqrDist, kddSqrDistLocal;
112  std::vector<size_t> kddIdxs, kddIdxsLocal;
113 
114  for (size_t i = 0; i < tl.x_locals.size(); i++)
115  {
116  const size_t localIdx = tl.idxs.has_value() ? (*tl.idxs)[i] : i;
117 
119  ms.localPairedBitField.point_layers.at(localName).at(localIdx))
120  continue; // skip, already paired.
121 
122  // Don't discard **global** map points if already used by another
123  // matcher, since the assumption of "plane" features implies that
124  // many local points may match the *same* "global plane", so it's ok
125  // to have multiple-local-to-one-global pairings.
126 
127  // For speed-up:
128  const float lx = tl.x_locals[i], ly = tl.y_locals[i],
129  lz = tl.z_locals[i];
130 
131  // Use a KD-tree to look for the nearnest neighbor of:
132  // (x_local, y_local, z_local)
133  // In "this" (global/reference) points map.
134 
135  pcGlobal.kdTreeNClosestPoint3DIdx(
136  lx, ly, lz, // Look closest to this guy
137  knn, // This max number of matches
138  kddIdxs, kddSqrDist);
139 
140  // Filter the list of neighbors by maximum distance threshold:
142  kddIdxs, kddSqrDist, maxDistForCorrespondenceSquared);
143 
144  // minimum: 3 points to be able to fit a plane
145  if (kddIdxs.size() < minimumPlanePoints) continue;
146 
148  gxs.data(), gys.data(), gzs.data(), kddIdxs);
149 
150  // Do these points look like a plane?
151 #if 0
152  std::cout << "eig values: " << eig.eigVals[0] << " " << eig.eigVals[1]
153  << " " << eig.eigVals[2]
154  << " eigvec0: " << eig.eigVectors[0].asString() << "\n"
155  << " eigvec1: " << eig.eigVectors[1].asString() << "\n"
156  << " eigvec2: " << eig.eigVectors[2].asString() << "\n";
157 #endif
158 
159  // e0/e2 must be < planeEigenThreshold:
160  if (eig.eigVals[0] > planeEigenThreshold * eig.eigVals[2]) continue;
161 
162  const auto& normal = eig.eigVectors[0];
163  const mrpt::math::TPoint3D planeCentroid = {
164  eig.meanCov.mean.x(), eig.meanCov.mean.y(), eig.meanCov.mean.z()};
165 
166  const auto thePlane = mrpt::math::TPlane(planeCentroid, normal);
167  const double ptPlaneDist = std::abs(thePlane.distance({lx, ly, lz}));
168 
169  if (ptPlaneDist > distanceThreshold) continue; // plane is too distant
170 
171  // Next, check plane-to-plane angle:
173  {
174  pcLocal.kdTreeNClosestPoint3DIdx(
175  // Look closest to this guy
176  lxs[localIdx], lys[localIdx], lzs[localIdx],
177  // This max number of matches
178  knn, kddIdxsLocal, kddSqrDistLocal);
179 
181  kddIdxsLocal, kddSqrDistLocal, maxDistForCorrespondenceSquared);
182 
183  // minimum: 3 points to be able to fit a plane
184  if (kddIdxsLocal.size() < minimumPlanePoints) continue;
185 
187  tl.x_locals.data(), tl.y_locals.data(), tl.z_locals.data(),
188  kddIdxsLocal);
189 
190  // Do these points look like a plane?
191  // e0/e2 must be < planeEigenThreshold:
192  if (eigLocal.eigVals[0] > planeEigenThreshold * eigLocal.eigVals[2])
193  continue;
194 
195  const auto& normalLocal = eigLocal.eigVectors[0];
196 
197  const float dotProd = normalLocal.x * normal.x +
198  normalLocal.y * normal.y +
199  normalLocal.z * normal.z;
200 
201  // Angle too large?
202  if (std::abs(dotProd) < localToGlobalPlaneMinAbsCosine) continue;
203  }
204 
205  // OK, all conditions pass: add the new pairing:
206  auto& p = out.paired_pt2pl.emplace_back();
207  p.pt_local = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
208  p.pl_global.centroid = planeCentroid;
209 
210  p.pl_global.plane = thePlane;
211 
212  // Mark local point as already paired:
213  ms.localPairedBitField.point_layers[localName].at(localIdx) = true;
214 
215  } // For each local point
216 
217  MRPT_END
218 }
mp2p_icp::Matcher_Point2Plane::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Point2Plane.cpp:28
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Matcher_Point2Plane
Definition: Matcher_Point2Plane.h:30
mp2p_icp::Matcher_Point2Plane::localPointMustFitPlaneToo
bool localPointMustFitPlaneToo
Definition: Matcher_Point2Plane.h:63
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::Matcher_Point2Plane::localToGlobalPlaneMinAbsCosine
double localToGlobalPlaneMinAbsCosine
Definition: Matcher_Point2Plane.h:64
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::idxs
std::optional< std::vector< std::size_t > > idxs
Definition: Matcher_Points_Base.h:89
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_Point2Plane::minimumPlanePoints
uint32_t minimumPlanePoints
Definition: Matcher_Point2Plane.h:61
mp2p_icp::Matcher_Point2Plane::knn
uint32_t knn
Definition: Matcher_Point2Plane.h:60
mp2p_icp::Matcher_Points_Base::localPointsSampleSeed_
uint64_t localPointsSampleSeed_
Definition: Matcher_Points_Base.h:48
mp2p_icp::Matcher_Point2Plane::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_Point2Plane.cpp:68
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_Point2Plane::Matcher_Point2Plane
Matcher_Point2Plane()
Definition: Matcher_Point2Plane.cpp:23
mp2p_icp::Matcher_Point2Plane::searchRadius
double searchRadius
Definition: Matcher_Point2Plane.h:59
mp2p_icp::Matcher_Point2Plane::planeEigenThreshold
double planeEigenThreshold
Definition: Matcher_Point2Plane.h:62
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::PointCloudEigen::eigVals
std::array< double, 3 > eigVals
Definition: estimate_points_eigen.h:35
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::x_locals
mrpt::aligned_std_vector< float > x_locals
Definition: Matcher_Points_Base.h:92
filterListByMaxDist
static void filterListByMaxDist(std::vector< size_t > &kddIdxs, std::vector< float > &kddSqrDist, const float maxDistForCorrespondenceSquared)
Definition: Matcher_Point2Plane.cpp:44
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
Matcher_Point2Plane.h
Pointcloud matcher: point to plane-fit of nearby points.
mp2p_icp::Matcher_Point2Plane::distanceThreshold
double distanceThreshold
Definition: Matcher_Point2Plane.h:58


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