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 #include "pcl/impl/instantiate.hpp"
00039 #include "pcl/point_types.h"
00040 #include "pcl/filters/statistical_outlier_removal.h"
00041 #include "pcl/filters/impl/statistical_outlier_removal.hpp"
00042 #include "pcl/ros/conversions.h"
00043
00045 void
00046 pcl::StatisticalOutlierRemoval<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00047 {
00048 output.is_dense = true;
00049
00050 if (x_idx_ == -1 || y_idx_ == -1 || z_idx_ == -1)
00051 {
00052 ROS_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!", getClassName ().c_str ());
00053 output.width = output.height = 0;
00054 output.data.clear ();
00055 return;
00056 }
00057
00058 if (std_mul_ == 0.0)
00059 {
00060 ROS_ERROR ("[pcl::%s::applyFilter] Standard deviation multipler not set!", getClassName ().c_str ());
00061 output.width = output.height = 0;
00062 output.data.clear ();
00063 return;
00064 }
00065
00066
00067
00068
00069
00070 tree_.reset (new pcl::KdTreeFLANN<pcl::PointXYZ>);
00071
00072
00073 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00074 pcl::fromROSMsg (*input_, *cloud);
00075 tree_->setInputCloud (cloud);
00076
00077
00078 std::vector<int> nn_indices (mean_k_);
00079 std::vector<float> nn_dists (mean_k_);
00080
00081 std::vector<float> distances (indices_->size ());
00082
00083 for (size_t cp = 0; cp < indices_->size (); ++cp)
00084 {
00085 if (!pcl_isfinite (cloud->points[(*indices_)[cp]].x) ||
00086 !pcl_isfinite (cloud->points[(*indices_)[cp]].y) ||
00087 !pcl_isfinite (cloud->points[(*indices_)[cp]].z))
00088 {
00089 distances[cp] = 0;
00090 continue;
00091 }
00092
00093 if (tree_->nearestKSearch ((*indices_)[cp], mean_k_, nn_indices, nn_dists) == 0)
00094 {
00095 distances[cp] = 0;
00096 ROS_WARN ("[pcl::%s::applyFilter] Searching for the closest %d neighbors failed.", getClassName ().c_str (), mean_k_);
00097 continue;
00098 }
00099
00100
00101 double dist_sum = 0;
00102 for (int j = 1; j < mean_k_; ++j)
00103 dist_sum += sqrt (nn_dists[j]);
00104 distances[cp] = dist_sum / (mean_k_-1);
00105 }
00106
00107
00108 double mean, stddev;
00109 getMeanStd (distances, mean, stddev);
00110 double distance_threshold = mean + std_mul_ * stddev;
00111
00112
00113 output.is_bigendian = input_->is_bigendian;
00114 output.point_step = input_->point_step;
00115 output.height = 1;
00116
00117 output.data.resize (indices_->size () * input_->point_step);
00118
00119
00120 int nr_p = 0;
00121 for (size_t cp = 0; cp < indices_->size (); ++cp)
00122 {
00123 if (negative_)
00124 {
00125 if (distances[cp] <= distance_threshold)
00126 continue;
00127 }
00128 else
00129 {
00130 if (distances[cp] > distance_threshold)
00131 continue;
00132 }
00133
00134 memcpy (&output.data[nr_p * output.point_step], &input_->data[(*indices_)[cp] * output.point_step], output.point_step);
00135 nr_p++;
00136 }
00137 output.width = nr_p;
00138 output.data.resize (output.width * output.point_step);
00139 output.row_step = output.point_step * output.width;
00140 }
00141
00142
00143 PCL_INSTANTIATE(StatisticalOutlierRemoval, PCL_XYZ_POINT_TYPES);
00144