Point Cloud Library (PCL)
1.3.1
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: radius_outlier_removal.h 3028 2011-11-01 04:12:17Z rusu $ 00035 * 00036 */ 00037 00038 #ifndef PCL_FILTERS_RADIUSOUTLIERREMOVAL_H_ 00039 #define PCL_FILTERS_RADIUSOUTLIERREMOVAL_H_ 00040 00041 #include "pcl/filters/filter.h" 00042 #include "pcl/point_types.h" 00043 #include "pcl/search/pcl_search.h" 00044 00045 namespace pcl 00046 { 00048 00054 template<typename PointT> 00055 class RadiusOutlierRemoval : public Filter<PointT> 00056 { 00057 using Filter<PointT>::input_; 00058 using Filter<PointT>::indices_; 00059 using Filter<PointT>::filter_name_; 00060 using Filter<PointT>::getClassName; 00061 00062 using Filter<PointT>::removed_indices_; 00063 using Filter<PointT>::extract_removed_indices_; 00064 00065 typedef typename pcl::search::Search<PointT> KdTree; 00066 typedef typename pcl::search::Search<PointT>::Ptr KdTreePtr; 00067 00068 typedef typename Filter<PointT>::PointCloud PointCloud; 00069 typedef typename PointCloud::Ptr PointCloudPtr; 00070 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00071 00072 public: 00074 RadiusOutlierRemoval (bool extract_removed_indices = false) : 00075 Filter<PointT>::Filter (extract_removed_indices), search_radius_ (0.0), min_pts_radius_ (1), tree_ () 00076 { 00077 filter_name_ = "RadiusOutlierRemoval"; 00078 } 00079 ; 00080 00084 inline void 00085 setRadiusSearch (double radius) 00086 { 00087 search_radius_ = radius; 00088 } 00089 00091 inline double 00092 getRadiusSearch () 00093 { 00094 return (search_radius_); 00095 } 00096 00101 inline void 00102 setMinNeighborsInRadius (int min_pts) 00103 { 00104 min_pts_radius_ = min_pts; 00105 } 00106 00110 inline double 00111 getMinNeighborsInRadius () 00112 { 00113 return (min_pts_radius_); 00114 } 00115 00116 protected: 00118 double search_radius_; 00119 00123 int min_pts_radius_; 00124 00126 KdTreePtr tree_; 00127 00131 void 00132 applyFilter (PointCloud &output); 00133 }; 00134 00136 00142 template<> 00143 class PCL_EXPORTS RadiusOutlierRemoval<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2> 00144 { 00145 using Filter<sensor_msgs::PointCloud2>::filter_name_; 00146 using Filter<sensor_msgs::PointCloud2>::getClassName; 00147 00148 using Filter<sensor_msgs::PointCloud2>::removed_indices_; 00149 using Filter<sensor_msgs::PointCloud2>::extract_removed_indices_; 00150 00151 typedef pcl::search::Search<pcl::PointXYZ> KdTree; 00152 typedef pcl::search::Search<pcl::PointXYZ>::Ptr KdTreePtr; 00153 00154 typedef sensor_msgs::PointCloud2 PointCloud2; 00155 typedef PointCloud2::Ptr PointCloud2Ptr; 00156 typedef PointCloud2::ConstPtr PointCloud2ConstPtr; 00157 00158 public: 00160 RadiusOutlierRemoval (bool extract_removed_indices = false) : 00161 Filter<sensor_msgs::PointCloud2>::Filter (extract_removed_indices), 00162 search_radius_ (0.0), min_pts_radius_ (1), tree_ () 00163 { 00164 filter_name_ = "RadiusOutlierRemoval"; 00165 } 00166 00170 inline void 00171 setRadiusSearch (double radius) 00172 { 00173 search_radius_ = radius; 00174 } 00175 00177 inline double 00178 getRadiusSearch () 00179 { 00180 return (search_radius_); 00181 } 00182 00187 inline void 00188 setMinNeighborsInRadius (int min_pts) 00189 { 00190 min_pts_radius_ = min_pts; 00191 } 00192 00196 inline double 00197 getMinNeighborsInRadius () 00198 { 00199 return (min_pts_radius_); 00200 } 00201 00202 protected: 00204 double search_radius_; 00205 00209 int min_pts_radius_; 00210 00212 KdTreePtr tree_; 00213 00214 void 00215 applyFilter (PointCloud2 &output); 00216 }; 00217 } 00218 00219 #endif //#ifndef PCL_FILTERS_RADIUSOUTLIERREMOVAL_H_