small_gicp
reduction.hpp
Go to the documentation of this file.
1 // SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
2 // SPDX-License-Identifier: MIT
3 #pragma once
4 
5 #include <vector>
6 #include <Eigen/Core>
7 
8 namespace small_gicp {
9 
20  template <typename TargetPointCloud, typename SourcePointCloud, typename TargetTree, typename CorrespondenceRejector, typename Factor>
21  std::tuple<Eigen::Matrix<double, 6, 6>, Eigen::Matrix<double, 6, 1>, double> linearize(
22  const TargetPointCloud& target,
23  const SourcePointCloud& source,
24  const TargetTree& target_tree,
25  const CorrespondenceRejector& rejector,
26  const Eigen::Isometry3d& T,
27  std::vector<Factor>& factors) const {
28  Eigen::Matrix<double, 6, 6> sum_H = Eigen::Matrix<double, 6, 6>::Zero();
29  Eigen::Matrix<double, 6, 1> sum_b = Eigen::Matrix<double, 6, 1>::Zero();
30  double sum_e = 0.0;
31 
32  for (size_t i = 0; i < factors.size(); i++) {
33  Eigen::Matrix<double, 6, 6> H;
34  Eigen::Matrix<double, 6, 1> b;
35  double e;
36 
37  if (!factors[i].linearize(target, source, target_tree, T, i, rejector, &H, &b, &e)) {
38  continue;
39  }
40 
41  sum_H += H;
42  sum_b += b;
43  sum_e += e;
44  }
45 
46  return {sum_H, sum_b, sum_e};
47  }
48 
55  template <typename TargetPointCloud, typename SourcePointCloud, typename Factor>
56  double error(const TargetPointCloud& target, const SourcePointCloud& source, const Eigen::Isometry3d& T, std::vector<Factor>& factors) const {
57  double sum_e = 0.0;
58  for (size_t i = 0; i < factors.size(); i++) {
59  sum_e += factors[i].error(target, source, T);
60  }
61  return sum_e;
62  }
63 };
64 
65 } // namespace small_gicp
Definition: flat_container.hpp:12
Single-thread reduction.
Definition: reduction.hpp:11
double error(const TargetPointCloud &target, const SourcePointCloud &source, const Eigen::Isometry3d &T, std::vector< Factor > &factors) const
Sum up evaluated errors.
Definition: reduction.hpp:56
std::tuple< Eigen::Matrix< double, 6, 6 >, Eigen::Matrix< double, 6, 1 >, double > linearize(const TargetPointCloud &target, const SourcePointCloud &source, const TargetTree &target_tree, const CorrespondenceRejector &rejector, const Eigen::Isometry3d &T, std::vector< Factor > &factors) const
Sum up linearized systems.
Definition: reduction.hpp:21