00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_EXTRACT_CLUSTERS_H_
00039 #define PCL_EXTRACT_CLUSTERS_H_
00040
00041 #include <pcl/pcl_base.h>
00042
00043 #include "pcl/kdtree/kdtree.h"
00044 #include "pcl/kdtree/tree_types.h"
00045
00046 namespace pcl
00047 {
00049
00058 template <typename PointT> void extractEuclideanClusters (const PointCloud<PointT> &cloud, const boost::shared_ptr<KdTree<PointT> > &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) ());
00059
00061
00071 template <typename PointT> void extractEuclideanClusters (const PointCloud<PointT> &cloud, const std::vector<int> &indices, const boost::shared_ptr<KdTree<PointT> > &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) ());
00072
00074
00086 template <typename PointT, typename Normal> void
00087 extractEuclideanClusters (
00088 const PointCloud<PointT> &cloud, const PointCloud<Normal> &normals,
00089 float tolerance, const boost::shared_ptr<KdTree<PointT> > &tree,
00090 std::vector<PointIndices> &clusters, double eps_angle,
00091 unsigned int min_pts_per_cluster = 1,
00092 unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ())
00093 {
00094 if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00095 {
00096 ROS_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!", tree->getInputCloud ()->points.size (), cloud.points.size ());
00097 return;
00098 }
00099 if (cloud.points.size () != normals.points.size ())
00100 {
00101 ROS_ERROR ("[pcl::extractEuclideanClusters] Number of points in the input point cloud (%zu) different than normals (%zu)!", cloud.points.size (), normals.points.size ());
00102 return;
00103 }
00104
00105
00106 std::vector<bool> processed (cloud.points.size (), false);
00107
00108 std::vector<int> nn_indices;
00109 std::vector<float> nn_distances;
00110
00111 for (size_t i = 0; i < cloud.points.size (); ++i)
00112 {
00113 if (processed[i])
00114 continue;
00115
00116 std::vector<unsigned int> seed_queue;
00117 int sq_idx = 0;
00118 seed_queue.push_back (i);
00119
00120 processed[i] = true;
00121
00122 while (sq_idx < (int)seed_queue.size ())
00123 {
00124
00125 if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
00126 {
00127 sq_idx++;
00128 continue;
00129 }
00130
00131 for (size_t j = 1; j < nn_indices.size (); ++j)
00132 {
00133 if (processed[nn_indices[j]])
00134 continue;
00135
00136 processed[nn_indices[j]] = true;
00137
00138 double dot_p = normals.points[i].normal[0] * normals.points[nn_indices[j]].normal[0] +
00139 normals.points[i].normal[1] * normals.points[nn_indices[j]].normal[1] +
00140 normals.points[i].normal[2] * normals.points[nn_indices[j]].normal[2];
00141 if ( fabs (acos (dot_p)) < eps_angle )
00142 {
00143 processed[nn_indices[j]] = true;
00144 seed_queue.push_back (nn_indices[j]);
00145 }
00146 }
00147
00148 sq_idx++;
00149 }
00150
00151
00152 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00153 {
00154 pcl::PointIndices r;
00155 r.indices.resize (seed_queue.size ());
00156 for (size_t j = 0; j < seed_queue.size (); ++j)
00157 r.indices[j] = seed_queue[j];
00158
00159 sort (r.indices.begin (), r.indices.end ());
00160 r.indices.erase (unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00161
00162 r.header = cloud.header;
00163 clusters.push_back (r);
00164 }
00165 }
00166 }
00167
00168
00170
00183 template <typename PointT, typename Normal>
00184 void extractEuclideanClusters (
00185 const PointCloud<PointT> &cloud, const PointCloud<Normal> &normals,
00186 const std::vector<int> &indices, const boost::shared_ptr<KdTree<PointT> > &tree,
00187 float tolerance, std::vector<PointIndices> &clusters, double eps_angle,
00188 unsigned int min_pts_per_cluster = 1,
00189 unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ())
00190 {
00191
00192
00193 if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00194 {
00195 ROS_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!", tree->getInputCloud ()->points.size (), cloud.points.size ());
00196 return;
00197 }
00198 if (tree->getIndices ()->size () != indices.size ())
00199 {
00200 ROS_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different set of indices (%zu) than the input set (%zu)!", tree->getIndices ()->size (), indices.size ());
00201 return;
00202 }
00203 if (cloud.points.size () != normals.points.size ())
00204 {
00205 ROS_ERROR ("[pcl::extractEuclideanClusters] Number of points in the input point cloud (%zu) different than normals (%zu)!", cloud.points.size (), normals.points.size ());
00206 return;
00207 }
00208
00209 std::vector<bool> processed (indices.size (), false);
00210
00211 std::vector<int> nn_indices;
00212 std::vector<float> nn_distances;
00213
00214 for (size_t i = 0; i < indices.size (); ++i)
00215 {
00216 if (processed[i])
00217 continue;
00218
00219 std::vector<int> seed_queue;
00220 int sq_idx = 0;
00221 seed_queue.push_back (i);
00222
00223 processed[i] = true;
00224
00225 while (sq_idx < (int)seed_queue.size ())
00226 {
00227
00228 if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
00229 {
00230 sq_idx++;
00231 continue;
00232 }
00233
00234 for (size_t j = 1; j < nn_indices.size (); ++j)
00235 {
00236 if (processed[nn_indices[j]])
00237 continue;
00238
00239 processed[nn_indices[j]] = true;
00240
00241 double dot_p =
00242 normals.points[indices[i]].normal[0] * normals.points[indices[nn_indices[j]]].normal[0] +
00243 normals.points[indices[i]].normal[1] * normals.points[indices[nn_indices[j]]].normal[1] +
00244 normals.points[indices[i]].normal[2] * normals.points[indices[nn_indices[j]]].normal[2];
00245 if ( fabs (acos (dot_p)) < eps_angle )
00246 {
00247 processed[nn_indices[j]] = true;
00248 seed_queue.push_back (nn_indices[j]);
00249 }
00250 }
00251
00252 sq_idx++;
00253 }
00254
00255
00256 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00257 {
00258 pcl::PointIndices r;
00259 r.indices.resize (seed_queue.size ());
00260 for (size_t j = 0; j < seed_queue.size (); ++j)
00261 r.indices[j] = indices[seed_queue[j]];
00262
00263 sort (r.indices.begin (), r.indices.end ());
00264 r.indices.erase (unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00265
00266 r.header = cloud.header;
00267 clusters.push_back (r);
00268 }
00269 }
00270 }
00271
00275
00278 template <typename PointT>
00279 class EuclideanClusterExtraction: public PCLBase<PointT>
00280 {
00281 typedef PCLBase<PointT> BasePCLBase;
00282
00283 public:
00284 typedef pcl::PointCloud<PointT> PointCloud;
00285 typedef typename PointCloud::Ptr PointCloudPtr;
00286 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00287
00288 typedef typename pcl::KdTree<PointT> KdTree;
00289 typedef typename pcl::KdTree<PointT>::Ptr KdTreePtr;
00290
00291 typedef PointIndices::Ptr PointIndicesPtr;
00292 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00293
00295
00296 EuclideanClusterExtraction () : tree_ (), spatial_locator_ (0), min_pts_per_cluster_ (1),
00297 max_pts_per_cluster_ (std::numeric_limits<int>::max ())
00298 {};
00299
00303 inline void setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00304
00306 inline KdTreePtr getSearchMethod () { return (tree_); }
00307
00311 inline void setClusterTolerance (double tolerance) { cluster_tolerance_ = tolerance; }
00312
00314 inline double getClusterTolerance () { return (cluster_tolerance_); }
00315
00319 inline void setMinClusterSize (int min_cluster_size) { min_pts_per_cluster_ = min_cluster_size; }
00320
00322 inline int getMinClusterSize () { return (min_pts_per_cluster_); }
00323
00327 inline void setMaxClusterSize (int max_cluster_size) { max_pts_per_cluster_ = max_cluster_size; }
00328
00330 inline int getMaxClusterSize () { return (max_pts_per_cluster_); }
00331
00335 void extract (std::vector<PointIndices> &clusters);
00336
00340 inline void setSpatialLocator (int locator) { spatial_locator_ = locator; }
00342 inline int getSpatialLocator () { return (spatial_locator_); }
00343 protected:
00344
00345 using BasePCLBase::input_;
00346 using BasePCLBase::indices_;
00347 using BasePCLBase::initCompute;
00348 using BasePCLBase::deinitCompute;
00349
00351 KdTreePtr tree_;
00352
00358 int spatial_locator_;
00359
00361 double cluster_tolerance_;
00362
00364 int min_pts_per_cluster_;
00365
00367 int max_pts_per_cluster_;
00368
00370 virtual std::string getClassName () const { return ("EuclideanClusterExtraction"); }
00371
00372 };
00373
00375 inline bool
00376 comparePointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b)
00377 {
00378 return (a.indices.size () < b.indices.size ());
00379 }
00380 }
00381
00382 #endif //#ifndef PCL_EXTRACT_CLUSTERS_H_