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-2021 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  OutlierIndices new_outliers;
89  new_outliers.point2point.reserve(in_out_outliers.point2point.size());
90 
91  auto it_next_outlier = in_out_outliers.point2point.begin();
92 
93  // Terms contributed by points & vectors have now the uniform form of
94  // unit vectors:
95  for (std::size_t i = 0; i < nAllMatches; i++)
96  {
97  // Skip outlier?
98  if (it_next_outlier != in_out_outliers.point2point.end() &&
99  i == *it_next_outlier)
100  {
101  ++it_next_outlier;
102  // also copy idx:
103  new_outliers.point2point.push_back(i);
104  continue;
105  }
106 
107  // Get "bi" (this/global) & "ri" (other/local) vectors:
108  TVector3D bi, ri;
109  double wi = .0;
110 
111  // Points, lines, planes, are all stored in sequence:
112  if (i < nPt2Pt)
113  {
114  // point-to-point pairing: normalize(point-centroid)
115  const auto& p = in.paired_pt2pt[i];
116  wi = waPoints;
117 
118  if (i >= cur_point_block_start + cur_point_block_weights->first)
119  {
120  ASSERT_(cur_point_block_weights != point_weights.end());
121  ++cur_point_block_weights; // move to next block
122  cur_point_block_start = i;
123  }
124  wi *= cur_point_block_weights->second;
125  // (solution will be normalized via w_sum a the end)
126 
127  bi = p.global - ct_global;
128  ri = p.local - ct_local;
129 
130  const auto bi_n = bi.norm(), ri_n = ri.norm();
131 
132  if (bi_n < 1e-4 || ri_n < 1e-4)
133  {
134  // In the rare event of a point (almost) exactly on the
135  // centroid, just discard it:
136  continue;
137  }
138 
139  // Horn requires regular relative vectors.
140  // OLAE requires unit vectors.
141  if (normalize_relative_point_vectors)
142  {
143  bi *= 1.0 / bi_n;
144  ri *= 1.0 / ri_n;
145  }
146 
147  // Note: ideally, both norms should be equal if noiseless and a
148  // real pairing. Let's use this property to detect outliers:
150  {
151  const double scale_mismatch =
152  std::max(bi_n, ri_n) / std::min(bi_n, ri_n);
153  if (scale_mismatch > wp.scale_outlier_threshold)
154  {
155  // Discard this pairing:
156  new_outliers.point2point.push_back(i);
158 
159  continue; // Skip (same effect than: wi = 0)
160  }
161  }
162  }
163  else if (i < nPt2Pt + nLn2Ln)
164  {
165  // line-to-line pairing:
166  wi = waLines;
167 
168  const auto idxLine = i - nPt2Pt;
169 
170  bi = in.paired_ln2ln[idxLine].ln_global.getDirectorVector();
171  ri = in.paired_ln2ln[idxLine].ln_local.getDirectorVector();
172 
173  ASSERTDEB_LT_(std::abs(bi.norm() - 1.0), 0.01);
174  ASSERTDEB_LT_(std::abs(ri.norm() - 1.0), 0.01);
175  }
176  else
177  {
178  // plane-to-plane pairing:
179  wi = waPlanes;
180 
181  const auto idxPlane = i - (nPt2Pt + nLn2Ln);
182  bi = in.paired_pl2pl[idxPlane].p_global.plane.getNormalVector();
183  ri = in.paired_pl2pl[idxPlane].p_local.plane.getNormalVector();
184 
185  ASSERTDEB_LT_(std::abs(bi.norm() - 1.0), 0.01);
186  ASSERTDEB_LT_(std::abs(ri.norm() - 1.0), 0.01);
187  }
188 
189  // If we are about to apply a robust kernel, we need a reference
190  // attitude wrt which apply such kernel, i.e. the "current SE(3)
191  // estimation" inside a caller ICP loop.
192  if (wp.use_robust_kernel)
193  {
194  ASSERT_(wp.currentEstimateForRobust.has_value());
195  const TVector3D ri2 = wp.currentEstimateForRobust->composePoint(ri);
196 
197  // mismatch angle between the two vectors:
198  const double ang =
199  std::acos(ri2.x * bi.x + ri2.y * bi.y + ri2.z * bi.z);
200  const double A = wp.robust_kernel_param;
201  const double B = wp.robust_kernel_scale;
202  if (ang > A)
203  {
204  const auto f = 1.0 / (1.0 + B * mrpt::square(ang - A));
205  wi *= f;
206  }
207  }
208 
209  ASSERT_(wi > .0);
210  w_sum += wi;
211 
212  // Visit this pair:
213  lambda_each_pair(bi, ri, wi);
214 
215  } // for each match
216 
217  in_out_outliers = std::move(new_outliers);
218 
219  lambda_final(w_sum);
220 
221  // send out optional stats
222  if (outStats.has_value()) outStats.value().get() = stats;
223 
224 } // end visit_correspondences()
225 
228 } // namespace mp2p_icp
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:104
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
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::WeightParameters::use_scale_outlier_detector
bool use_scale_outlier_detector
Definition: WeightParameters.h:34
mp2p_icp::WeightParameters::robust_kernel_scale
double robust_kernel_scale
Definition: WeightParameters.h:55
mp2p_icp::WeightParameters::pair_weights
PairWeights pair_weights
See docs for PairWeights.
Definition: WeightParameters.h:45
mp2p_icp::OutlierIndices::point2point
std::vector< std::size_t > point2point
Definition: Pairings.h:189
mp2p_icp::Pairings::point_weights
std::vector< std::pair< std::size_t, double > > point_weights
Definition: Pairings.h:111
mp2p_icp::WeightParameters::robust_kernel_param
double robust_kernel_param
Definition: WeightParameters.h:55
mp2p_icp::PairWeights::pl2pl
double pl2pl
Weight of plane-to-plane pairs.
Definition: PairWeights.h:38
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:53
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:105
mp2p_icp::WeightParameters::scale_outlier_threshold
double scale_outlier_threshold
Definition: WeightParameters.h:42
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:102
mp2p_icp::WeightParameters::use_robust_kernel
bool use_robust_kernel
Definition: WeightParameters.h:49
mp2p_icp::WeightParameters
Definition: WeightParameters.h:25
mp2p_icp::OutlierIndices
Definition: Pairings.h:187
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:101
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:103
mp2p_icp::PairWeights::pt2pt
double pt2pt
Definition: PairWeights.h:32


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