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-2024 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, const mrpt::math::TPoint3D& ct_local,
71  const mrpt::math::TPoint3D& ct_global, mrpt::math::CQuaternionDouble& out_attitude,
72  OutlierIndices& in_out_outliers)
73 {
74  MRPT_START
75 
76  // Compute the centroids
77  const auto nPt2Pt = in.paired_pt2pt.size();
78  const auto nPt2Ln = in.paired_pt2ln.size();
79  const auto nPt2Pl = in.paired_pt2pl.size();
80  const auto nLn2Ln = in.paired_ln2ln.size();
81  const auto nPl2Pl = in.paired_pl2pl.size();
82 
83  ASSERTMSG_(nPt2Ln == 0, "This solver cannot handle point-to-line pairings.");
84  ASSERTMSG_(nPt2Pl == 0, "This solver cannot handle point-to-plane pairings yet.");
85  const auto nAllMatches = nPt2Pt + nLn2Ln + nPl2Pl;
86 
87  // Horn method needs at least 3 references
88  if (nAllMatches < 3) return false;
89 
90  auto S = mrpt::math::CMatrixDouble33::Zero();
91 
92  // Lambda: process each pairing:
93  auto lambda_each_pair =
94  [&](const mrpt::math::TVector3D& bi, const mrpt::math::TVector3D& ri, const double wi)
95  {
96  // These vectors are already direction vectors, or the
97  // centroids-centered relative positions of points. Compute the S matrix
98  // of cross products.
99  S(0, 0) += wi * ri.x * bi.x;
100  S(0, 1) += wi * ri.x * bi.y;
101  S(0, 2) += wi * ri.x * bi.z;
102 
103  S(1, 0) += wi * ri.y * bi.x;
104  S(1, 1) += wi * ri.y * bi.y;
105  S(1, 2) += wi * ri.y * bi.z;
106 
107  S(2, 0) += wi * ri.z * bi.x;
108  S(2, 1) += wi * ri.z * bi.y;
109  S(2, 2) += wi * ri.z * bi.z;
110  };
111 
112  auto lambda_final = [&](const double w_sum)
113  {
114  // Normalize weights. OLAE assumes \sum(w_i) = 1.0
115  if (w_sum > .0) S *= (1.0 / w_sum);
116  };
117 
119  in, wp, ct_local, ct_global, in_out_outliers /*in/out*/,
120  // Operations to run on pairs:
121  lambda_each_pair, lambda_final, false /* do not make unit point vectors for Horn */);
122 
123  // Construct the N matrix
124  auto N = mrpt::math::CMatrixDouble44::Zero();
125 
126  N(0, 0) = S(0, 0) + S(1, 1) + S(2, 2);
127  N(0, 1) = S(1, 2) - S(2, 1);
128  N(0, 2) = S(2, 0) - S(0, 2);
129  N(0, 3) = S(0, 1) - S(1, 0);
130 
131  N(1, 0) = N(0, 1);
132  N(1, 1) = S(0, 0) - S(1, 1) - S(2, 2);
133  N(1, 2) = S(0, 1) + S(1, 0);
134  N(1, 3) = S(2, 0) + S(0, 2);
135 
136  N(2, 0) = N(0, 2);
137  N(2, 1) = N(1, 2);
138  N(2, 2) = -S(0, 0) + S(1, 1) - S(2, 2);
139  N(2, 3) = S(1, 2) + S(2, 1);
140 
141  N(3, 0) = N(0, 3);
142  N(3, 1) = N(1, 3);
143  N(3, 2) = N(2, 3);
144  N(3, 3) = -S(0, 0) - S(1, 1) + S(2, 2);
145 
146  // q is the quaternion correspondent to the greatest eigenvector of the N
147  // matrix (last column in Z)
148  auto Z = mrpt::math::CMatrixDouble44::Zero();
149  std::vector<double> eigvals;
150  N.eig_symmetric(Z, eigvals, true /*sorted*/);
151 
152  auto v = Z.blockCopy<4, 1>(0, 3);
153 
154  ASSERTDEB_(fabs(sqrt(v[0] * v[0] + v[1] * v[1] + v[2] * v[2] + v[3] * v[3]) - 1.0) < 0.1);
155 
156  // Make q_r > 0
157  if (v[0] < 0)
158  {
159  v[0] *= -1;
160  v[1] *= -1;
161  v[2] *= -1;
162  v[3] *= -1;
163  }
164 
165  // out_transform: Create a pose rotation with the quaternion
166  for (unsigned int i = 0; i < 4; i++) out_attitude[i] = v[i];
167 
168 #if 0
169  // Compute scale
170  double s;
171  if (forceScaleToUnity)
172  {
173  s = 1.0; // Enforce scale to be 1
174  }
175  else
176  {
177  double num = 0.0;
178  double den = 0.0;
179  for (size_t i = 0; i < nMatches; i++)
180  {
181  num += ri[i].sqrNorm();
182  den += bi[i].sqrNorm();
183  }
184  // The scale:
185  s = std::sqrt(num / den);
186  }
187 #endif
188 
189  return true;
190  MRPT_END
191 }
192 
194  const mp2p_icp::Pairings& in, const WeightParameters& wp, OptimalTF_Result& result)
195 {
196  MRPT_START
197 
198  result = OptimalTF_Result();
199 
200  // Normalize weights for each feature type and for each target (attitude
201  // / translation):
202  ASSERT_(wp.pair_weights.pt2pt >= .0);
203  ASSERT_(wp.pair_weights.ln2ln >= .0);
204  ASSERT_(wp.pair_weights.pl2pl >= .0);
205 
206  // Compute the centroids:
207  auto [ct_local, ct_global] = eval_centroids_robust(in, result.outliers /* in: empty for now */);
208 
209  mrpt::math::CQuaternionDouble optimal_q;
210 
211  // Build the linear system & solves for optimal quaternion:
212  if (!se3_l2_internal(in, wp, ct_local, ct_global, optimal_q, result.outliers /* in/out */))
213  return false;
214 
215  // Re-evaluate the centroids, now that we have a guess on outliers.
216  if (wp.use_scale_outlier_detector && !result.outliers.empty())
217  {
218  // Re-evaluate the centroids:
219  const auto [new_ct_local, new_ct_global] = eval_centroids_robust(in, result.outliers);
220 
221  ct_local = new_ct_local;
222  ct_global = new_ct_global;
223 
224  // And rebuild the linear system with the new values:
225  if (!se3_l2_internal(in, wp, ct_local, ct_global, optimal_q, result.outliers /* in/out */))
226  return false;
227  }
228 
229  // quaternion to rotation matrix:
230  result.optimalPose = mrpt::poses::CPose3D(optimal_q, 0, 0, 0);
231 
232  // Use centroids to solve for optimal translation:
233  mrpt::math::TPoint3D pp;
234  result.optimalPose.composePoint(ct_local.x, ct_local.y, ct_local.z, pp.x, pp.y, pp.z);
235  // Scale, if used, was: pp *= s;
236 
237  result.optimalPose.x(ct_global.x - pp.x);
238  result.optimalPose.y(ct_global.y - pp.y);
239  result.optimalPose.z(ct_global.z - pp.z);
240 
241  return true;
242 
243  MRPT_END
244 }
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:89
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:193
s
XmlRpcServer s
mp2p_icp::Pairings
Definition: Pairings.h:76
mp2p_icp::WeightParameters::use_scale_outlier_detector
bool use_scale_outlier_detector
Definition: WeightParameters.h:35
mp2p_icp::Coordinate::Z
@ Z
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
mp2p_icp::WeightParameters::pair_weights
PairWeights pair_weights
See docs for PairWeights.
Definition: WeightParameters.h:46
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:60
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:90
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:87
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:26
mp2p_icp::OutlierIndices
Definition: Pairings.h:172
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:86
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:88
mp2p_icp::PairWeights::pt2pt
double pt2pt
Definition: PairWeights.h:32


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:50