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_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_
00039 #define PCL_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_
00040
00041 #include "pcl/segmentation/extract_clusters.h"
00042
00044 template <typename PointT> void
00045 pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
00046 const boost::shared_ptr<KdTree<PointT> > &tree,
00047 float tolerance, std::vector<PointIndices> &clusters,
00048 unsigned int min_pts_per_cluster,
00049 unsigned int max_pts_per_cluster)
00050 {
00051 if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00052 {
00053 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 ());
00054 return;
00055 }
00056
00057 std::vector<bool> processed (cloud.points.size (), false);
00058
00059 std::vector<int> nn_indices;
00060 std::vector<float> nn_distances;
00061
00062 for (size_t i = 0; i < cloud.points.size (); ++i)
00063 {
00064 if (processed[i])
00065 continue;
00066
00067 std::vector<int> seed_queue;
00068 int sq_idx = 0;
00069 seed_queue.push_back (i);
00070
00071 processed[i] = true;
00072
00073 while (sq_idx < (int)seed_queue.size ())
00074 {
00075
00076 if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
00077 {
00078 sq_idx++;
00079 continue;
00080 }
00081
00082 for (size_t j = 1; j < nn_indices.size (); ++j)
00083 {
00084 if (processed[nn_indices[j]])
00085 continue;
00086
00087
00088 seed_queue.push_back (nn_indices[j]);
00089 processed[nn_indices[j]] = true;
00090 }
00091
00092 sq_idx++;
00093 }
00094
00095
00096 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00097 {
00098 pcl::PointIndices r;
00099 r.indices.resize (seed_queue.size ());
00100 for (size_t j = 0; j < seed_queue.size (); ++j)
00101 r.indices[j] = seed_queue[j];
00102
00103 sort (r.indices.begin (), r.indices.end ());
00104 r.indices.erase (unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00105
00106 r.header = cloud.header;
00107 clusters.push_back (r);
00108 }
00109 }
00110 }
00111
00113 template <typename PointT> void
00114 pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
00115 const std::vector<int> &indices,
00116 const boost::shared_ptr<KdTree<PointT> > &tree,
00117 float tolerance, std::vector<PointIndices> &clusters,
00118 unsigned int min_pts_per_cluster,
00119 unsigned int max_pts_per_cluster)
00120 {
00121
00122
00123 if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00124 {
00125 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 ());
00126 return;
00127 }
00128 if (tree->getIndices ()->size () != indices.size ())
00129 {
00130 ROS_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different set of indices (%zu) than the input set (%zu)!", tree->getIndices ()->size (), indices.size ());
00131 return;
00132 }
00133
00134
00135 std::vector<bool> processed (indices.size (), false);
00136
00137 std::vector<int> nn_indices;
00138 std::vector<float> nn_distances;
00139
00140 for (size_t i = 0; i < indices.size (); ++i)
00141 {
00142 if (processed[i])
00143 continue;
00144
00145 std::vector<int> seed_queue;
00146 int sq_idx = 0;
00147 seed_queue.push_back (i);
00148
00149 processed[i] = true;
00150
00151 while (sq_idx < (int)seed_queue.size ())
00152 {
00153
00154 if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
00155 {
00156 sq_idx++;
00157 continue;
00158 }
00159
00160 for (size_t j = 1; j < nn_indices.size (); ++j)
00161 {
00162 if (processed[nn_indices[j]])
00163 continue;
00164
00165
00166 seed_queue.push_back (nn_indices[j]);
00167 processed[nn_indices[j]] = true;
00168 }
00169
00170 sq_idx++;
00171 }
00172
00173
00174 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00175 {
00176 pcl::PointIndices r;
00177 r.indices.resize (seed_queue.size ());
00178 for (size_t j = 0; j < seed_queue.size (); ++j)
00179
00180 r.indices[j] = indices[seed_queue[j]];
00181
00182
00183 sort (r.indices.begin (), r.indices.end ());
00184 r.indices.erase (unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00185
00186 r.header = cloud.header;
00187 clusters.push_back (r);
00188 }
00189 }
00190 }
00191
00195
00196 template <typename PointT> void
00197 pcl::EuclideanClusterExtraction<PointT>::extract (std::vector<PointIndices> &clusters)
00198 {
00199 if (!initCompute ())
00200 {
00201 clusters.clear ();
00202 return;
00203 }
00204
00205
00206 initTree (spatial_locator_, tree_);
00207
00208
00209 tree_->setInputCloud (input_, indices_);
00210 extractEuclideanClusters (*input_, *indices_, tree_, cluster_tolerance_, clusters, min_pts_per_cluster_, max_pts_per_cluster_);
00211
00212
00213
00214
00215 std::sort (clusters.rbegin (), clusters.rend (), comparePointClusters);
00216
00217 deinitCompute ();
00218 }
00219
00220 #define PCL_INSTANTIATE_EuclideanClusterExtraction(T) template class pcl::EuclideanClusterExtraction<T>;
00221 #define PCL_INSTANTIATE_extractEuclideanClusters(T) template void pcl::extractEuclideanClusters<T>(const pcl::PointCloud<T> &, const boost::shared_ptr<pcl::KdTree<T> > &, float , std::vector<pcl::PointIndices> &, unsigned int, unsigned int);
00222 #define PCL_INSTANTIATE_extractEuclideanClusters_indices(T) template void pcl::extractEuclideanClusters<T>(const pcl::PointCloud<T> &, const std::vector<int> &, const boost::shared_ptr<pcl::KdTree<T> > &, float , std::vector<pcl::PointIndices> &, unsigned int, unsigned int);
00223
00224 #endif // PCL_EXTRACT_CLUSTERS_IMPL_H_