optimal_tf_olae.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/core/exceptions.h>
15 #include <mrpt/poses/Lie/SE.h>
16 #include <mrpt/tfest/se3.h>
17 
18 #include <Eigen/Dense>
19 
20 #include "visit_correspondences.h"
21 
22 using namespace mp2p_icp;
23 
24 // Convert to quaternion by normalizing q=[1, optim_rot], then to rot. matrix:
25 static mrpt::poses::CPose3D gibbs2pose(const Eigen::Vector3d& v)
26 {
27  auto x = v[0], y = v[1], z = v[2];
28  const auto r = 1.0 / std::sqrt(1.0 + x * x + y * y + z * z);
29  x *= r;
30  y *= r;
31  z *= r;
32  auto q = mrpt::math::CQuaternionDouble(r, -x, -y, -z);
33 
34  // Quaternion to 3x3 rot matrix:
35  return mrpt::poses::CPose3D(q, .0, .0, .0);
36 }
37 
48 {
49  Eigen::Matrix3d M, Mx, My, Mz;
50  Eigen::Vector3d v, vx, vy, vz;
51 
53  Eigen::Matrix3d B;
54 };
55 
58  const Pairings& in, const WeightParameters& wp,
59  const mrpt::math::TPoint3D& ct_local, const mrpt::math::TPoint3D& ct_global,
60  OutlierIndices& in_out_outliers)
61 {
62  MRPT_START
63 
64  using mrpt::math::TPoint3D;
65  using mrpt::math::TVector3D;
66 
68 
69  // Build the linear system: M g = v
70  res.M = Eigen::Matrix3d::Zero();
71  res.v = Eigen::Vector3d::Zero();
72 
73  // Attitude profile matrix:
74  res.B = Eigen::Matrix3d::Zero();
75 
76  // Lambda: process each pairing:
77  auto lambda_each_pair = [&](const mrpt::math::TVector3D& bi,
78  const mrpt::math::TVector3D& ri,
79  const double wi)
80  {
81 // We will evaluate M from an alternative expression below from the
82 // attitude profile matrix B instead, since it seems to be slightly more
83 // stable, numerically. The original code for M is left here for
84 // reference, though.
85 #if 0
86  // M+=(1/2)* ([s_i]_{x})^2
87  // with: s_i = b_i + r_i
88  const double sx = bi.x + ri.x, sy = bi.y + ri.y, sz = bi.z + ri.z;
89 
90  /* ([s_i]_{x})^2 is:
91  *
92  * ⎡ 2 2 ⎤
93  * ⎢- sy - sz sx⋅sy sx⋅sz ⎥
94  * ⎢ ⎥
95  * ⎢ 2 2 ⎥
96  * ⎢ sx⋅sy - sx - sz sy⋅sz ⎥
97  * ⎢ ⎥
98  * ⎢ 2 2⎥
99  * ⎣ sx⋅sz sy⋅sz - sx - sy ⎦
100  */
101  const double c00 = -sy * sy - sz * sz;
102  const double c11 = -sx * sx - sz * sz;
103  const double c22 = -sx * sx - sy * sy;
104  const double c01 = sx * sy;
105  const double c02 = sx * sz;
106  const double c12 = sy * sz;
107 
108  // clang-format off
109  const auto dM = (Eigen::Matrix3d() <<
110  c00, c01, c02,
111  c01, c11, c12,
112  c02, c12, c22 ).finished();
113  // clang-format on
114 
115  // res.M += wi * dM;
116 
117  // The missing (1/2) from the formulas above:
118  res.M *= 0.5;
119 #endif
120  /* v-= weight * [b_i]_{x} r_i
121  * Each term is:
122  * ⎡by⋅rz - bz⋅ry ⎤ ⎡ B23 - B32 ⎤
123  * ⎢ ⎥ | ⎥
124  * ⎢-bx⋅rz + bz⋅rx⎥ = | B31 - B13 ⎥
125  * ⎢ ⎥ | ⎥
126  * ⎣bx⋅ry - by⋅rx ⎦ ⎣ B12 - B21 ⎦
127  *
128  * B (attitude profile matrix):
129  *
130  * B+= weight * (b_i * r_i')
131  *
132  */
133 
134  // clang-format off
135  const auto dV = (Eigen::Vector3d() <<
136  (bi.y * ri.z - bi.z * ri.y),
137  (-bi.x * ri.z + bi.z * ri.x),
138  (bi.x * ri.y - bi.y * ri.x) ).finished();
139  // clang-format on
140 
141  res.v -= wi * dV;
142 
143  // clang-format off
144  const auto dB = (Eigen::Matrix3d() <<
145  bi.x * ri.x, bi.x * ri.y, bi.x * ri.z,
146  bi.y * ri.x, bi.y * ri.y, bi.y * ri.z,
147  bi.z * ri.x, bi.z * ri.y, bi.z * ri.z).finished();
148  // clang-format on
149  res.B += wi * dB;
150  }; // end lambda for visit_correspondences()
151 
152  // Lambda for the final stage after visiting all corres:
153  auto lambda_final = [&](const double w_sum)
154  {
155  // Normalize weights. OLAE assumes \sum(w_i) = 1.0
156  if (w_sum > .0)
157  {
158  const auto f = (1.0 / w_sum);
159  // res.M *= f;
160  res.v *= f;
161  res.B *= f;
162  }
163  else
164  {
165  // We either had NO input correspondences, or ALL were detected
166  // as outliers... What to do in this case?
167  }
168  };
169 
171  in, wp, ct_local, ct_global, in_out_outliers, lambda_each_pair,
172  lambda_final, true /* DO make unit point vectors for OLAE */);
173 
174  // Now, compute the other three sets of linear systems, corresponding
175  // to the "sequential rotation method" [shuster1981attitude], so we can
176  // later keep the best one (i.e. the one with the largest |M|).
177  {
178  const Eigen::Matrix3d S = res.B + res.B.transpose();
179  const double p = res.B.trace() + 1;
180  const double m = res.B.trace() - 1;
181  // Short cut:
182  const auto& v = res.v;
183 
184  // Set #0: M g=v, without further rotations (the system built above).
185  // clang-format off
186  res.M = (Eigen::Matrix3d() <<
187  S(0,0)-p, S(0,1), S(0,2),
188  S(0,1), S(1,1)-p, S(1,2),
189  S(0,2), S(1,2), S(2,2)-p ).finished();
190  // clang-format on
191 
192  const auto& M0 = res.M; // shortcut
193  const double z1 = v[0], z2 = v[1], z3 = v[2];
194 
195  // Set #1: rotating 180 deg around "x":
196  // clang-format off
197  res.Mx = (Eigen::Matrix3d() <<
198  m , -z3 , z2,
199  -z3 , M0(2,2), -S(1,2),
200  z2 , -S(1,2), M0(1,1)).finished();
201  res.vx = (Eigen::Vector3d() <<
202  -z1, S(0,2), -S(0,1)
203  ).finished();
204  // clang-format on
205 
206  // Set #2: rotating 180 deg around "y":
207  // clang-format off
208  res.My = (Eigen::Matrix3d() <<
209  M0(2,2), z3 , -S(0,2),
210  z3 , m , -z1,
211  -S(0,2) , -z1 , M0(0,0)).finished();
212  res.vy = (Eigen::Vector3d() <<
213  -S(1,2), -z2, S(0,1)
214  ).finished();
215  // clang-format on
216 
217  // Set #3: rotating 180 deg around "z":
218  // clang-format off
219  res.Mz = (Eigen::Matrix3d() <<
220  M0(1,1), -S(0,1), -z2,
221  -S(0,1) , M0(0,0), z1,
222  -z2 , z1 , m).finished();
223  res.vz = (Eigen::Vector3d() <<
224  S(1,2), -S(0,2), -z3
225  ).finished();
226  // clang-format on
227  }
228 
229  return res;
230 
231  MRPT_END
232 }
233 
234 // See .h docs, and associated technical report.
236  const Pairings& in, const WeightParameters& wp, OptimalTF_Result& result)
237 {
238  MRPT_START
239 
240  using mrpt::math::TPoint3D;
241  using mrpt::math::TVector3D;
242 
243  // Note on notation: we are search the relative transformation of
244  // the "other" frame wrt to "this", i.e. "this"="global",
245  // "other"="local":
246  // p_this = pose \oplus p_other
247  // p_A = pose \oplus p_B --> pB = p_A \ominus pose
248 
249  // Reset output to defaults:
250  result = OptimalTF_Result();
251 
252  // Normalize weights for each feature type and for each target (attitude
253  // / translation):
254  ASSERT_(wp.pair_weights.pt2pt >= .0);
255  ASSERT_(wp.pair_weights.ln2ln >= .0);
256  ASSERT_(wp.pair_weights.pl2pl >= .0);
257 
258  // Compute the centroids:
259  auto [ct_local, ct_global] =
260  eval_centroids_robust(in, result.outliers /* empty for now */);
261 
262  // Build the linear system: M g = v
264  in, wp, ct_local, ct_global, result.outliers /* empty for now */);
265 
266  // Re-evaluate the centroids, now that we have a guess on outliers.
267  if (!result.outliers.empty())
268  {
269  // Re-evaluate the centroids:
270  const auto [new_ct_local, new_ct_global] =
271  eval_centroids_robust(in, result.outliers);
272 
273  ct_local = new_ct_local;
274  ct_global = new_ct_global;
275 
276  // And rebuild the linear system with the new values:
277  linsys = olae_build_linear_system(
278  in, wp, ct_local, ct_global, result.outliers);
279  }
280 
281  // We are finding the optimal rotation "g", as a Gibbs vector.
282  // Solve linear system for optimal rotation: M g = v
283 
284  const double detM_orig = std::abs(linsys.M.determinant()),
285  detMx = std::abs(linsys.Mx.determinant()),
286  detMy = std::abs(linsys.My.determinant()),
287  detMz = std::abs(linsys.Mz.determinant());
288 
289 #if 0
290  // clang-format off
291  std::cout << " |M_orig|= " << detM_orig << "\n"
292  " |M_x| = " << detMx << "\n"
293  " |M_t| = " << detMy << "\n"
294  " |M_z| = " << detMz << "\n";
295  // clang-format on
296 #endif
297 
298  if (detM_orig > mrpt::max3(detMx, detMy, detMz))
299  {
300  // original rotation is the best numerically-determined problem:
301  const auto sol0 =
302  gibbs2pose(linsys.M.colPivHouseholderQr().solve(linsys.v));
303  result.optimalPose = sol0;
304 #if 0
305  std::cout << "M : |M|="
306  << mrpt::format("%16.07f", linsys.M.determinant())
307  << " sol: " << sol0.asString() << "\n";
308 #endif
309  }
310  else if (detMx > mrpt::max3(detM_orig, detMy, detMz))
311  {
312  // rotation wrt X is the best choice:
313  auto sol1 =
314  gibbs2pose(linsys.Mx.colPivHouseholderQr().solve(linsys.vx));
315  sol1 = mrpt::poses::CPose3D(0, 0, 0, 0, 0, M_PI) + sol1;
316  result.optimalPose = sol1;
317 #if 0
318  std::cout << "M_x : |M|="
319  << mrpt::format("%16.07f", linsys.Mx.determinant())
320  << " sol: " << sol1.asString() << "\n";
321 #endif
322  }
323  else if (detMy > mrpt::max3(detM_orig, detMx, detMz))
324  {
325  // rotation wrt Y is the best choice:
326  auto sol2 =
327  gibbs2pose(linsys.My.colPivHouseholderQr().solve(linsys.vy));
328  sol2 = mrpt::poses::CPose3D(0, 0, 0, 0, M_PI, 0) + sol2;
329  result.optimalPose = sol2;
330 #if 0
331  std::cout << "M_y : |M|="
332  << mrpt::format("%16.07f", linsys.My.determinant())
333  << " sol: " << sol2.asString() << "\n";
334 #endif
335  }
336  else
337  {
338  // rotation wrt Z is the best choice:
339  auto sol3 =
340  gibbs2pose(linsys.Mz.colPivHouseholderQr().solve(linsys.vz));
341  sol3 = mrpt::poses::CPose3D(0, 0, 0, M_PI, 0, 0) + sol3;
342  result.optimalPose = sol3;
343 #if 0
344  std::cout << "M_z : |M|="
345  << mrpt::format("%16.07f", linsys.Mz.determinant())
346  << " sol: " << sol3.asString() << "\n";
347 #endif
348  }
349 
350  // Use centroids to solve for optimal translation:
351  mrpt::math::TPoint3D pp;
352  result.optimalPose.composePoint(
353  ct_local.x, ct_local.y, ct_local.z, pp.x, pp.y, pp.z);
354  // Scale, if used, was: pp *= s;
355 
356  result.optimalPose.x(ct_global.x - pp.x);
357  result.optimalPose.y(ct_global.y - pp.y);
358  result.optimalPose.z(ct_global.z - pp.z);
359 
360  return true;
361 
362  MRPT_END
363 }
OLAE_LinearSystems
Definition: optimal_tf_olae.cpp:47
mp2p_icp::OptimalTF_Result::optimalPose
mrpt::poses::CPose3D optimalPose
Definition: OptimalTF_Result.h:26
mp2p_icp
Definition: covariance.h:17
OLAE_LinearSystems::My
Eigen::Matrix3d My
Definition: optimal_tf_olae.cpp:49
test.res
res
Definition: test.py:11
OLAE_LinearSystems::vz
Eigen::Vector3d vz
Definition: optimal_tf_olae.cpp:50
OLAE_LinearSystems::Mx
Eigen::Matrix3d Mx
Definition: optimal_tf_olae.cpp:49
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp::Pairings
Definition: Pairings.h:78
OLAE_LinearSystems::vx
Eigen::Vector3d vx
Definition: optimal_tf_olae.cpp:50
optimal_tf_olae.h
OLAE algorithm to find the SE(3) optimal transformation.
OLAE_LinearSystems::vy
Eigen::Vector3d vy
Definition: optimal_tf_olae.cpp:50
test.x
x
Definition: test.py:4
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
OLAE_LinearSystems::v
Eigen::Vector3d v
Definition: optimal_tf_olae.cpp:50
mp2p_icp::OutlierIndices::empty
bool empty() const
Definition: Pairings.h:186
mp2p_icp::OptimalTF_Result::outliers
OutlierIndices outliers
Definition: OptimalTF_Result.h:30
OLAE_LinearSystems::B
Eigen::Matrix3d B
Definition: optimal_tf_olae.cpp:53
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::optimal_tf_olae
bool optimal_tf_olae(const Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
Definition: optimal_tf_olae.cpp:235
OLAE_LinearSystems::Mz
Eigen::Matrix3d Mz
Definition: optimal_tf_olae.cpp:49
gibbs2pose
static mrpt::poses::CPose3D gibbs2pose(const Eigen::Vector3d &v)
Definition: optimal_tf_olae.cpp:25
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:63
olae_build_linear_system
static OLAE_LinearSystems olae_build_linear_system(const Pairings &in, const WeightParameters &wp, const mrpt::math::TPoint3D &ct_local, const mrpt::math::TPoint3D &ct_global, OutlierIndices &in_out_outliers)
Definition: optimal_tf_olae.cpp:57
OLAE_LinearSystems::M
Eigen::Matrix3d M
Definition: optimal_tf_olae.cpp:49
visit_correspondences.h
Template that applies lambdas to unified vector forms of pairings.
mp2p_icp::WeightParameters
Definition: WeightParameters.h:26
mp2p_icp::OutlierIndices
Definition: Pairings.h:180
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
test.q
q
Definition: test.py:8
mp2p_icp::PairWeights::pt2pt
double pt2pt
Definition: PairWeights.h:32


mp2p_icp
Author(s):
autogenerated on Sun Feb 2 2025 03:45:53