small_gicp
normal_estimation_omp.hpp
Go to the documentation of this file.
1 // SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
2 // SPDX-License-Identifier: MIT
3 #pragma once
4 
6 
7 namespace small_gicp {
8 
9 template <typename Setter, typename PointCloud>
10 void estimate_local_features_omp(PointCloud& cloud, int num_neighbors, int num_threads) {
11  traits::resize(cloud, traits::size(cloud));
12  UnsafeKdTree<PointCloud> kdtree(cloud);
13 #pragma omp parallel for num_threads(num_threads)
14  for (size_t i = 0; i < traits::size(cloud); i++) {
15  estimate_local_features<Setter>(cloud, kdtree, num_neighbors, i);
16  }
17 }
18 
19 template <typename Setter, typename PointCloud, typename KdTree>
20 void estimate_local_features_omp(PointCloud& cloud, KdTree& kdtree, int num_neighbors, int num_threads) {
21  traits::resize(cloud, traits::size(cloud));
22 #pragma omp parallel for num_threads(num_threads)
23  for (std::int64_t i = 0; i < traits::size(cloud); i++) {
24  estimate_local_features<Setter>(cloud, kdtree, num_neighbors, i);
25  }
26 }
27 
34 template <typename PointCloud>
35 void estimate_normals_omp(PointCloud& cloud, int num_neighbors = 20, int num_threads = 4) {
36  estimate_local_features_omp<NormalSetter<PointCloud>>(cloud, num_neighbors, num_threads);
37 }
38 
46 template <typename PointCloud, typename KdTree>
47 void estimate_normals_omp(PointCloud& cloud, KdTree& kdtree, int num_neighbors = 20, int num_threads = 4) {
48  estimate_local_features_omp<NormalSetter<PointCloud>>(cloud, kdtree, num_neighbors, num_threads);
49 }
50 
57 template <typename PointCloud>
58 void estimate_covariances_omp(PointCloud& cloud, int num_neighbors = 20, int num_threads = 4) {
59  estimate_local_features_omp<CovarianceSetter<PointCloud>>(cloud, num_neighbors, num_threads);
60 }
61 
69 template <typename PointCloud, typename KdTree>
70 void estimate_covariances_omp(PointCloud& cloud, KdTree& kdtree, int num_neighbors = 20, int num_threads = 4) {
71  estimate_local_features_omp<CovarianceSetter<PointCloud>>(cloud, kdtree, num_neighbors, num_threads);
72 }
73 
80 template <typename PointCloud>
81 void estimate_normals_covariances_omp(PointCloud& cloud, int num_neighbors = 20, int num_threads = 4) {
82  estimate_local_features_omp<NormalCovarianceSetter<PointCloud>>(cloud, num_neighbors, num_threads);
83 }
84 
92 template <typename PointCloud, typename KdTree>
93 void estimate_normals_covariances_omp(PointCloud& cloud, KdTree& kdtree, int num_neighbors = 20, int num_threads = 4) {
94  estimate_local_features_omp<NormalCovarianceSetter<PointCloud>>(cloud, kdtree, num_neighbors, num_threads);
95 }
96 
97 } // namespace small_gicp
size_t size(const T &points)
Get the number of points.
Definition: traits.hpp:16
void resize(T &points, size_t n)
Resize the point cloud (this function should resize all attributes)
Definition: traits.hpp:58
Definition: flat_container.hpp:12
void estimate_local_features_omp(PointCloud &cloud, int num_neighbors, int num_threads)
Definition: normal_estimation_omp.hpp:10
void estimate_normals_omp(PointCloud &cloud, int num_neighbors=20, int num_threads=4)
Estimate point normals with OpenMP.
Definition: normal_estimation_omp.hpp:35
void estimate_normals_covariances_omp(PointCloud &cloud, int num_neighbors=20, int num_threads=4)
Estimate point normals and covariances with OpenMP.
Definition: normal_estimation_omp.hpp:81
void estimate_covariances_omp(PointCloud &cloud, int num_neighbors=20, int num_threads=4)
Estimate point covariances with OpenMP.
Definition: normal_estimation_omp.hpp:58
"Safe" KdTree that holds the ownership of the input points.
Definition: kdtree.hpp:245
Point cloud.
Definition: point_cloud.hpp:15
"Unsafe" KdTree.
Definition: kdtree.hpp:137