optimal_tf_horn.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  * ------------------------------------------------------------------------- */
14 #include <mrpt/math/CMatrixFixed.h>
15 #include <mrpt/math/CQuaternion.h>
16 #include <mrpt/math/CVectorFixed.h>
17 
18 #include "visit_correspondences.h"
19 
20 using namespace mp2p_icp;
21 
22 // The next function is code ported from our former implementation in MRPT,
23 // from function: mrpt::tfest::se3_l2_internal()
24 // (BSD-3 Licence)
25 
26 // "Closed-form solution of absolute orientation using unit quaternions", BKP
27 // Horn, Journal of the Optical Society of America, 1987.
28 // Algorithm:
29 // 0. Preliminary
30 // pLi = { pLix, pLiy, pLiz }
31 // pRi = { pRix, pRiy, pRiz }
32 // -------------------------------------------------------
33 // 1. Find the centroids of the two sets of measurements:
34 // ct_locals = (1/n)*sum{i}( pLi ) ct_locals = { cLx, cLy, cLz }
35 // ct_global = (1/n)*sum{i}( pRi ) ct_global = { cRx, cRy, cRz }
36 //
37 // 2. Substract centroids from the point coordinates:
38 // pLi' = pLi - ct_locals pLi' = { pLix', pLiy', pLiz' }
39 // pRi' = pRi - ct_global pRi' = { pRix', pRiy', pRiz' }
40 //
41 // 3. For each pair of coordinates (correspondences) compute the nine possible
42 // products:
43 // pi1 = pLix'*pRix' pi2 = pLix'*pRiy' pi3 = pLix'*pRiz'
44 // pi4 = pLiy'*pRix' pi5 = pLiy'*pRiy' pi6 = pLiy'*pRiz'
45 // pi7 = pLiz'*pRix' pi8 = pLiz'*pRiy' pi9 = pLiz'*pRiz'
46 //
47 // 4. Compute S components:
48 // Sxx = sum{i}( pi1 ) Sxy = sum{i}( pi2 ) Sxz = sum{i}( pi3 )
49 // Syx = sum{i}( pi4 ) Syy = sum{i}( pi5 ) Syz = sum{i}( pi6 )
50 // Szx = sum{i}( pi7 ) Szy = sum{i}( pi8 ) Szz = sum{i}( pi9 )
51 //
52 // 5. Compute N components:
53 // [ Sxx+Syy+Szz Syz-Szy Szx-Sxz Sxy-Syx ]
54 // [ Syz-Szy Sxx-Syy-Szz Sxy+Syx Szx+Sxz ]
55 // N = [ Szx-Sxz Sxy+Syx -Sxx+Syy-Szz Syz+Szy ]
56 // [ Sxy-Syx Szx+Sxz Syz+Szy -Sxx-Syy+Szz ]
57 //
58 // 6. Rotation represented by the quaternion eigenvector correspondent to the
59 // higher eigenvalue of N
60 //
61 // 7. Scale computation (symmetric expression)
62 // s = sqrt( sum{i}( square(abs(pRi')) / sum{i}( square(abs(pLi')) ) )
63 //
64 // 8. Translation computation (distance between the Right centroid and the
65 // scaled and rotated Left centroid)
66 // t = ct_global-sR(ct_locals)
67 
68 // Returns false if the number of pairings is not >=3
69 static bool se3_l2_internal(
70  const mp2p_icp::Pairings& in, const WeightParameters& wp,
71  const mrpt::math::TPoint3D& ct_local, const mrpt::math::TPoint3D& ct_global,
72  mrpt::math::CQuaternionDouble& out_attitude,
73  OutlierIndices& in_out_outliers)
74 {
75  MRPT_START
76 
77  // Compute the centroids
78  const auto nPt2Pt = in.paired_pt2pt.size();
79  const auto nPt2Ln = in.paired_pt2ln.size();
80  const auto nPt2Pl = in.paired_pt2pl.size();
81  const auto nLn2Ln = in.paired_ln2ln.size();
82  const auto nPl2Pl = in.paired_pl2pl.size();
83 
84  ASSERTMSG_(
85  nPt2Ln == 0, "This solver cannot handle point-to-line pairings.");
86  ASSERTMSG_(
87  nPt2Pl == 0, "This solver cannot handle point-to-plane pairings yet.");
88  const auto nAllMatches = nPt2Pt + nLn2Ln + nPl2Pl;
89 
90  // Horn method needs at least 3 references
91  if (nAllMatches < 3) return false;
92 
93  auto S = mrpt::math::CMatrixDouble33::Zero();
94 
95  // Lambda: process each pairing:
96  auto lambda_each_pair = [&](const mrpt::math::TVector3D& bi,
97  const mrpt::math::TVector3D& ri,
98  const double wi) {
99  // These vectors are already direction vectors, or the
100  // centroids-centered relative positions of points. Compute the S matrix
101  // of cross products.
102  S(0, 0) += wi * ri.x * bi.x;
103  S(0, 1) += wi * ri.x * bi.y;
104  S(0, 2) += wi * ri.x * bi.z;
105 
106  S(1, 0) += wi * ri.y * bi.x;
107  S(1, 1) += wi * ri.y * bi.y;
108  S(1, 2) += wi * ri.y * bi.z;
109 
110  S(2, 0) += wi * ri.z * bi.x;
111  S(2, 1) += wi * ri.z * bi.y;
112  S(2, 2) += wi * ri.z * bi.z;
113  };
114 
115  auto lambda_final = [&](const double w_sum) {
116  // Normalize weights. OLAE assumes \sum(w_i) = 1.0
117  if (w_sum > .0) S *= (1.0 / w_sum);
118  };
119 
121  in, wp, ct_local, ct_global, in_out_outliers /*in/out*/,
122  // Operations to run on pairs:
123  lambda_each_pair, lambda_final,
124  false /* do not make unit point vectors for Horn */);
125 
126  // Construct the N matrix
127  auto N = mrpt::math::CMatrixDouble44::Zero();
128 
129  N(0, 0) = S(0, 0) + S(1, 1) + S(2, 2);
130  N(0, 1) = S(1, 2) - S(2, 1);
131  N(0, 2) = S(2, 0) - S(0, 2);
132  N(0, 3) = S(0, 1) - S(1, 0);
133 
134  N(1, 0) = N(0, 1);
135  N(1, 1) = S(0, 0) - S(1, 1) - S(2, 2);
136  N(1, 2) = S(0, 1) + S(1, 0);
137  N(1, 3) = S(2, 0) + S(0, 2);
138 
139  N(2, 0) = N(0, 2);
140  N(2, 1) = N(1, 2);
141  N(2, 2) = -S(0, 0) + S(1, 1) - S(2, 2);
142  N(2, 3) = S(1, 2) + S(2, 1);
143 
144  N(3, 0) = N(0, 3);
145  N(3, 1) = N(1, 3);
146  N(3, 2) = N(2, 3);
147  N(3, 3) = -S(0, 0) - S(1, 1) + S(2, 2);
148 
149  // q is the quaternion correspondent to the greatest eigenvector of the N
150  // matrix (last column in Z)
151  auto Z = mrpt::math::CMatrixDouble44::Zero();
152  std::vector<double> eigvals;
153  N.eig_symmetric(Z, eigvals, true /*sorted*/);
154 
155  auto v = Z.blockCopy<4, 1>(0, 3);
156 
157  ASSERTDEB_(
158  fabs(
159  sqrt(v[0] * v[0] + v[1] * v[1] + v[2] * v[2] + v[3] * v[3]) - 1.0) <
160  0.1);
161 
162  // Make q_r > 0
163  if (v[0] < 0)
164  {
165  v[0] *= -1;
166  v[1] *= -1;
167  v[2] *= -1;
168  v[3] *= -1;
169  }
170 
171  // out_transform: Create a pose rotation with the quaternion
172  for (unsigned int i = 0; i < 4; i++) out_attitude[i] = v[i];
173 
174 #if 0
175  // Compute scale
176  double s;
177  if (forceScaleToUnity)
178  {
179  s = 1.0; // Enforce scale to be 1
180  }
181  else
182  {
183  double num = 0.0;
184  double den = 0.0;
185  for (size_t i = 0; i < nMatches; i++)
186  {
187  num += ri[i].sqrNorm();
188  den += bi[i].sqrNorm();
189  }
190  // The scale:
191  s = std::sqrt(num / den);
192  }
193 #endif
194 
195  return true;
196  MRPT_END
197 }
198 
200  const mp2p_icp::Pairings& in, const WeightParameters& wp,
201  OptimalTF_Result& result)
202 {
203  MRPT_START
204 
205  result = OptimalTF_Result();
206 
207  // Normalize weights for each feature type and for each target (attitude
208  // / translation):
209  ASSERT_(wp.pair_weights.pt2pt >= .0);
210  ASSERT_(wp.pair_weights.ln2ln >= .0);
211  ASSERT_(wp.pair_weights.pl2pl >= .0);
212 
213  // Compute the centroids:
214  auto [ct_local, ct_global] =
215  eval_centroids_robust(in, result.outliers /* in: empty for now */);
216 
217  mrpt::math::CQuaternionDouble optimal_q;
218 
219  // Build the linear system & solves for optimal quaternion:
220  if (!se3_l2_internal(
221  in, wp, ct_local, ct_global, optimal_q, result.outliers /* in/out */))
222  return false;
223 
224  // Re-evaluate the centroids, now that we have a guess on outliers.
225  if (wp.use_scale_outlier_detector && !result.outliers.empty())
226  {
227  // Re-evaluate the centroids:
228  const auto [new_ct_local, new_ct_global] =
229  eval_centroids_robust(in, result.outliers);
230 
231  ct_local = new_ct_local;
232  ct_global = new_ct_global;
233 
234  // And rebuild the linear system with the new values:
235  if (!se3_l2_internal(
236  in, wp, ct_local, ct_global, optimal_q,
237  result.outliers /* in/out */))
238  return false;
239  }
240 
241  // quaternion to rotation matrix:
242  result.optimalPose = mrpt::poses::CPose3D(optimal_q, 0, 0, 0);
243 
244  // Use centroids to solve for optimal translation:
245  mrpt::math::TPoint3D pp;
246  result.optimalPose.composePoint(
247  ct_local.x, ct_local.y, ct_local.z, pp.x, pp.y, pp.z);
248  // Scale, if used, was: pp *= s;
249 
250  result.optimalPose.x(ct_global.x - pp.x);
251  result.optimalPose.y(ct_global.y - pp.y);
252  result.optimalPose.z(ct_global.z - pp.z);
253 
254  return true;
255 
256  MRPT_END
257 }
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:104
mp2p_icp
Definition: covariance.h:17
mp2p_icp::optimal_tf_horn
bool optimal_tf_horn(const mp2p_icp::Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
Definition: optimal_tf_horn.cpp:199
s
XmlRpcServer s
mp2p_icp::Coordinate::Z
@ Z
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::OptimalTF_Result
Definition: OptimalTF_Result.h:24
mp2p_icp::WeightParameters::pair_weights
PairWeights pair_weights
See docs for PairWeights.
Definition: WeightParameters.h:45
se3_l2_internal
static bool se3_l2_internal(const mp2p_icp::Pairings &in, const WeightParameters &wp, const mrpt::math::TPoint3D &ct_local, const mrpt::math::TPoint3D &ct_global, mrpt::math::CQuaternionDouble &out_attitude, OutlierIndices &in_out_outliers)
Definition: optimal_tf_horn.cpp:69
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
mp2p_icp::eval_centroids_robust
std::tuple< mrpt::math::TPoint3D, mrpt::math::TPoint3D > eval_centroids_robust(const Pairings &in, const OutlierIndices &outliers)
Definition: Pairings.cpp:59
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:105
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:102
visit_correspondences.h
Template that applies lambdas to unified vector forms of pairings.
optimal_tf_horn.h
Classic Horn's solution for optimal SE(3) transformation.
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::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