cpp-toolbox  0.0.1
A toolbox library for C++
Loading...
Searching...
No Matches
curvature_keypoints_impl.hpp
Go to the documentation of this file.
1#pragma once
2
5#include <Eigen/Dense>
6#include <Eigen/Eigenvalues>
7#include <algorithm>
8#include <cmath>
9#include <future>
10#include <vector>
11
12namespace toolbox::pcl
13{
14
15template<typename DataType, typename KNN>
17{
18 m_cloud = std::make_shared<point_cloud>(cloud);
19 return m_cloud->size();
20}
21
22template<typename DataType, typename KNN>
24{
25 m_cloud = cloud;
26 return m_cloud->size();
27}
28
29template<typename DataType, typename KNN>
31{
32 m_knn = const_cast<knn_type*>(&knn);
33 if (m_cloud) {
34 m_knn->set_input(*m_cloud);
35 }
36 return m_cloud ? m_cloud->size() : 0;
37}
38
39template<typename DataType, typename KNN>
41{
42 m_search_radius = radius;
43 return 0;
44}
45
46template<typename DataType, typename KNN>
48{
49 m_enable_parallel = enable;
50}
51
52template<typename DataType, typename KNN>
55{
56 if (!m_cloud || !m_knn || point_idx >= m_cloud->size()) {
57 return CurvatureInfo{0, 0, 0, 0, 0};
58 }
59
60 const auto& query_point = m_cloud->points[point_idx];
61 std::vector<std::size_t> neighbor_indices;
62 std::vector<data_type> neighbor_distances;
63
64 // 在半径内查找邻居点 / Find neighbors within radius
65 m_knn->radius_neighbors(query_point, m_search_radius, neighbor_indices, neighbor_distances);
66
67 if (neighbor_indices.size() < m_min_neighbors) {
68 return CurvatureInfo{0, 0, 0, 0, 0};
69 }
70
71 // 计算协方差矩阵 / Compute covariance matrix
72 Eigen::Vector3d centroid(0, 0, 0);
73 for (const auto& idx : neighbor_indices) {
74 const auto& p = m_cloud->points[idx];
75 centroid += Eigen::Vector3d(static_cast<double>(p.x),
76 static_cast<double>(p.y),
77 static_cast<double>(p.z));
78 }
79 centroid /= static_cast<double>(neighbor_indices.size());
80
81 Eigen::Matrix3d covariance = Eigen::Matrix3d::Zero();
82 for (const auto& idx : neighbor_indices) {
83 const auto& p = m_cloud->points[idx];
84 Eigen::Vector3d point_vec(static_cast<double>(p.x),
85 static_cast<double>(p.y),
86 static_cast<double>(p.z));
87 Eigen::Vector3d diff = point_vec - centroid;
88 covariance += diff * diff.transpose();
89 }
90 covariance /= static_cast<double>(neighbor_indices.size() - 1);
91
92 // 计算特征值和特征向量 / Compute eigenvalues and eigenvectors
93 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigen_solver(covariance);
94 if (eigen_solver.info() != Eigen::Success) {
95 return CurvatureInfo{0, 0, 0, 0, 0};
96 }
97
98 const Eigen::Vector3d& eigenvalues = eigen_solver.eigenvalues();
99
100 // 按降序排序特征值:λ0 >= λ1 >= λ2 / Sort eigenvalues in descending order: λ0 >= λ1 >= λ2
101 std::vector<double> sorted_eigenvals = {eigenvalues(2), eigenvalues(1), eigenvalues(0)};
102 std::sort(sorted_eigenvals.rbegin(), sorted_eigenvals.rend());
103
104 const double lambda0 = sorted_eigenvals[0];
105 const double lambda1 = sorted_eigenvals[1];
106 const double lambda2 = sorted_eigenvals[2];
107
108 // 避免除零 / Avoid division by zero
109 const double eigensum = lambda0 + lambda1 + lambda2;
110 if (eigensum < 1e-10) {
111 return CurvatureInfo{0, 0, 0, 0, 0};
112 }
113
114 // 计算曲率测度 / Compute curvature measures
115 const double principal_curvature_1 = lambda1 / eigensum;
116 const double principal_curvature_2 = lambda2 / eigensum;
117 const double mean_curvature = (principal_curvature_1 + principal_curvature_2) / 2.0;
118 const double gaussian_curvature = principal_curvature_1 * principal_curvature_2;
119 const double curvature_magnitude = std::sqrt(principal_curvature_1 * principal_curvature_1 +
120 principal_curvature_2 * principal_curvature_2);
121
122 return CurvatureInfo{
123 static_cast<data_type>(principal_curvature_1),
124 static_cast<data_type>(principal_curvature_2),
125 static_cast<data_type>(mean_curvature),
126 static_cast<data_type>(gaussian_curvature),
127 static_cast<data_type>(curvature_magnitude)
128 };
129}
130
131template<typename DataType, typename KNN>
132void curvature_keypoint_extractor_t<DataType, KNN>::compute_curvatures_range(
133 std::vector<CurvatureInfo>& curvatures,
134 std::size_t start_idx,
135 std::size_t end_idx)
136{
137 for (std::size_t i = start_idx; i < end_idx; ++i) {
138 curvatures[i] = compute_curvature(i);
139 }
140}
141
142template<typename DataType, typename KNN>
143std::vector<typename curvature_keypoint_extractor_t<DataType, KNN>::CurvatureInfo>
144curvature_keypoint_extractor_t<DataType, KNN>::compute_all_curvatures()
145{
146 if (!m_cloud) {
147 return {};
148 }
149
150 const std::size_t num_points = m_cloud->size();
151 std::vector<CurvatureInfo> curvatures(num_points);
152
153 if (m_enable_parallel && num_points > k_parallel_threshold) {
154 // 并行计算 / Parallel computation
155 const std::size_t num_threads = toolbox::base::thread_pool_singleton_t::instance().get_thread_count();
156 const std::size_t chunk_size = (num_points + num_threads - 1) / num_threads;
157
158 std::vector<std::future<void>> futures;
159 for (std::size_t t = 0; t < num_threads; ++t) {
160 const std::size_t start_idx = t * chunk_size;
161 const std::size_t end_idx = std::min(start_idx + chunk_size, num_points);
162
163 if (start_idx < end_idx) {
164 futures.emplace_back(
166 [this, &curvatures, start_idx, end_idx]() {
167 compute_curvatures_range(curvatures, start_idx, end_idx);
168 }
169 )
170 );
171 }
172 }
173
174 // 等待所有线程完成 / Wait for all threads to complete
175 for (auto& future : futures) {
176 future.wait();
177 }
178 } else {
179 // 顺序计算 / Sequential computation
180 compute_curvatures_range(curvatures, 0, num_points);
181 }
182
183 return curvatures;
184}
185
186template<typename DataType, typename KNN>
188curvature_keypoint_extractor_t<DataType, KNN>::apply_non_maxima_suppression(
189 const std::vector<CurvatureInfo>& curvatures)
190{
191 if (!m_cloud || curvatures.empty()) {
192 return {};
193 }
194
195 indices_vector keypoints;
196 const std::size_t num_points = m_cloud->size();
197
198 for (std::size_t i = 0; i < num_points; ++i) {
199 const auto& current_curvature = curvatures[i];
200
201 // 跳过低曲率的点 / Skip points with low curvature
202 if (current_curvature.curvature_magnitude < m_curvature_threshold) {
203 continue;
204 }
205
206 // 在非极大值抑制半径内查找邻居 / Find neighbors within non-maxima suppression radius
207 const auto& query_point = m_cloud->points[i];
208 std::vector<std::size_t> neighbor_indices;
209 std::vector<data_type> neighbor_distances;
210
211 m_knn->radius_neighbors(query_point, m_non_maxima_radius, neighbor_indices, neighbor_distances);
212
213 // 检查当前点是否为局部最大值 / Check if current point is local maximum
214 bool is_local_maximum = true;
215 for (const auto& neighbor_idx : neighbor_indices) {
216 if (neighbor_idx != i && neighbor_idx < curvatures.size()) {
217 if (curvatures[neighbor_idx].curvature_magnitude > current_curvature.curvature_magnitude) {
218 is_local_maximum = false;
219 break;
220 }
221 }
222 }
223
224 if (is_local_maximum) {
225 keypoints.push_back(i);
226 }
227 }
228
229 return keypoints;
230}
231
232template<typename DataType, typename KNN>
235{
236 if (!m_cloud || !m_knn) {
237 return {};
238 }
239
240 // 计算所有点的曲率 / Compute curvatures for all points
241 auto curvatures = compute_all_curvatures();
242
243 // 应用非极大值抑制找到关键点 / Apply non-maxima suppression to find keypoints
244 return apply_non_maxima_suppression(curvatures);
245}
246
247template<typename DataType, typename KNN>
249{
250 keypoint_indices = extract_impl();
251}
252
253template<typename DataType, typename KNN>
256{
257 auto keypoint_indices = extract_impl();
258
259 point_cloud keypoints;
260 keypoints.points.reserve(keypoint_indices.size());
261
262 for (const auto& idx : keypoint_indices) {
263 keypoints.points.push_back(m_cloud->points[idx]);
264 }
265
266 return keypoints;
267}
268
269template<typename DataType, typename KNN>
271{
272 auto keypoint_indices = extract_impl();
273
274 output->points.clear();
275 output->points.reserve(keypoint_indices.size());
276
277 for (const auto& idx : keypoint_indices) {
278 output->points.push_back(m_cloud->points[idx]);
279 }
280}
281
282} // namespace toolbox::pcl
static thread_pool_singleton_t & instance()
获取单例实例/Get the singleton instance
Definition thread_pool_singleton.hpp:23
基于曲率的关键点提取器 / Curvature-based keypoint extractor
Definition curvature_keypoints.hpp:61
std::size_t set_search_radius_impl(data_type radius)
CRTP实现方法 - 设置搜索半径 / CRTP implementation - set search radius.
Definition curvature_keypoints_impl.hpp:40
std::size_t set_knn_impl(const knn_type &knn)
CRTP实现方法 - 设置KNN算法 / CRTP implementation - set KNN algorithm.
Definition curvature_keypoints_impl.hpp:30
typename base_type::point_cloud point_cloud
Definition curvature_keypoints.hpp:68
std::size_t set_input_impl(const point_cloud &cloud)
CRTP实现方法 - 设置输入点云 / CRTP implementation - set input point cloud.
Definition curvature_keypoints_impl.hpp:16
typename base_type::point_cloud_ptr point_cloud_ptr
Definition curvature_keypoints.hpp:69
point_cloud extract_keypoints_impl()
Definition curvature_keypoints_impl.hpp:255
typename base_type::data_type data_type
Definition curvature_keypoints.hpp:66
indices_vector extract_impl()
CRTP实现方法 - 提取关键点 / CRTP implementation - extract keypoints.
Definition curvature_keypoints_impl.hpp:234
void enable_parallel_impl(bool enable)
CRTP实现方法 - 启用并行处理 / CRTP implementation - enable parallel processing.
Definition curvature_keypoints_impl.hpp:47
typename base_type::knn_type knn_type
Definition curvature_keypoints.hpp:67
typename base_type::indices_vector indices_vector
Definition curvature_keypoints.hpp:70
Definition base_correspondence_generator.hpp:18