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
00038 #ifndef PCL_ROS_FILTERS_STATISTICALOUTLIERREMOVAL_H_
00039 #define PCL_ROS_FILTERS_STATISTICALOUTLIERREMOVAL_H_
00040
00041
00042 #include <pcl/filters/statistical_outlier_removal.h>
00043 #include "pcl_ros/filters/filter.h"
00044
00045
00046 #include "pcl_ros/StatisticalOutlierRemovalConfig.h"
00047
00048 namespace pcl_ros
00049 {
00061 class StatisticalOutlierRemoval : public Filter
00062 {
00063 protected:
00065 boost::shared_ptr <dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig> > srv_;
00066
00072 inline void
00073 filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
00074 PointCloud2 &output)
00075 {
00076 boost::mutex::scoped_lock lock (mutex_);
00077 pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
00078 pcl_conversions::toPCL(*(input), *(pcl_input));
00079 impl_.setInputCloud (pcl_input);
00080 impl_.setIndices (indices);
00081 pcl::PCLPointCloud2 pcl_output;
00082 impl_.filter (pcl_output);
00083 pcl_conversions::moveFromPCL(pcl_output, output);
00084 }
00085
00090 bool child_init (ros::NodeHandle &nh, bool &has_service);
00091
00096 void config_callback (pcl_ros::StatisticalOutlierRemovalConfig &config, uint32_t level);
00097
00098 private:
00100 pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2> impl_;
00101 public:
00102 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00103 };
00104 }
00105
00106 #endif //#ifndef PCL_FILTERS_STATISTICALOUTLIERREMOVAL_H_