visit_correspondences.h
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  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/Pairings.h>
16 #include <mrpt/core/optional_ref.h>
17 #include <mrpt/math/TPoint3D.h>
18 
19 namespace mp2p_icp
20 {
25 {
27 };
28 
30 template <class LAMBDA, class LAMBDA2>
32  const Pairings& in, const WeightParameters& wp,
33  const mrpt::math::TPoint3D& ct_local, const mrpt::math::TPoint3D& ct_global,
34  OutlierIndices& in_out_outliers, LAMBDA lambda_each_pair,
35  LAMBDA2 lambda_final, bool normalize_relative_point_vectors,
36  const mrpt::optional_ref<VisitCorrespondencesStats>& outStats =
37  std::nullopt)
38 {
39  using mrpt::math::TPoint3D;
40  using mrpt::math::TVector3D;
41 
42  const auto nPt2Pt = in.paired_pt2pt.size();
43  const auto nPt2Ln = in.paired_pt2ln.size();
44  const auto nPt2Pl = in.paired_pt2pl.size();
45  const auto nLn2Ln = in.paired_ln2ln.size();
46  const auto nPl2Pl = in.paired_pl2pl.size();
47 
48  ASSERTMSG_(
49  nPt2Ln == 0, "This solver cannot handle point-to-line pairings.");
50  ASSERTMSG_(
51  nPt2Pl == 0, "This solver cannot handle point-to-plane pairings yet.");
52 
53  const auto nAllMatches = nPt2Pt + nLn2Ln + nPl2Pl;
54 
56 
57  // weight of points, block by block:
58  auto point_weights = in.point_weights;
59  if (point_weights.empty())
60  {
61  // Default, equal weights:
62  point_weights.emplace_back(nPt2Pt, 1.0);
63  }
64 
65  auto cur_point_block_weights = point_weights.begin();
66  std::size_t cur_point_block_start = 0;
67 
68  // Normalized weights for attitude "waXX":
69  double waPoints, waLines, waPlanes;
70  {
71  const auto wPt = wp.pair_weights.pt2pt, wLi = wp.pair_weights.ln2ln,
72  wPl = wp.pair_weights.pl2pl;
73 
74  ASSERTMSG_(
75  wPt + wLi + wPl > .0,
76  "All, point, line, plane attidude weights, are <=0 (!)");
77 
78  const auto k = 1.0 / (wPt * nPt2Pt + wLi * nLn2Ln + wPl * nPl2Pl);
79  waPoints = wPt * k;
80  waLines = wLi * k;
81  waPlanes = wPl * k;
82  }
83 
84  // Accumulator of robust kernel terms (and other user-provided weights)
85  // to normalize the final linear equation at the end:
86  double w_sum = .0;
87 
88  const robust_sqrt_weight_func_t robustSqrtWeightFunc =
91 
92  OutlierIndices new_outliers;
93  new_outliers.point2point.reserve(in_out_outliers.point2point.size());
94 
95  auto it_next_outlier = in_out_outliers.point2point.begin();
96 
97  // Terms contributed by points & vectors have now the uniform form of
98  // unit vectors:
99  for (std::size_t i = 0; i < nAllMatches; i++)
100  {
101  // Skip outlier?
102  if (it_next_outlier != in_out_outliers.point2point.end() &&
103  i == *it_next_outlier)
104  {
105  ++it_next_outlier;
106  // also copy idx:
107  new_outliers.point2point.push_back(i);
108  continue;
109  }
110 
111  // Get "bi" (this/global) & "ri" (other/local) vectors:
112  TVector3D bi, ri;
113  double wi = .0;
114 
115  // Points, lines, planes, are all stored in sequence:
116  if (i < nPt2Pt)
117  {
118  // point-to-point pairing: normalize(point-centroid)
119  const auto& p = in.paired_pt2pt[i];
120  wi = waPoints;
121 
122  if (i >= cur_point_block_start + cur_point_block_weights->first)
123  {
124  ASSERT_(cur_point_block_weights != point_weights.end());
125  ++cur_point_block_weights; // move to next block
126  cur_point_block_start = i;
127  }
128  wi *= cur_point_block_weights->second;
129  // (solution will be normalized via w_sum a the end)
130 
131  bi = p.global - ct_global;
132  ri = p.local - ct_local;
133 
134  const auto bi_n = bi.norm(), ri_n = ri.norm();
135 
136  if (bi_n < 1e-4 || ri_n < 1e-4)
137  {
138  // In the rare event of a point (almost) exactly on the
139  // centroid, just discard it:
140  continue;
141  }
142 
143  // Horn requires regular relative vectors.
144  // OLAE requires unit vectors.
145  if (normalize_relative_point_vectors)
146  {
147  bi *= 1.0 / bi_n;
148  ri *= 1.0 / ri_n;
149  }
150 
151  // Note: ideally, both norms should be equal if noiseless and a
152  // real pairing. Let's use this property to detect outliers:
154  {
155  const double scale_mismatch =
156  std::max(bi_n, ri_n) / std::min(bi_n, ri_n);
157  if (scale_mismatch > wp.scale_outlier_threshold)
158  {
159  // Discard this pairing:
160  new_outliers.point2point.push_back(i);
162 
163  continue; // Skip (same effect than: wi = 0)
164  }
165  }
166  }
167  else if (i < nPt2Pt + nLn2Ln)
168  {
169  // line-to-line pairing:
170  wi = waLines;
171 
172  const auto idxLine = i - nPt2Pt;
173 
174  bi = in.paired_ln2ln[idxLine].ln_global.getDirectorVector();
175  ri = in.paired_ln2ln[idxLine].ln_local.getDirectorVector();
176 
177  ASSERTDEB_LT_(std::abs(bi.norm() - 1.0), 0.01);
178  ASSERTDEB_LT_(std::abs(ri.norm() - 1.0), 0.01);
179  }
180  else
181  {
182  // plane-to-plane pairing:
183  wi = waPlanes;
184 
185  const auto idxPlane = i - (nPt2Pt + nLn2Ln);
186  bi = in.paired_pl2pl[idxPlane].p_global.plane.getNormalVector();
187  ri = in.paired_pl2pl[idxPlane].p_local.plane.getNormalVector();
188 
189  ASSERTDEB_LT_(std::abs(bi.norm() - 1.0), 0.01);
190  ASSERTDEB_LT_(std::abs(ri.norm() - 1.0), 0.01);
191  }
192 
193  // If we are about to apply a robust kernel, we need a reference
194  // attitude wrt which apply such kernel, i.e. the "current SE(3)
195  // estimation" inside a caller ICP loop.
196  if (robustSqrtWeightFunc)
197  {
198  ASSERT_(wp.currentEstimateForRobust.has_value());
199  const TVector3D ri2 = wp.currentEstimateForRobust->composePoint(ri);
200 
201  // mismatch between the two vectors:
202  const double errorSqr = mrpt::square(ri2.x - bi.x) +
203  mrpt::square(ri2.y - bi.y) +
204  mrpt::square(ri2.z - bi.z);
205  wi *= robustSqrtWeightFunc(errorSqr);
206  }
207 
208  ASSERT_(wi > .0);
209  w_sum += wi;
210 
211  // Visit this pair:
212  lambda_each_pair(bi, ri, wi);
213 
214  } // for each match
215 
216  in_out_outliers = std::move(new_outliers);
217 
218  lambda_final(w_sum);
219 
220  // send out optional stats
221  if (outStats.has_value()) outStats.value().get() = stats;
222 
223 } // end visit_correspondences()
224 
227 } // namespace mp2p_icp
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:107
mp2p_icp
Definition: covariance.h:17
mp2p_icp::VisitCorrespondencesStats::num_pairings_discarded_scale_outliers
uint32_t num_pairings_discarded_scale_outliers
Definition: visit_correspondences.h:26
mp2p_icp::robust_sqrt_weight_func_t
std::function< double(double)> robust_sqrt_weight_func_t
Definition: robust_kernels.h:37
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::WeightParameters::use_scale_outlier_detector
bool use_scale_outlier_detector
Definition: WeightParameters.h:35
mp2p_icp::WeightParameters::pair_weights
PairWeights pair_weights
See docs for PairWeights.
Definition: WeightParameters.h:46
mp2p_icp::OutlierIndices::point2point
std::vector< std::size_t > point2point
Definition: Pairings.h:198
mp2p_icp::Pairings::point_weights
std::vector< std::pair< std::size_t, double > > point_weights
Definition: Pairings.h:120
mp2p_icp::WeightParameters::robust_kernel_param
double robust_kernel_param
Definition: WeightParameters.h:56
mp2p_icp::PairWeights::pl2pl
double pl2pl
Weight of plane-to-plane pairs.
Definition: PairWeights.h:38
mp2p_icp::create_robust_kernel
robust_sqrt_weight_func_t create_robust_kernel(const RobustKernel kernel, const double kernelParam)
Definition: robust_kernels.h:49
mp2p_icp::PairWeights::ln2ln
double ln2ln
Weight of line-to-line pairs.
Definition: PairWeights.h:37
Pairings.h
Common types for all SE(3) optimal transformation methods.
WeightParameters.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::WeightParameters::currentEstimateForRobust
std::optional< mrpt::poses::CPose3D > currentEstimateForRobust
Definition: WeightParameters.h:54
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:108
mp2p_icp::WeightParameters::scale_outlier_threshold
double scale_outlier_threshold
Definition: WeightParameters.h:43
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:105
mp2p_icp::WeightParameters
Definition: WeightParameters.h:26
mp2p_icp::OutlierIndices
Definition: Pairings.h:196
mp2p_icp::visit_correspondences
void visit_correspondences(const Pairings &in, const WeightParameters &wp, const mrpt::math::TPoint3D &ct_local, const mrpt::math::TPoint3D &ct_global, OutlierIndices &in_out_outliers, LAMBDA lambda_each_pair, LAMBDA2 lambda_final, bool normalize_relative_point_vectors, const mrpt::optional_ref< VisitCorrespondencesStats > &outStats=std::nullopt)
Definition: visit_correspondences.h:31
mp2p_icp::VisitCorrespondencesStats
Definition: visit_correspondences.h:24
mp2p_icp::Pairings::paired_pt2pt
mrpt::tfest::TMatchingPairList paired_pt2pt
Definition: Pairings.h:104
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:106
mp2p_icp::WeightParameters::robust_kernel
RobustKernel robust_kernel
Definition: WeightParameters.h:50
mp2p_icp::PairWeights::pt2pt
double pt2pt
Definition: PairWeights.h:32


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