small_gicp
registration.hpp
Go to the documentation of this file.
1 // SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
2 // SPDX-License-Identifier: MIT
3 #pragma once
4 
13 
14 namespace small_gicp {
15 
17 template <
18  typename PointFactor,
19  typename Reduction,
20  typename GeneralFactor = NullFactor,
21  typename CorrespondenceRejector = DistanceRejector,
22  typename Optimizer = LevenbergMarquardtOptimizer>
23 struct Registration {
24 public:
31  template <typename TargetPointCloud, typename SourcePointCloud, typename TargetTree>
33  align(const TargetPointCloud& target, const SourcePointCloud& source, const TargetTree& target_tree, const Eigen::Isometry3d& init_T = Eigen::Isometry3d::Identity()) const {
34  if (traits::size(target) <= 10) {
35  std::cerr << "warning: target point cloud is too small. |target|=" << traits::size(target) << std::endl;
36  }
37  if (traits::size(source) <= 10) {
38  std::cerr << "warning: source point cloud is too small. |source|=" << traits::size(source) << std::endl;
39  }
40 
41  std::vector<PointFactor> factors(traits::size(source), PointFactor(point_factor));
42  return optimizer.optimize(target, source, target_tree, rejector, criteria, reduction, init_T, factors, general_factor);
43  }
44 
45 public:
46  using PointFactorSetting = typename PointFactor::Setting;
47 
49  CorrespondenceRejector rejector;
51  GeneralFactor general_factor;
52  Reduction reduction;
53  Optimizer optimizer;
54 };
55 
56 } // namespace small_gicp
size_t size(const T &points)
Get the number of points.
Definition: traits.hpp:16
Definition: flat_container.hpp:12
Registration result.
Definition: registration_result.hpp:11
Point cloud registration.
Definition: registration.hpp:23
GeneralFactor general_factor
General factor.
Definition: registration.hpp:51
typename PointFactor::Setting PointFactorSetting
Definition: registration.hpp:46
PointFactorSetting point_factor
Factor setting.
Definition: registration.hpp:50
RegistrationResult align(const TargetPointCloud &target, const SourcePointCloud &source, const TargetTree &target_tree, const Eigen::Isometry3d &init_T=Eigen::Isometry3d::Identity()) const
Align point clouds.
Definition: registration.hpp:33
TerminationCriteria criteria
Termination criteria.
Definition: registration.hpp:48
CorrespondenceRejector rejector
Correspondence rejector.
Definition: registration.hpp:49
Reduction reduction
Reduction.
Definition: registration.hpp:52
Optimizer optimizer
Optimizer.
Definition: registration.hpp:53
Registration termination criteria.
Definition: termination_criteria.hpp:10