gtsam_points
Loading...
Searching...
No Matches
region_growing.hpp
1// SPDX-License-Identifier: MIT
2// Copyright (c) 2025 Kenji Koide (k.koide@aist.go.jp)
3
4#pragma once
5
6#include <deque>
7#include <vector>
8#include <cstdint>
9#include <Eigen/Core>
10#include <gtsam_points/types/point_cloud.hpp>
11#include <gtsam_points/ann/nearest_neighbor_search.hpp>
12
13namespace gtsam_points {
14
17 double distance_threshold = 0.5;
18 double angle_threshold = 10.0 * M_PI / 180.0;
19 double dilation_radius = 0.5;
20 int max_cluster_size = 1000000;
21 int max_steps = 1000000;
22 int num_threads = 1;
23};
24
27 std::vector<size_t> cluster_indices;
28 std::deque<size_t> seed_points;
29 std::vector<bool> visited_seeds;
30};
31
38template <typename PointCloud>
39RegionGrowingContext region_growing_init_(
40 const PointCloud& points,
41 const NearestNeighborSearch& search,
42 const Eigen::Vector4d& seed_point,
43 const RegionGrowingParams& params);
44
51template <typename PointCloud>
52bool region_growing_step_(
53 RegionGrowingContext& context,
54 const PointCloud& points,
55 const NearestNeighborSearch& search,
56 const RegionGrowingParams& params);
57
63template <typename PointCloud>
64void region_growing_dilation_(
65 RegionGrowingContext& context,
66 const PointCloud& points,
67 const NearestNeighborSearch& search,
68 const RegionGrowingParams& params);
69
76template <typename PointCloud>
77bool region_growing_update_(
78 RegionGrowingContext& context,
79 const PointCloud& points,
80 const NearestNeighborSearch& search,
81 const RegionGrowingParams& params);
82
83RegionGrowingContext region_growing_init(
84 const PointCloud& points,
85 const NearestNeighborSearch& search,
86 const Eigen::Vector4d& seed_point,
87 const RegionGrowingParams& params);
88
89bool region_growing_update(
90 RegionGrowingContext& context,
91 const PointCloud& points,
92 const NearestNeighborSearch& search,
93 const RegionGrowingParams& params);
94
95} // namespace gtsam_points
Nearest neighbor search interface.
Definition nearest_neighbor_search.hpp:16
Standard point cloud class that holds only pointers to point attributes.
Definition point_cloud.hpp:19
Region growing context.
Definition region_growing.hpp:26
std::vector< size_t > cluster_indices
Indices of points in the cluster.
Definition region_growing.hpp:27
std::deque< size_t > seed_points
Seed points to be evaluated.
Definition region_growing.hpp:28
std::vector< bool > visited_seeds
Seed points that have been visited.
Definition region_growing.hpp:29
Region growing parameters.
Definition region_growing.hpp:16
int num_threads
Number of threads.
Definition region_growing.hpp:22
double angle_threshold
Angle threshold.
Definition region_growing.hpp:18
double distance_threshold
Distance threshold.
Definition region_growing.hpp:17
int max_steps
Maximum number of update steps.
Definition region_growing.hpp:21
double dilation_radius
Radius of dilation after region growing.
Definition region_growing.hpp:19
int max_cluster_size
Maximum cluster size.
Definition region_growing.hpp:20