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


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Tue Jul 2 2024 02:47:25