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<search::Search<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 PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!\n", 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 (int i = 0; i < static_cast<int> (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 < static_cast<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 (nn_indices[j] == -1 || 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
00104 std::sort (r.indices.begin (), r.indices.end ());
00105 r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00106
00107 r.header = cloud.header;
00108 clusters.push_back (r);
00109 }
00110 }
00111 }
00112
00114
00115 template <typename PointT> void
00116 pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
00117 const std::vector<int> &indices,
00118 const boost::shared_ptr<search::Search<PointT> > &tree,
00119 float tolerance, std::vector<PointIndices> &clusters,
00120 unsigned int min_pts_per_cluster,
00121 unsigned int max_pts_per_cluster)
00122 {
00123
00124
00125 if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00126 {
00127 PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ());
00128 return;
00129 }
00130 if (tree->getIndices ()->size () != indices.size ())
00131 {
00132 PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different set of indices (%zu) than the input set (%zu)!\n", tree->getIndices ()->size (), indices.size ());
00133 return;
00134 }
00135
00136
00137 std::vector<bool> processed (cloud.points.size (), false);
00138
00139 std::vector<int> nn_indices;
00140 std::vector<float> nn_distances;
00141
00142 for (int i = 0; i < static_cast<int> (indices.size ()); ++i)
00143 {
00144 if (processed[indices[i]])
00145 continue;
00146
00147 std::vector<int> seed_queue;
00148 int sq_idx = 0;
00149 seed_queue.push_back (indices[i]);
00150
00151 processed[indices[i]] = true;
00152
00153 while (sq_idx < static_cast<int> (seed_queue.size ()))
00154 {
00155
00156 int ret = tree->radiusSearch (cloud.points[seed_queue[sq_idx]], tolerance, nn_indices, nn_distances);
00157 if( ret == -1)
00158 {
00159 PCL_ERROR("[pcl::extractEuclideanClusters] Received error code -1 from radiusSearch\n");
00160 exit(0);
00161 }
00162 if (!ret)
00163 {
00164 sq_idx++;
00165 continue;
00166 }
00167
00168 for (size_t j = 1; j < nn_indices.size (); ++j)
00169 {
00170 if (nn_indices[j] == -1 || processed[nn_indices[j]])
00171 continue;
00172
00173
00174 seed_queue.push_back (nn_indices[j]);
00175 processed[nn_indices[j]] = true;
00176 }
00177
00178 sq_idx++;
00179 }
00180
00181
00182 if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00183 {
00184 pcl::PointIndices r;
00185 r.indices.resize (seed_queue.size ());
00186 for (size_t j = 0; j < seed_queue.size (); ++j)
00187
00188 r.indices[j] = seed_queue[j];
00189
00190
00191
00192 std::sort (r.indices.begin (), r.indices.end ());
00193 r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00194
00195 r.header = cloud.header;
00196 clusters.push_back (r);
00197 }
00198 }
00199 }
00200
00204
00205 template <typename PointT> void
00206 pcl::EuclideanClusterExtraction<PointT>::extract (std::vector<PointIndices> &clusters)
00207 {
00208 if (!initCompute () ||
00209 (input_ != 0 && input_->points.empty ()) ||
00210 (indices_ != 0 && indices_->empty ()))
00211 {
00212 clusters.clear ();
00213 return;
00214 }
00215
00216
00217 if (!tree_)
00218 {
00219 if (input_->isOrganized ())
00220 tree_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
00221 else
00222 tree_.reset (new pcl::search::KdTree<PointT> (false));
00223 }
00224
00225
00226 tree_->setInputCloud (input_, indices_);
00227 extractEuclideanClusters (*input_, *indices_, tree_, static_cast<float> (cluster_tolerance_), clusters, min_pts_per_cluster_, max_pts_per_cluster_);
00228
00229
00230
00231
00232
00233 std::sort (clusters.rbegin (), clusters.rend (), comparePointClusters);
00234
00235 deinitCompute ();
00236 }
00237
00238 #define PCL_INSTANTIATE_EuclideanClusterExtraction(T) template class PCL_EXPORTS pcl::EuclideanClusterExtraction<T>;
00239 #define PCL_INSTANTIATE_extractEuclideanClusters(T) template void PCL_EXPORTS pcl::extractEuclideanClusters<T>(const pcl::PointCloud<T> &, const boost::shared_ptr<pcl::search::Search<T> > &, float , std::vector<pcl::PointIndices> &, unsigned int, unsigned int);
00240 #define PCL_INSTANTIATE_extractEuclideanClusters_indices(T) template void PCL_EXPORTS pcl::extractEuclideanClusters<T>(const pcl::PointCloud<T> &, const std::vector<int> &, const boost::shared_ptr<pcl::search::Search<T> > &, float , std::vector<pcl::PointIndices> &, unsigned int, unsigned int);
00241
00242 #endif // PCL_EXTRACT_CLUSTERS_IMPL_H_