small_gicp
registration_helper.hpp
Go to the documentation of this file.
1 // SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
2 // SPDX-License-Identifier: MIT
3 #pragma once
4 
9 
10 namespace small_gicp {
11 
19 std::pair<PointCloud::Ptr, std::shared_ptr<KdTree<PointCloud>>>
20 preprocess_points(const PointCloud& points, double downsampling_resolution, int num_neighbors = 10, int num_threads = 4);
21 
26 template <typename T, int D>
27 std::pair<PointCloud::Ptr, std::shared_ptr<KdTree<PointCloud>>>
28 preprocess_points(const std::vector<Eigen::Matrix<T, D, 1>>& points, double downsampling_resolution, int num_neighbors = 10, int num_threads = 4);
29 
34 GaussianVoxelMap::Ptr create_gaussian_voxelmap(const PointCloud& points, double voxel_resolution);
35 
39 
41  double voxel_resolution = 1.0;
42  double downsampling_resolution = 0.25;
44  double rotation_eps = 0.1 * M_PI / 180.0;
45  double translation_eps = 1e-3;
46  int num_threads = 4;
47  int max_iterations = 20;
48  bool verbose = false;
49 };
50 
59 template <typename T, int D>
61  const std::vector<Eigen::Matrix<T, D, 1>>& target,
62  const std::vector<Eigen::Matrix<T, D, 1>>& source,
63  const Eigen::Isometry3d& init_T = Eigen::Isometry3d::Identity(),
64  const RegistrationSetting& setting = RegistrationSetting());
65 
74  const PointCloud& target,
75  const PointCloud& source,
76  const KdTree<PointCloud>& target_tree,
77  const Eigen::Isometry3d& init_T = Eigen::Isometry3d::Identity(),
78  const RegistrationSetting& setting = RegistrationSetting());
79 
87  const GaussianVoxelMap& target,
88  const PointCloud& source,
89  const Eigen::Isometry3d& init_T = Eigen::Isometry3d::Identity(),
90  const RegistrationSetting& setting = RegistrationSetting());
91 
92 } // namespace small_gicp
Definition: flat_container.hpp:12
std::pair< PointCloud::Ptr, std::shared_ptr< KdTree< PointCloud > > > preprocess_points(const PointCloud &points, double downsampling_resolution, int num_neighbors=10, int num_threads=4)
Preprocess point cloud (downsampling, kdtree creation, and normal and covariance estimation).
GaussianVoxelMap::Ptr create_gaussian_voxelmap(const PointCloud &points, double voxel_resolution)
Create an incremental Gaussian voxel map.
RegistrationResult align(const std::vector< Eigen::Matrix< T, D, 1 >> &target, const std::vector< Eigen::Matrix< T, D, 1 >> &source, const Eigen::Isometry3d &init_T=Eigen::Isometry3d::Identity(), const RegistrationSetting &setting=RegistrationSetting())
Align point clouds.
Incremental voxelmap. This class supports incremental point cloud insertion and LRU-based voxel delet...
Definition: incremental_voxelmap.hpp:38
std::shared_ptr< IncrementalVoxelMap > Ptr
Definition: incremental_voxelmap.hpp:40
"Safe" KdTree that holds the ownership of the input points.
Definition: kdtree.hpp:245
Point cloud.
Definition: point_cloud.hpp:15
Registration result.
Definition: registration_result.hpp:11
Registration setting.
Definition: registration_helper.hpp:37
double max_correspondence_distance
Maximum correspondence distance.
Definition: registration_helper.hpp:43
double voxel_resolution
Voxel resolution for VGICP.
Definition: registration_helper.hpp:41
double rotation_eps
Rotation tolerance for convergence check [rad].
Definition: registration_helper.hpp:44
int num_threads
Number of threads.
Definition: registration_helper.hpp:46
double translation_eps
Translation tolerance for convergence check.
Definition: registration_helper.hpp:45
RegistrationType type
Registration type.
Definition: registration_helper.hpp:40
RegistrationType
Definition: registration_helper.hpp:38
@ GICP
Definition: registration_helper.hpp:38
@ PLANE_ICP
Definition: registration_helper.hpp:38
@ VGICP
Definition: registration_helper.hpp:38
@ ICP
Definition: registration_helper.hpp:38
bool verbose
Verbose mode.
Definition: registration_helper.hpp:48
int max_iterations
Maximum number of iterations.
Definition: registration_helper.hpp:47
double downsampling_resolution
Downsample resolution (this will be used only in the Eigen-based interface)
Definition: registration_helper.hpp:42