radius_outlier_removal.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: radius_outlier_removal.h 6144 2012-07-04 22:06:28Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_
00041 #define PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_
00042 
00043 #include <pcl/filters/filter_indices.h>
00044 #include <pcl/search/pcl_search.h>
00045 
00046 namespace pcl
00047 {
00071   template<typename PointT>
00072   class RadiusOutlierRemoval : public FilterIndices<PointT>
00073   {
00074     protected:
00075       typedef typename FilterIndices<PointT>::PointCloud PointCloud;
00076       typedef typename PointCloud::Ptr PointCloudPtr;
00077       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00078       typedef typename pcl::search::Search<PointT>::Ptr SearcherPtr;
00079 
00080     public:
00084       RadiusOutlierRemoval (bool extract_removed_indices = false) :
00085         FilterIndices<PointT>::FilterIndices (extract_removed_indices),
00086         searcher_ (),
00087         search_radius_ (0.0),
00088         min_pts_radius_ (1)
00089       {
00090         filter_name_ = "RadiusOutlierRemoval";
00091       }
00092 
00098       inline void
00099       setRadiusSearch (double radius)
00100       {
00101         search_radius_ = radius;
00102       }
00103 
00109       inline double
00110       getRadiusSearch ()
00111       {
00112         return (search_radius_);
00113       }
00114 
00120       inline void
00121       setMinNeighborsInRadius (int min_pts)
00122       {
00123         min_pts_radius_ = min_pts;
00124       }
00125 
00131       inline int
00132       getMinNeighborsInRadius ()
00133       {
00134         return (min_pts_radius_);
00135       }
00136 
00137     protected:
00138       using PCLBase<PointT>::input_;
00139       using PCLBase<PointT>::indices_;
00140       using Filter<PointT>::filter_name_;
00141       using Filter<PointT>::getClassName;
00142       using FilterIndices<PointT>::negative_;
00143       using FilterIndices<PointT>::keep_organized_;
00144       using FilterIndices<PointT>::user_filter_value_;
00145       using FilterIndices<PointT>::extract_removed_indices_;
00146       using FilterIndices<PointT>::removed_indices_;
00147 
00151       void
00152       applyFilter (PointCloud &output);
00153 
00157       void
00158       applyFilter (std::vector<int> &indices)
00159       {
00160         applyFilterIndices (indices);
00161       }
00162 
00166       void
00167       applyFilterIndices (std::vector<int> &indices);
00168 
00169     private:
00171       SearcherPtr searcher_;
00172 
00174       double search_radius_;
00175 
00177       int min_pts_radius_;
00178   };
00179 
00181 
00187   template<>
00188   class PCL_EXPORTS RadiusOutlierRemoval<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2>
00189   {
00190     using Filter<sensor_msgs::PointCloud2>::filter_name_;
00191     using Filter<sensor_msgs::PointCloud2>::getClassName;
00192 
00193     using Filter<sensor_msgs::PointCloud2>::removed_indices_;
00194     using Filter<sensor_msgs::PointCloud2>::extract_removed_indices_;
00195 
00196     typedef pcl::search::Search<pcl::PointXYZ> KdTree;
00197     typedef pcl::search::Search<pcl::PointXYZ>::Ptr KdTreePtr;
00198 
00199     typedef sensor_msgs::PointCloud2 PointCloud2;
00200     typedef PointCloud2::Ptr PointCloud2Ptr;
00201     typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
00202 
00203     public:
00205       RadiusOutlierRemoval (bool extract_removed_indices = false) :
00206         Filter<sensor_msgs::PointCloud2>::Filter (extract_removed_indices), 
00207         search_radius_ (0.0), min_pts_radius_ (1), tree_ ()
00208       {
00209         filter_name_ = "RadiusOutlierRemoval";
00210       }
00211 
00215       inline void
00216       setRadiusSearch (double radius)
00217       {
00218         search_radius_ = radius;
00219       }
00220 
00222       inline double
00223       getRadiusSearch ()
00224       {
00225         return (search_radius_);
00226       }
00227 
00232       inline void
00233       setMinNeighborsInRadius (int min_pts)
00234       {
00235         min_pts_radius_ = min_pts;
00236       }
00237 
00241       inline double
00242       getMinNeighborsInRadius ()
00243       {
00244         return (min_pts_radius_);
00245       }
00246 
00247     protected:
00249       double search_radius_;
00250 
00254       int min_pts_radius_;
00255 
00257       KdTreePtr tree_;
00258 
00259       void
00260       applyFilter (PointCloud2 &output);
00261   };
00262 }
00263 
00264 #endif  // PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_
00265 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:33