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_FILTERS_IMPL_STATISTICAL_OUTLIER_REMOVAL_H_
00039 #define PCL_FILTERS_IMPL_STATISTICAL_OUTLIER_REMOVAL_H_
00040
00041 #include "pcl/filters/statistical_outlier_removal.h"
00042
00044 template <typename PointT> void
00045 pcl::StatisticalOutlierRemoval<PointT>::applyFilter (PointCloud &output)
00046 {
00047 if (std_mul_ == 0.0)
00048 {
00049 ROS_ERROR ("[pcl::%s::applyFilter] Standard deviation multipler not set!", getClassName ().c_str ());
00050 output.width = output.height = 0;
00051 output.points.clear ();
00052 return;
00053 }
00054
00055
00056
00057
00058
00059 tree_.reset (new KdTreeFLANN<PointT> ());
00060
00061
00062 tree_->setInputCloud (input_);
00063
00064
00065 std::vector<int> nn_indices (mean_k_);
00066 std::vector<float> nn_dists (mean_k_);
00067
00068 std::vector<float> distances (indices_->size ());
00069
00070 for (size_t cp = 0; cp < indices_->size (); ++cp)
00071 {
00072 if (!pcl_isfinite (input_->points[(*indices_)[cp]].x) ||
00073 !pcl_isfinite (input_->points[(*indices_)[cp]].y) ||
00074 !pcl_isfinite (input_->points[(*indices_)[cp]].z))
00075 {
00076 distances[cp] = 0;
00077 continue;
00078 }
00079
00080 if (tree_->nearestKSearch ((*indices_)[cp], mean_k_, nn_indices, nn_dists) == 0)
00081 {
00082 distances[cp] = 0;
00083 ROS_WARN ("[pcl::%s::applyFilter] Searching for the closest %d neighbors failed.", getClassName ().c_str (), mean_k_);
00084 continue;
00085 }
00086
00087
00088 double dist_sum = 0;
00089 for (int j = 1; j < mean_k_; ++j)
00090 dist_sum += sqrt (nn_dists[j]);
00091 distances[cp] = dist_sum / (mean_k_-1);
00092 }
00093
00094
00095 double mean, stddev;
00096 getMeanStd (distances, mean, stddev);
00097 double distance_threshold = mean + std_mul_ * stddev;
00098
00099 output.points.resize (input_->points.size ());
00100
00101 int nr_p = 0;
00102 for (size_t cp = 0; cp < indices_->size (); ++cp)
00103 {
00104 if (negative_)
00105 {
00106 if (distances[cp] <= distance_threshold)
00107 continue;
00108 }
00109 else
00110 {
00111 if (distances[cp] > distance_threshold)
00112 continue;
00113 }
00114
00115 output.points[nr_p++] = input_->points[(*indices_)[cp]];
00116 }
00117 output.points.resize (nr_p);
00118 output.width = nr_p;
00119 output.height = 1;
00120 output.is_dense = true;
00121 }
00122
00123 #define PCL_INSTANTIATE_StatisticalOutlierRemoval(T) template class pcl::StatisticalOutlierRemoval<T>;
00124
00125 #endif // PCL_FILTERS_IMPL_STATISTICAL_OUTLIER_REMOVAL_H_
00126