Point Cloud Library (PCL) 1.14.0
Loading...
Searching...
No Matches
extract_clusters.h
1/*
2 * Software License Agreement (BSD License)
3 *
4 * Point Cloud Library (PCL) - www.pointclouds.org
5 * Copyright (c) 2010-2011, Willow Garage, Inc.
6 *
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of the copyright holder(s) nor the names of its
20 * contributors may be used to endorse or promote products derived
21 * from this software without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *
36 * $Id$
37 *
38 */
39
40#pragma once
41
42#include <pcl/console/print.h> // for PCL_ERROR
43#include <pcl/pcl_base.h>
44
45#include <pcl/search/search.h> // for Search
46#include <pcl/search/kdtree.h> // for KdTree
47
48namespace pcl
49{
50 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
51 /** \brief Decompose a region of space into clusters based on the Euclidean distance between points
52 * \param cloud the point cloud message
53 * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
54 * \note the tree has to be created as a spatial locator on \a cloud
55 * \param tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
56 * \param clusters the resultant clusters containing point indices (as a vector of PointIndices)
57 * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
58 * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)
59 * \ingroup segmentation
60 */
61 template <typename PointT> void
63 const PointCloud<PointT> &cloud, const typename search::Search<PointT>::Ptr &tree,
64 float tolerance, std::vector<PointIndices> &clusters,
65 unsigned int min_pts_per_cluster = 1, unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ());
66
67 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
68 /** \brief Decompose a region of space into clusters based on the Euclidean distance between points
69 * \param cloud the point cloud message
70 * \param indices a list of point indices to use from \a cloud
71 * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
72 * \note the tree has to be created as a spatial locator on \a cloud and \a indices
73 * \param tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
74 * \param clusters the resultant clusters containing point indices (as a vector of PointIndices)
75 * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
76 * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)
77 * \ingroup segmentation
78 */
79 template <typename PointT> void
81 const PointCloud<PointT> &cloud, const Indices &indices,
82 const typename search::Search<PointT>::Ptr &tree, float tolerance, std::vector<PointIndices> &clusters,
83 unsigned int min_pts_per_cluster = 1, unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ());
84
85 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
86 /** \brief Decompose a region of space into clusters based on the euclidean distance between points, and the normal
87 * angular deviation between points. Each point added to the cluster is origin to another radius search. Each point
88 * within radius range will be compared to the origin in respect to normal angle and euclidean distance. If both
89 * are under their respective threshold the point will be added to the cluster. Generally speaking the cluster
90 * algorithm will not stop on smooth surfaces but on surfaces with sharp edges.
91 * \param cloud the point cloud message
92 * \param normals the point cloud message containing normal information
93 * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
94 * \note the tree has to be created as a spatial locator on \a cloud
95 * \param tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space
96 * \param clusters the resultant clusters containing point indices (as a vector of PointIndices)
97 * \param eps_angle the maximum allowed difference between normals in radians for cluster/region growing
98 * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
99 * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)
100 * \ingroup segmentation
101 */
102 template <typename PointT, typename Normal> void
104 const PointCloud<PointT> &cloud, const PointCloud<Normal> &normals,
105 float tolerance, const typename KdTree<PointT>::Ptr &tree,
106 std::vector<PointIndices> &clusters, double eps_angle,
107 unsigned int min_pts_per_cluster = 1,
108 unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ())
109 {
110 if (tree->getInputCloud ()->size () != cloud.size ())
111 {
112 PCL_ERROR("[pcl::extractEuclideanClusters] Tree built for a different point "
113 "cloud dataset (%zu) than the input cloud (%zu)!\n",
114 static_cast<std::size_t>(tree->getInputCloud()->size()),
115 static_cast<std::size_t>(cloud.size()));
116 return;
117 }
118 if (cloud.size () != normals.size ())
119 {
120 PCL_ERROR("[pcl::extractEuclideanClusters] Number of points in the input point "
121 "cloud (%zu) different than normals (%zu)!\n",
122 static_cast<std::size_t>(cloud.size()),
123 static_cast<std::size_t>(normals.size()));
124 return;
125 }
126 const double cos_eps_angle = std::cos (eps_angle); // compute this once instead of acos many times (faster)
127
128 // Create a bool vector of processed point indices, and initialize it to false
129 std::vector<bool> processed (cloud.size (), false);
130
131 Indices nn_indices;
132 std::vector<float> nn_distances;
133 // Process all points in the indices vector
134 for (std::size_t i = 0; i < cloud.size (); ++i)
135 {
136 if (processed[i])
137 continue;
138
139 Indices seed_queue;
140 int sq_idx = 0;
141 seed_queue.push_back (static_cast<index_t> (i));
142
143 processed[i] = true;
144
145 while (sq_idx < static_cast<int> (seed_queue.size ()))
146 {
147 // Search for sq_idx
148 if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
149 {
150 sq_idx++;
151 continue;
152 }
153
154 for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx
155 {
156 if (processed[nn_indices[j]]) // Has this point been processed before ?
157 continue;
158
159 //processed[nn_indices[j]] = true;
160 // [-1;1]
161 double dot_p = normals[seed_queue[sq_idx]].normal[0] * normals[nn_indices[j]].normal[0] +
162 normals[seed_queue[sq_idx]].normal[1] * normals[nn_indices[j]].normal[1] +
163 normals[seed_queue[sq_idx]].normal[2] * normals[nn_indices[j]].normal[2];
164 if ( std::abs (dot_p) > cos_eps_angle )
165 {
166 processed[nn_indices[j]] = true;
167 seed_queue.push_back (nn_indices[j]);
168 }
169 }
170
171 sq_idx++;
172 }
173
174 // If this queue is satisfactory, add to the clusters
175 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
176 {
178 r.indices.resize (seed_queue.size ());
179 for (std::size_t j = 0; j < seed_queue.size (); ++j)
180 r.indices[j] = seed_queue[j];
181
182 // After clustering, indices are out of order, so sort them
183 std::sort (r.indices.begin (), r.indices.end ());
184
185 r.header = cloud.header;
186 clusters.push_back (r); // We could avoid a copy by working directly in the vector
187 }
188 else
189 {
190 PCL_DEBUG("[pcl::extractEuclideanClusters] This cluster has %zu points, which is not between %u and %u points, so it is not a final cluster\n",
191 seed_queue.size (), min_pts_per_cluster, max_pts_per_cluster);
192 }
193 }
194 }
195
196
197 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
198 /** \brief Decompose a region of space into clusters based on the euclidean distance between points, and the normal
199 * angular deviation between points. Each point added to the cluster is origin to another radius search. Each point
200 * within radius range will be compared to the origin in respect to normal angle and euclidean distance. If both
201 * are under their respective threshold the point will be added to the cluster. Generally speaking the cluster
202 * algorithm will not stop on smooth surfaces but on surfaces with sharp edges.
203 * \param cloud the point cloud message
204 * \param normals the point cloud message containing normal information
205 * \param indices a list of point indices to use from \a cloud
206 * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
207 * \note the tree has to be created as a spatial locator on \a cloud
208 * \param tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space
209 * \param clusters the resultant clusters containing point indices (as PointIndices)
210 * \param eps_angle the maximum allowed difference between normals in radians for cluster/region growing
211 * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
212 * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)
213 * \ingroup segmentation
214 */
215 template <typename PointT, typename Normal>
217 const PointCloud<PointT> &cloud, const PointCloud<Normal> &normals,
218 const Indices &indices, const typename KdTree<PointT>::Ptr &tree,
219 float tolerance, std::vector<PointIndices> &clusters, double eps_angle,
220 unsigned int min_pts_per_cluster = 1,
221 unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ())
222 {
223 // \note If the tree was created over <cloud, indices>, we guarantee a 1-1 mapping between what the tree returns
224 //and indices[i]
225 if (tree->getInputCloud()->size() != cloud.size()) {
226 PCL_ERROR("[pcl::extractEuclideanClusters] Tree built for a different point "
227 "cloud dataset (%zu) than the input cloud (%zu)!\n",
228 static_cast<std::size_t>(tree->getInputCloud()->size()),
229 static_cast<std::size_t>(cloud.size()));
230 return;
231 }
232 if (tree->getIndices()->size() != indices.size()) {
233 PCL_ERROR("[pcl::extractEuclideanClusters] Tree built for a different set of "
234 "indices (%zu) than the input set (%zu)!\n",
235 static_cast<std::size_t>(tree->getIndices()->size()),
236 indices.size());
237 return;
238 }
239 if (cloud.size() != normals.size()) {
240 PCL_ERROR("[pcl::extractEuclideanClusters] Number of points in the input point "
241 "cloud (%zu) different than normals (%zu)!\n",
242 static_cast<std::size_t>(cloud.size()),
243 static_cast<std::size_t>(normals.size()));
244 return;
245 }
246 const double cos_eps_angle = std::cos (eps_angle); // compute this once instead of acos many times (faster)
247 // Create a bool vector of processed point indices, and initialize it to false
248 std::vector<bool> processed (cloud.size (), false);
249
250 Indices nn_indices;
251 std::vector<float> nn_distances;
252 // Process all points in the indices vector
253 for (const auto& point_idx : indices)
254 {
255 if (processed[point_idx])
256 continue;
257
258 Indices seed_queue;
259 int sq_idx = 0;
260 seed_queue.push_back (point_idx);
261
262 processed[point_idx] = true;
263
264 while (sq_idx < static_cast<int> (seed_queue.size ()))
265 {
266 // Search for sq_idx
267 if (!tree->radiusSearch (cloud[seed_queue[sq_idx]], tolerance, nn_indices, nn_distances))
268 {
269 sq_idx++;
270 continue;
271 }
272
273 for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx
274 {
275 if (processed[nn_indices[j]]) // Has this point been processed before ?
276 continue;
277
278 //processed[nn_indices[j]] = true;
279 // [-1;1]
280 double dot_p = normals[seed_queue[sq_idx]].normal[0] * normals[nn_indices[j]].normal[0] +
281 normals[seed_queue[sq_idx]].normal[1] * normals[nn_indices[j]].normal[1] +
282 normals[seed_queue[sq_idx]].normal[2] * normals[nn_indices[j]].normal[2];
283 if ( std::abs (dot_p) > cos_eps_angle )
284 {
285 processed[nn_indices[j]] = true;
286 seed_queue.push_back (nn_indices[j]);
287 }
288 }
289
290 sq_idx++;
291 }
292
293 // If this queue is satisfactory, add to the clusters
294 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
295 {
297 r.indices.resize (seed_queue.size ());
298 for (std::size_t j = 0; j < seed_queue.size (); ++j)
299 r.indices[j] = seed_queue[j];
300
301 // After clustering, indices are out of order, so sort them
302 std::sort (r.indices.begin (), r.indices.end ());
303
304 r.header = cloud.header;
305 clusters.push_back (r);
306 }
307 else
308 {
309 PCL_DEBUG("[pcl::extractEuclideanClusters] This cluster has %zu points, which is not between %u and %u points, so it is not a final cluster\n",
310 seed_queue.size (), min_pts_per_cluster, max_pts_per_cluster);
311 }
312 }
313 }
314
315 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
316 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
317 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
318 /** \brief @b EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense.
319 * \author Radu Bogdan Rusu
320 * \ingroup segmentation
321 */
322 template <typename PointT>
324 {
326
327 public:
331
333 using KdTreePtr = typename KdTree::Ptr;
334
337
338 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
339 /** \brief Empty constructor. */
341
342 /** \brief Provide a pointer to the search object.
343 * \param[in] tree a pointer to the spatial search object.
344 */
345 inline void
347 {
348 tree_ = tree;
349 }
350
351 /** \brief Get a pointer to the search method used.
352 * @todo fix this for a generic search tree
353 */
354 inline KdTreePtr
356 {
357 return (tree_);
358 }
359
360 /** \brief Set the spatial cluster tolerance as a measure in the L2 Euclidean space
361 * \param[in] tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space
362 */
363 inline void
364 setClusterTolerance (double tolerance)
365 {
366 cluster_tolerance_ = tolerance;
367 }
368
369 /** \brief Get the spatial cluster tolerance as a measure in the L2 Euclidean space. */
370 inline double
372 {
373 return (cluster_tolerance_);
374 }
375
376 /** \brief Set the minimum number of points that a cluster needs to contain in order to be considered valid.
377 * \param[in] min_cluster_size the minimum cluster size
378 */
379 inline void
381 {
382 min_pts_per_cluster_ = min_cluster_size;
383 }
384
385 /** \brief Get the minimum number of points that a cluster needs to contain in order to be considered valid. */
386 inline pcl::uindex_t
388 {
389 return (min_pts_per_cluster_);
390 }
391
392 /** \brief Set the maximum number of points that a cluster needs to contain in order to be considered valid.
393 * \param[in] max_cluster_size the maximum cluster size
394 */
395 inline void
397 {
398 max_pts_per_cluster_ = max_cluster_size;
399 }
400
401 /** \brief Get the maximum number of points that a cluster needs to contain in order to be considered valid. */
402 inline pcl::uindex_t
404 {
405 return (max_pts_per_cluster_);
406 }
407
408 /** \brief Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>
409 * \param[out] clusters the resultant point clusters
410 */
411 void
412 extract (std::vector<PointIndices> &clusters);
413
414 protected:
415 // Members derived from the base class
420
421 /** \brief A pointer to the spatial search object. */
422 KdTreePtr tree_{nullptr};
423
424 /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
426
427 /** \brief The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). */
429
430 /** \brief The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). */
431 pcl::uindex_t max_pts_per_cluster_{std::numeric_limits<pcl::uindex_t>::max()};
432
433 /** \brief Class getName method. */
434 virtual std::string getClassName () const { return ("EuclideanClusterExtraction"); }
435
436 };
437
438 /** \brief Sort clusters method (for std::sort).
439 * \ingroup segmentation
440 */
441 inline bool
443 {
444 return (a.indices.size () < b.indices.size ());
445 }
446}
447
448#ifdef PCL_NO_PRECOMPILE
449#include <pcl/segmentation/impl/extract_clusters.hpp>
450#endif
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sen...
pcl::uindex_t getMaxClusterSize() const
Get the maximum number of points that a cluster needs to contain in order to be considered valid.
double cluster_tolerance_
The spatial cluster tolerance as a measure in the L2 Euclidean space.
pcl::uindex_t max_pts_per_cluster_
The maximum number of points that a cluster needs to contain in order to be considered valid (default...
typename PointCloud::Ptr PointCloudPtr
typename PointCloud::ConstPtr PointCloudConstPtr
void extract(std::vector< PointIndices > &clusters)
Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>
EuclideanClusterExtraction()=default
Empty constructor.
double getClusterTolerance() const
Get the spatial cluster tolerance as a measure in the L2 Euclidean space.
virtual std::string getClassName() const
Class getName method.
void setClusterTolerance(double tolerance)
Set the spatial cluster tolerance as a measure in the L2 Euclidean space.
pcl::uindex_t min_pts_per_cluster_
The minimum number of points that a cluster needs to contain in order to be considered valid (default...
void setSearchMethod(const KdTreePtr &tree)
Provide a pointer to the search object.
PointIndices::ConstPtr PointIndicesConstPtr
KdTreePtr getSearchMethod() const
Get a pointer to the search method used.
void setMaxClusterSize(pcl::uindex_t max_cluster_size)
Set the maximum number of points that a cluster needs to contain in order to be considered valid.
void setMinClusterSize(pcl::uindex_t min_cluster_size)
Set the minimum number of points that a cluster needs to contain in order to be considered valid.
KdTreePtr tree_
A pointer to the spatial search object.
pcl::PointCloud< PointT > PointCloud
pcl::uindex_t getMinClusterSize() const
Get the minimum number of points that a cluster needs to contain in order to be considered valid.
PointCloudConstPtr getInputCloud() const
Get a pointer to the input point cloud dataset.
Definition kdtree.h:101
IndicesConstPtr getIndices() const
Get a pointer to the vector of indices used.
Definition kdtree.h:94
virtual int radiusSearch(const PointT &p_q, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const =0
Search for all the nearest neighbors of the query point in a given radius.
shared_ptr< KdTree< PointT > > Ptr
Definition kdtree.h:69
PCL base class.
Definition pcl_base.h:70
PointCloudConstPtr input_
The input point cloud dataset.
Definition pcl_base.h:147
IndicesPtr indices_
A pointer to the vector of point indices to use.
Definition pcl_base.h:150
bool initCompute()
This method should get called before starting the actual computation.
Definition pcl_base.hpp:138
bool deinitCompute()
This method should get called after finishing the actual computation.
Definition pcl_base.hpp:175
PointCloud represents the base class in PCL for storing collections of 3D points.
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
pcl::PCLHeader header
The point cloud header.
std::size_t size() const
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr
Generic search class.
Definition search.h:75
shared_ptr< pcl::search::Search< PointT > > Ptr
Definition search.h:81
void extractEuclideanClusters(const PointCloud< PointT > &cloud, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< PointIndices > &clusters, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)())
Decompose a region of space into clusters based on the Euclidean distance between points.
bool comparePointClusters(const pcl::PointIndices &a, const pcl::PointIndices &b)
Sort clusters method (for std::sort).
detail::int_type_t< detail::index_type_size, false > uindex_t
Type used for an unsigned index in PCL.
Definition types.h:120
detail::int_type_t< detail::index_type_size, detail::index_type_signed > index_t
Type used for an index in PCL.
Definition types.h:112
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition types.h:133
shared_ptr< ::pcl::PointIndices > Ptr
::pcl::PCLHeader header
shared_ptr< const ::pcl::PointIndices > ConstPtr