optimal_tf_gauss_newton.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  * ------------------------------------------------------------------------- */
13 #include <mp2p_icp/errorTerms.h>
16 #include <mrpt/poses/Lie/SE.h>
17 
18 #include <Eigen/Dense>
19 #include <iostream>
20 
21 #if defined(MP2P_HAS_TBB)
22 #include <tbb/blocked_range.h>
23 #include <tbb/parallel_reduce.h>
24 #endif
25 
26 using namespace mp2p_icp;
27 
29  const Pairings& in, OptimalTF_Result& result, const OptimalTF_GN_Parameters& gnParams)
30 {
31  using std::size_t;
32 
33  MRPT_START
34 
35  // Run Gauss-Newton steps, using SE(3) relinearization at the current
36  // solution:
37  ASSERTMSG_(
38  gnParams.linearizationPoint.has_value(), "This method requires a linearization point");
39 
40  result.optimalPose = gnParams.linearizationPoint.value();
41 
42  const robust_sqrt_weight_func_t robustSqrtWeightFunc =
44 
45  const auto nPt2Pt = in.paired_pt2pt.size();
46  const auto nPt2Ln = in.paired_pt2ln.size();
47  const auto nPt2Pl = in.paired_pt2pl.size();
48  const auto nPl2Pl = in.paired_pl2pl.size();
49  const auto nLn2Ln = in.paired_ln2ln.size();
50 
51  // Note: Using Matrix<N,1> instead of Vector<N> for compatibility
52  // with Eigen<=3.4 in ROS Noetic.
53  Eigen::Matrix<double, 6, 1> g = Eigen::Matrix<double, 6, 1>::Zero();
54  Eigen::Matrix<double, 6, 6> H = Eigen::Matrix<double, 6, 6>::Zero();
55 
56  auto w = gnParams.pairWeights;
57 
58  const bool has_per_pt_weight = !in.point_weights.empty();
59  auto cur_point_block_weights = in.point_weights.begin();
60  std::size_t cur_point_block_start = 0;
61 
62  for (size_t iter = 0; iter < gnParams.maxInnerLoopIterations; iter++)
63  {
64  // (12x6 Jacobian)
65  const auto dDexpe_de = mrpt::poses::Lie::SE<3>::jacob_dDexpe_de(result.optimalPose);
66 
67  double errNormSqr = 0;
68 
69 #if defined(MP2P_HAS_TBB)
70  // For the TBB lambdas:
71  // TBB call structure based on the beautiful implementation in KISS-ICP.
72  struct Result
73  {
74  Result()
75  {
76  H.setZero();
77  g.setZero();
78  }
79 
80  Result operator+(const Result& other)
81  {
82  H += other.H;
83  g += other.g;
84  return *this;
85  }
86 
87  Eigen::Matrix<double, 6, 6> H;
88  Eigen::Matrix<double, 6, 1> g;
89  };
90 
91  const auto& [H_tbb_pt2pt, g_tbb_pt2pt] = tbb::parallel_reduce(
92  // Range
93  tbb::blocked_range<size_t>{0, nPt2Pt},
94  // Identity
95  Result(),
96  // 1st lambda: Parallel computation
97  [&](const tbb::blocked_range<size_t>& r, Result res) -> Result
98  {
99  auto& [H_local, g_local] = res;
100  for (size_t idx_pt = r.begin(); idx_pt < r.end(); idx_pt++)
101  {
102  // Error:
103  const auto& p = in.paired_pt2pt[idx_pt];
104  mrpt::math::CMatrixFixed<double, 3, 12> J1;
105  mrpt::math::CVectorFixedDouble<3> ret =
107 
108  // Get point weight:
109  if (has_per_pt_weight)
110  {
111  if (idx_pt >= cur_point_block_start + cur_point_block_weights->first)
112  {
113  ASSERT_(cur_point_block_weights != in.point_weights.end());
114  ++cur_point_block_weights; // move to next block
115  cur_point_block_start = idx_pt;
116  }
117  w.pt2pt = cur_point_block_weights->second;
118  }
119 
120  // Apply robust kernel?
121  double weight = w.pt2pt, retSqrNorm = ret.asEigen().squaredNorm();
122  if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
123 
124  // Error and Jacobian:
125  const Eigen::Vector3d err_i = ret.asEigen();
126  errNormSqr += weight * retSqrNorm;
127 
128  const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
129  g_local.noalias() += weight * Ji.transpose() * err_i;
130  H_local.noalias() += weight * Ji.transpose() * Ji;
131  }
132  return res;
133  },
134  // 2nd lambda: Parallel reduction
135  [](Result a, const Result& b) -> Result { return a + b; });
136 
137  H = std::move(H_tbb_pt2pt);
138  g = std::move(g_tbb_pt2pt);
139 #else
140  // Point-to-point:
141  for (size_t idx_pt = 0; idx_pt < nPt2Pt; idx_pt++)
142  {
143  // Error:
144  const auto& p = in.paired_pt2pt[idx_pt];
145  mrpt::math::CMatrixFixed<double, 3, 12> J1;
146  mrpt::math::CVectorFixedDouble<3> ret =
148 
149  // Get point weight:
150  if (has_per_pt_weight)
151  {
152  if (idx_pt >= cur_point_block_start + cur_point_block_weights->first)
153  {
154  ASSERT_(cur_point_block_weights != in.point_weights.end());
155  ++cur_point_block_weights; // move to next block
156  cur_point_block_start = idx_pt;
157  }
158  w.pt2pt = cur_point_block_weights->second;
159  }
160 
161  // Apply robust kernel?
162  double weight = w.pt2pt, retSqrNorm = ret.asEigen().squaredNorm();
163  if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
164 
165  // Error and Jacobian:
166  const Eigen::Vector3d err_i = ret.asEigen();
167  errNormSqr += weight * retSqrNorm;
168 
169  const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
170  g.noalias() += weight * Ji.transpose() * err_i;
171  H.noalias() += weight * Ji.transpose() * Ji;
172  }
173 #endif
174 
175  // Point-to-line
176  for (size_t idx_pt = 0; idx_pt < nPt2Ln; idx_pt++)
177  {
178  // Error
179  const auto& p = in.paired_pt2ln[idx_pt];
180  mrpt::math::CMatrixFixed<double, 3, 12> J1;
181  mrpt::math::CVectorFixedDouble<3> ret =
183 
184  // Apply robust kernel?
185  double weight = w.pt2ln, retSqrNorm = ret.asEigen().squaredNorm();
186  if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
187 
188  // Error and Jacobian:
189  const Eigen::Vector3d err_i = ret.asEigen();
190  errNormSqr += weight * weight * retSqrNorm;
191 
192  const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
193  g.noalias() += weight * Ji.transpose() * err_i;
194  H.noalias() += weight * Ji.transpose() * Ji;
195  }
196 
197  // Line-to-Line
198  // Minimum angle to approach zero
199  for (size_t idx_ln = 0; idx_ln < nLn2Ln; idx_ln++)
200  {
201  const auto& p = in.paired_ln2ln[idx_ln];
202  mrpt::math::CMatrixFixed<double, 4, 12> J1;
203  mrpt::math::CVectorFixedDouble<4> ret =
204  mp2p_icp::error_line2line(p, result.optimalPose, J1);
205 
206  // Apply robust kernel?
207  double weight = w.ln2ln, retSqrNorm = ret.asEigen().squaredNorm();
208  if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
209 
210  // Error and Jacobian:
211  const Eigen::Vector4d err_i = ret.asEigen();
212  errNormSqr += weight * weight * retSqrNorm;
213 
214  const Eigen::Matrix<double, 4, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
215  g.noalias() += weight * Ji.transpose() * err_i;
216  H.noalias() += weight * Ji.transpose() * Ji;
217  }
218 
219 #if defined(MP2P_HAS_TBB)
220  // Point-to-plane:
221  const auto& [H_tbb_pt2pl, g_tbb_pt2pl] = tbb::parallel_reduce(
222  // Range
223  tbb::blocked_range<size_t>{0, nPt2Pl},
224  // Identity
225  Result(),
226  // 1st lambda: Parallel computation
227  [&](const tbb::blocked_range<size_t>& r, Result res) -> Result
228  {
229  auto& [H_local, g_local] = res;
230  for (size_t idx_pl = r.begin(); idx_pl < r.end(); idx_pl++)
231  {
232  // Error:
233  const auto& p = in.paired_pt2pl[idx_pl];
234  mrpt::math::CMatrixFixed<double, 3, 12> J1;
235  mrpt::math::CVectorFixedDouble<3> ret =
237 
238  // Apply robust kernel?
239  double weight = w.pt2pl, retSqrNorm = ret.asEigen().squaredNorm();
240  if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
241 
242  // Error and Jacobian:
243  const Eigen::Vector3d err_i = ret.asEigen();
244  errNormSqr += weight * retSqrNorm;
245 
246  const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
247  g_local.noalias() += weight * Ji.transpose() * err_i;
248  H_local.noalias() += weight * Ji.transpose() * Ji;
249  }
250  return res;
251  },
252  // 2nd lambda: Parallel reduction
253  [](Result a, const Result& b) -> Result { return a + b; });
254 
255  H += H_tbb_pt2pl;
256  g += g_tbb_pt2pl;
257 #else
258  // Point-to-plane:
259  for (size_t idx_pl = 0; idx_pl < nPt2Pl; idx_pl++)
260  {
261  // Error:
262  const auto& p = in.paired_pt2pl[idx_pl];
263  mrpt::math::CMatrixFixed<double, 3, 12> J1;
264  mrpt::math::CVectorFixedDouble<3> ret =
266 
267  // Apply robust kernel?
268  double weight = w.pt2pl, retSqrNorm = ret.asEigen().squaredNorm();
269  if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
270 
271  // Error and Jacobian:
272  const Eigen::Vector3d err_i = ret.asEigen();
273  errNormSqr += weight * weight * retSqrNorm;
274 
275  const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
276  g.noalias() += weight * Ji.transpose() * err_i;
277  H.noalias() += weight * Ji.transpose() * Ji;
278  }
279 #endif
280 
281  // Plane-to-plane (only direction of normal vectors):
282  for (size_t idx_pl = 0; idx_pl < nPl2Pl; idx_pl++)
283  {
284  // Error term:
285  const auto& p = in.paired_pl2pl[idx_pl];
286  mrpt::math::CMatrixFixed<double, 3, 12> J1;
287  mrpt::math::CVectorFixedDouble<3> ret =
289 
290  // Apply robust kernel?
291  double weight = w.pl2pl, retSqrNorm = ret.asEigen().squaredNorm();
292  if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
293 
294  const Eigen::Vector3d err_i = ret.asEigen();
295  errNormSqr += weight * weight * retSqrNorm;
296 
297  const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
298  g.noalias() += weight * Ji.transpose() * err_i;
299  H.noalias() += weight * Ji.transpose() * Ji;
300  }
301 
302  // Prior guess term:
303  if (gnParams.prior.has_value())
304  {
305  const auto& priorMean = gnParams.prior->mean;
306  const auto& priorInf = gnParams.prior->cov_inv;
307 
308  // Compute the residual pose error of these pair of nodes + its
309  // constraint:
310  // SE(3) error = inv(P_prior) * P_current
311  // = (P_current \ominus P_prior)
312 
313  const mrpt::poses::CPose3D P1invP2 = result.optimalPose - priorMean;
314  const auto err_i = mrpt::poses::Lie::SE<3>::log(P1invP2);
315 
316  mrpt::math::CMatrixDouble66 df_de2;
317 
318  mrpt::poses::Lie::SE<3>::jacob_dDinvP1invP2_de1e2(
319  // edge between the two poses:in this case, both should coincide
320  mrpt::poses::CPose3D::Identity(),
321  // P1:
322  priorMean,
323  // P2:
324  result.optimalPose,
325  // df_de1
326  std::nullopt,
327  // df_de2
328  df_de2);
329 
330  g.noalias() += (df_de2.transpose() * priorInf.asEigen()) * err_i.asEigen();
331 
332  H.noalias() += (df_de2.transpose() * priorInf.asEigen()) * df_de2.asEigen();
333  }
334 
335  // Target error?
336  const double errNorm = std::sqrt(errNormSqr);
337 
338  if (errNorm <= gnParams.maxCost) break;
339 
340  // 3) Solve Gauss-Newton:
341  // g = J.transpose() * err;
342  // H = J.transpose() * J;
343  const Eigen::Matrix<double, 6, 1> delta = -H.ldlt().solve(g);
344 
345  // 4) add SE(3) increment:
346  const auto dE = mrpt::poses::Lie::SE<3>::exp(mrpt::math::CVectorFixed<double, 6>(delta));
347 
348  result.optimalPose = result.optimalPose + dE;
349 
350  if (gnParams.verbose)
351  {
352  std::cout << "[P2P GN] iter:" << iter << " err:" << errNorm
353  << " delta:" << delta.transpose() << "\n";
354  }
355 
356  // Simple convergence test:
357  if (delta.norm() < gnParams.minDelta) break;
358 
359  } // for each iteration
360 
361  return true;
362 
363  MRPT_END
364 }
mp2p_icp::OptimalTF_GN_Parameters
Definition: optimal_tf_gauss_newton.h:24
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:89
mp2p_icp::optimal_tf_gauss_newton
bool optimal_tf_gauss_newton(const Pairings &in, OptimalTF_Result &result, const OptimalTF_GN_Parameters &gnParams=OptimalTF_GN_Parameters())
Definition: optimal_tf_gauss_newton.cpp:28
mp2p_icp::OptimalTF_Result::optimalPose
mrpt::poses::CPose3D optimalPose
Definition: OptimalTF_Result.h:26
mp2p_icp::OptimalTF_GN_Parameters::kernelParam
double kernelParam
Definition: optimal_tf_gauss_newton.h:50
mp2p_icp
Definition: covariance.h:17
test.res
res
Definition: test.py:11
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:76
mp2p_icp::OptimalTF_GN_Parameters::verbose
bool verbose
Definition: optimal_tf_gauss_newton.h:52
mp2p_icp::OptimalTF_GN_Parameters::kernel
RobustKernel kernel
Definition: optimal_tf_gauss_newton.h:49
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
mp2p_icp::OptimalTF_GN_Parameters::maxCost
double maxCost
Definition: optimal_tf_gauss_newton.h:42
optimal_tf_gauss_newton.h
Simple non-linear optimizer to find the SE(3) optimal transformation.
mp2p_icp::Pairings::point_weights
std::vector< std::pair< std::size_t, double > > point_weights
Definition: Pairings.h:102
errorTerms.h
mp2p_icp::error_plane2plane
mrpt::math::CVectorFixedDouble< 3 > error_plane2plane(const mp2p_icp::matched_plane_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:320
mp2p_icp::error_point2plane
mrpt::math::CVectorFixedDouble< 3 > error_point2plane(const mp2p_icp::point_plane_pair_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:107
mp2p_icp::OptimalTF_GN_Parameters::prior
std::optional< mrpt::poses::CPose3DPDFGaussianInf > prior
Definition: optimal_tf_gauss_newton.h:36
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::OptimalTF_GN_Parameters::maxInnerLoopIterations
uint32_t maxInnerLoopIterations
Definition: optimal_tf_gauss_newton.h:47
mp2p_icp::OptimalTF_GN_Parameters::pairWeights
PairWeights pairWeights
Definition: optimal_tf_gauss_newton.h:44
mp2p_icp::OptimalTF_GN_Parameters::linearizationPoint
std::optional< mrpt::poses::CPose3D > linearizationPoint
Definition: optimal_tf_gauss_newton.h:29
mp2p_icp::error_point2point
mrpt::math::CVectorFixedDouble< 3 > error_point2point(const mrpt::tfest::TMatchingPair &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:28
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:90
robust_kernels.h
Robust kernel types and functions, for common use in all solvers.
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:87
operator+
TF2SIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
mp2p_icp::OptimalTF_GN_Parameters::minDelta
double minDelta
Definition: optimal_tf_gauss_newton.h:39
mp2p_icp::Pairings::paired_pt2pt
mrpt::tfest::TMatchingPairList paired_pt2pt
Definition: Pairings.h:86
mp2p_icp::error_point2line
mrpt::math::CVectorFixedDouble< 3 > error_point2line(const mp2p_icp::point_line_pair_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:60
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:88
mp2p_icp::error_line2line
mrpt::math::CVectorFixedDouble< 4 > error_line2line(const mp2p_icp::matched_line_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 4, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:155


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