Go to the documentation of this file.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 #ifndef PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_
00038 #define PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_
00039
00040 #include <pcl/segmentation/conditional_euclidean_clustering.h>
00041
00042 template<typename PointT> void
00043 pcl::ConditionalEuclideanClustering<PointT>::segment (pcl::IndicesClusters &clusters)
00044 {
00045
00046 clusters.clear ();
00047 if (extract_removed_clusters_)
00048 {
00049 small_clusters_->clear ();
00050 large_clusters_->clear ();
00051 }
00052
00053
00054 if (!initCompute () || input_->points.empty () || indices_->empty () || !condition_function_)
00055 return;
00056
00057
00058 if (!searcher_)
00059 {
00060 if (input_->isOrganized ())
00061 searcher_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
00062 else
00063 searcher_.reset (new pcl::search::KdTree<PointT> ());
00064 }
00065 searcher_->setInputCloud (input_, indices_);
00066
00067
00068 std::vector<int> nn_indices;
00069 std::vector<float> nn_distances;
00070
00071
00072
00073 std::vector<bool> processed (input_->points.size (), false);
00074
00075
00076 for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)
00077 {
00078
00079 if ((*indices_)[iii] == -1 || processed[(*indices_)[iii]])
00080 continue;
00081
00082
00083 std::vector<int> current_cluster;
00084 int cii = 0;
00085
00086
00087 current_cluster.push_back ((*indices_)[iii]);
00088 processed[(*indices_)[iii]] = true;
00089
00090
00091 while (cii < static_cast<int> (current_cluster.size ()))
00092 {
00093
00094 if (searcher_->radiusSearch (input_->points[current_cluster[cii]], cluster_tolerance_, nn_indices, nn_distances) < 1)
00095 {
00096 cii++;
00097 continue;
00098 }
00099
00100
00101 for (int nii = 1; nii < static_cast<int> (nn_indices.size ()); ++nii)
00102 {
00103
00104 if (nn_indices[nii] == -1 || processed[nn_indices[nii]])
00105 continue;
00106
00107
00108 if (condition_function_ (input_->points[current_cluster[cii]], input_->points[nn_indices[nii]], nn_distances[nii]))
00109 {
00110
00111 current_cluster.push_back (nn_indices[nii]);
00112 processed[nn_indices[nii]] = true;
00113 }
00114 }
00115 cii++;
00116 }
00117
00118
00119 if (extract_removed_clusters_ || (current_cluster.size () >= min_cluster_size_ && current_cluster.size () <= max_cluster_size_))
00120 {
00121 pcl::PointIndices pi;
00122 pi.header = input_->header;
00123 pi.indices.resize (current_cluster.size ());
00124 for (int ii = 0; ii < static_cast<int> (current_cluster.size ()); ++ii)
00125 pi.indices[ii] = current_cluster[ii];
00126
00127 if (extract_removed_clusters_ && current_cluster.size () < min_cluster_size_)
00128 small_clusters_->push_back (pi);
00129 else if (extract_removed_clusters_ && current_cluster.size () > max_cluster_size_)
00130 large_clusters_->push_back (pi);
00131 else
00132 clusters.push_back (pi);
00133 }
00134 }
00135
00136 deinitCompute ();
00137 }
00138
00139 #define PCL_INSTANTIATE_ConditionalEuclideanClustering(T) template class PCL_EXPORTS pcl::ConditionalEuclideanClustering<T>;
00140
00141 #endif // PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_
00142