covariance.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/covariance.h>
14 #include <mp2p_icp/errorTerms.h>
15 #include <mrpt/math/CVectorDynamic.h>
16 #include <mrpt/math/num_jacobian.h>
17 
18 #include <Eigen/Dense>
19 
20 using namespace mp2p_icp;
21 
22 mrpt::math::CMatrixDouble66 mp2p_icp::covariance(
23  const Pairings& in, const mrpt::poses::CPose3D& finalAlignSolution,
24  const CovarianceParameters& param)
25 {
26  // If we don't have pairings, we can't provide an estimation:
27  if (in.empty())
28  {
29  mrpt::math::CMatrixDouble66 cov;
30  cov.setDiagonal(1e6);
31  return cov;
32  }
33 
34  mrpt::math::CMatrixDouble61 xInitial;
35  xInitial[0] = finalAlignSolution.x();
36  xInitial[1] = finalAlignSolution.y();
37  xInitial[0] = finalAlignSolution.x();
38  xInitial[3] = finalAlignSolution.yaw();
39  xInitial[4] = finalAlignSolution.pitch();
40  xInitial[5] = finalAlignSolution.roll();
41 
42  mrpt::math::CMatrixDouble61 xIncrs;
43  for (int i = 0; i < 3; i++) xIncrs[i] = param.finDif_xyz;
44  for (int i = 0; i < 3; i++) xIncrs[3 + i] = param.finDif_angles;
45 
46  struct LambdaParams
47  {
48  };
49 
50  LambdaParams lmbParams;
51 
52  auto errorLambda = [&](const mrpt::math::CMatrixDouble61& x,
53  const LambdaParams&,
54  mrpt::math::CVectorDouble& err) {
55  mrpt::poses::CPose3D pose;
56  pose.setFromValues(x[0], x[1], x[2], x[3], x[4], x[5]);
57 
58  const auto nPt2Pt = in.paired_pt2pt.size();
59  const auto nPt2Ln = in.paired_pt2ln.size();
60  const auto nPt2Pl = in.paired_pt2pl.size();
61  const auto nPl2Pl = in.paired_pl2pl.size();
62  const auto nLn2Ln = in.paired_ln2ln.size();
63 
64  const auto nErrorTerms =
65  (nPt2Pt + nPl2Pl + nPt2Ln + nPt2Pl) * 3 + nLn2Ln * 4;
66  ASSERT_(nErrorTerms > 0);
67  err.resize(nErrorTerms);
68 
69  // Point-to-point:
70  for (size_t idx_pt = 0; idx_pt < nPt2Pt; idx_pt++)
71  {
72  // Error:
73  const auto& p = in.paired_pt2pt[idx_pt];
74  mrpt::math::CVectorFixedDouble<3> ret =
76  err.block<3, 1>(idx_pt * 3, 0) = ret.asEigen();
77  }
78  auto base_idx = nPt2Pt * 3;
79 
80  // Point-to-line
81  for (size_t idx_pt = 0; idx_pt < nPt2Ln; idx_pt++)
82  {
83  // Error
84  const auto& p = in.paired_pt2ln[idx_pt];
85  mrpt::math::CVectorFixedDouble<3> ret =
87  err.block<3, 1>(base_idx + idx_pt * 3, 0) = ret.asEigen();
88  }
89  base_idx += nPt2Ln * 3;
90 
91  // Line-to-Line
92  // Minimum angle to approach zero
93  for (size_t idx_ln = 0; idx_ln < nLn2Ln; idx_ln++)
94  {
95  const auto& p = in.paired_ln2ln[idx_ln];
96  mrpt::math::CVectorFixedDouble<4> ret =
98  err.block<4, 1>(base_idx + idx_ln * 4, 0) = ret.asEigen();
99  }
100  base_idx += nLn2Ln;
101 
102  // Point-to-plane:
103  for (size_t idx_pl = 0; idx_pl < nPt2Pl; idx_pl++)
104  {
105  // Error:
106  const auto& p = in.paired_pt2pl[idx_pl];
107  mrpt::math::CVectorFixedDouble<3> ret =
109  err.block<3, 1>(idx_pl * 3 + base_idx, 0) = ret.asEigen();
110  }
111  base_idx += nPt2Pl * 3;
112 
113  // Plane-to-plane (only direction of normal vectors):
114  for (size_t idx_pl = 0; idx_pl < nPl2Pl; idx_pl++)
115  {
116  // Error term:
117  const auto& p = in.paired_pl2pl[idx_pl];
118  mrpt::math::CVectorFixedDouble<3> ret =
120  err.block<3, 1>(idx_pl * 3 + base_idx, 0) = ret.asEigen();
121  }
122  };
123 
124  // Do NOT use "Eigen::MatrixXd", it may have different alignment
125  // requirements than MRPT matrices:
126  mrpt::math::CMatrixDouble jacob;
127  mrpt::math::estimateJacobian(
128  xInitial,
129  std::function<void(
130  const mrpt::math::CMatrixDouble61&, const LambdaParams&,
131  mrpt::math::CVectorDouble&)>(errorLambda),
132  xIncrs, lmbParams, jacob);
133 
134  const mrpt::math::CMatrixDouble66 hessian(
135  jacob.asEigen().transpose() * jacob.asEigen());
136 
137  const mrpt::math::CMatrixDouble66 cov = hessian.inverse_LLt();
138 
139  return cov;
140 }
141 
142 // other ideas?
143 // See: http://censi.mit.edu/pub/research/2007-icra-icpcov-slides.pdf
mp2p_icp
Definition: covariance.h:17
mp2p_icp::CovarianceParameters
Definition: covariance.h:19
mp2p_icp::Pairings
Definition: Pairings.h:78
mp2p_icp::Pairings::empty
virtual bool empty() const
Definition: Pairings.h:111
test.x
x
Definition: test.py:4
errorTerms.h
mp2p_icp::covariance
mrpt::math::CMatrixDouble66 covariance(const Pairings &finalPairings, const mrpt::poses::CPose3D &finalAlignSolution, const CovarianceParameters &p)
Definition: covariance.cpp:22
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
covariance.h
Covariance estimation methods for ICP results.
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
param
T param(const std::string &param_name, const T &default_val)
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::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):
autogenerated on Thu Dec 26 2024 03:48:10