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-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
13 #include <mp2p_icp/errorTerms.h>
15 #include <mrpt/poses/Lie/SE.h>
16 
17 #include <Eigen/Dense>
18 #include <iostream>
19 
20 using namespace mp2p_icp;
21 
23  const Pairings& in, OptimalTF_Result& result,
24  const OptimalTF_GN_Parameters& gnParams)
25 {
26  using std::size_t;
27 
28  MRPT_START
29 
30  // Run Gauss-Newton steps, using SE(3) relinearization at the current
31  // solution:
32  ASSERTMSG_(
33  gnParams.linearizationPoint.has_value(),
34  "This method requires a linearization point");
35 
36  result.optimalPose = gnParams.linearizationPoint.value();
37 
38  const auto nPt2Pt = in.paired_pt2pt.size();
39  const auto nPt2Ln = in.paired_pt2ln.size();
40  const auto nPt2Pl = in.paired_pt2pl.size();
41  const auto nPl2Pl = in.paired_pl2pl.size();
42  const auto nLn2Ln = in.paired_ln2ln.size();
43 
44  const auto nErrorTerms =
45  (nPt2Pt + nPl2Pl + nPt2Ln + nPt2Pl) * 3 + nLn2Ln * 4;
46 
47  Eigen::VectorXd err(nErrorTerms);
48  Eigen::Matrix<double, Eigen::Dynamic, 6> J(nErrorTerms, 6);
49 
50  auto w = gnParams.pairWeights;
51 
52  const bool has_per_pt_weight = !in.point_weights.empty();
53  auto cur_point_block_weights = in.point_weights.begin();
54  std::size_t cur_point_block_start = 0;
55 
56  MRPT_TODO("Implement robust Kernel in this solver");
57 
58  for (size_t iter = 0; iter < gnParams.maxInnerLoopIterations; iter++)
59  {
60  // (12x6 Jacobian)
61  const auto dDexpe_de =
62  mrpt::poses::Lie::SE<3>::jacob_dDexpe_de(result.optimalPose);
63 
64  // Point-to-point:
65  for (size_t idx_pt = 0; idx_pt < nPt2Pt; idx_pt++)
66  {
67  // Error:
68  const auto& p = in.paired_pt2pt[idx_pt];
69  mrpt::math::CMatrixFixed<double, 3, 12> J1;
70  mrpt::math::CVectorFixedDouble<3> ret =
72  err.block<3, 1>(idx_pt * 3, 0) = ret.asEigen();
73 
74  // Get weight:
75  if (has_per_pt_weight)
76  {
77  if (idx_pt >=
78  cur_point_block_start + cur_point_block_weights->first)
79  {
80  ASSERT_(cur_point_block_weights != in.point_weights.end());
81  ++cur_point_block_weights; // move to next block
82  cur_point_block_start = idx_pt;
83  }
84  w.pt2pt = cur_point_block_weights->second;
85  }
86 
87  // Build Jacobian:
88  J.block<3, 6>(idx_pt * 3, 0) =
89  w.pt2pt * J1.asEigen() * dDexpe_de.asEigen();
90  }
91  auto base_idx = nPt2Pt * 3;
92 
93  // Point-to-line
94  for (size_t idx_pt = 0; idx_pt < nPt2Ln; idx_pt++)
95  {
96  // Error
97  const auto& p = in.paired_pt2ln[idx_pt];
98  mrpt::math::CMatrixFixed<double, 3, 12> J1;
99  mrpt::math::CVectorFixedDouble<3> ret =
101  err.block<3, 1>(base_idx + idx_pt * 3, 0) = ret.asEigen();
102 
103  // Get weight
104  // ...
105 
106  // Build Jacobian
107  J.block<3, 6>(base_idx + idx_pt * 3, 0) =
108  w.pt2ln * J1.asEigen() * dDexpe_de.asEigen();
109  }
110  base_idx += nPt2Ln * 3;
111 
112  // Line-to-Line
113  // Minimum angle to approach zero
114  for (size_t idx_ln = 0; idx_ln < nLn2Ln; idx_ln++)
115  {
116  const auto& p = in.paired_ln2ln[idx_ln];
117  mrpt::math::CMatrixFixed<double, 4, 12> J1;
118  mrpt::math::CVectorFixedDouble<4> ret =
119  mp2p_icp::error_line2line(p, result.optimalPose, J1);
120  err.block<4, 1>(base_idx + idx_ln * 4, 0) = ret.asEigen();
121 
122  // Build Jacobian
123  J.block<4, 6>(base_idx + idx_ln, 0) =
124  J1.asEigen() * dDexpe_de.asEigen();
125  }
126  base_idx += nLn2Ln;
127 
128  // Point-to-plane:
129  for (size_t idx_pl = 0; idx_pl < nPt2Pl; idx_pl++)
130  {
131  // Error:
132  const auto& p = in.paired_pt2pl[idx_pl];
133  mrpt::math::CMatrixFixed<double, 3, 12> J1;
134  mrpt::math::CVectorFixedDouble<3> ret =
136  err.block<3, 1>(idx_pl * 3 + base_idx, 0) = ret.asEigen();
137 
138  J.block<3, 6>(idx_pl * 3 + base_idx, 0) =
139  w.pt2pl * J1.asEigen() * dDexpe_de.asEigen();
140  }
141  base_idx += nPt2Pl * 3;
142 
143  // Plane-to-plane (only direction of normal vectors):
144  for (size_t idx_pl = 0; idx_pl < nPl2Pl; idx_pl++)
145  {
146  // Error term:
147  const auto& p = in.paired_pl2pl[idx_pl];
148  mrpt::math::CMatrixFixed<double, 3, 12> J1;
149  mrpt::math::CVectorFixedDouble<3> ret =
151  err.block<3, 1>(idx_pl * 3 + base_idx, 0) = ret.asEigen();
152 
153  J.block<3, 6>(3 * idx_pl + base_idx, 0) =
154  w.pl2pl * J1.asEigen() * dDexpe_de.asEigen();
155  }
156 
157  // Target error?
158  if (err.norm() <= gnParams.maxCost) break;
159 
160  // 3) Solve Gauss-Newton:
161  const Eigen::VectorXd g = J.transpose() * err;
162  const Eigen::Matrix<double, 6, 6> H = J.transpose() * J;
163  const Eigen::Matrix<double, 6, 1> delta =
164  -H.colPivHouseholderQr().solve(g);
165 
166  // 4) add SE(3) increment:
167  const auto dE = mrpt::poses::Lie::SE<3>::exp(
168  mrpt::math::CVectorFixed<double, 6>(delta));
169 
170  result.optimalPose = result.optimalPose + dE;
171 
172  if (gnParams.verbose)
173  {
174  std::cout << "[P2P GN] iter:" << iter << " err:" << err.norm()
175  << " delta:" << delta.transpose() << "\n";
176  }
177 
178  // Simple convergence test:
179  if (delta.norm() < gnParams.minDelta) break;
180 
181  } // for each iteration
182 
183  return true;
184 
185  MRPT_END
186 }
mp2p_icp::OptimalTF_GN_Parameters
Definition: optimal_tf_gauss_newton.h:23
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:104
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:22
mp2p_icp::OptimalTF_Result::optimalPose
mrpt::poses::CPose3D optimalPose
Definition: OptimalTF_Result.h:26
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::OptimalTF_GN_Parameters::verbose
bool verbose
Definition: optimal_tf_gauss_newton.h:25
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
mp2p_icp::OptimalTF_GN_Parameters::maxCost
double maxCost
Definition: optimal_tf_gauss_newton.h:34
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:111
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::maxInnerLoopIterations
uint32_t maxInnerLoopIterations
Definition: optimal_tf_gauss_newton.h:28
mp2p_icp::OptimalTF_GN_Parameters::pairWeights
PairWeights pairWeights
Definition: optimal_tf_gauss_newton.h:39
mp2p_icp::OptimalTF_GN_Parameters::linearizationPoint
std::optional< mrpt::poses::CPose3D > linearizationPoint
Definition: optimal_tf_gauss_newton.h:37
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:105
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:102
mp2p_icp::OptimalTF_GN_Parameters::minDelta
double minDelta
Definition: optimal_tf_gauss_newton.h:31
mp2p_icp::Pairings::paired_pt2pt
mrpt::tfest::TMatchingPairList paired_pt2pt
Definition: Pairings.h:101
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:103
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


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04