Point Cloud Library (PCL)
1.7.0
|
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 the copyright holder(s) 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$ 00037 * 00038 */ 00039 00040 #ifndef PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ 00041 #define PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ 00042 00043 #include <pcl/filters/filter_indices.h> 00044 #include <pcl/search/pcl_search.h> 00045 00046 namespace pcl 00047 { 00048 /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. 00049 * \details The algorithm iterates through the entire input twice: 00050 * During the first iteration it will compute the average distance that each point has to its nearest k neighbors. 00051 * The value of k can be set using setMeanK(). 00052 * Next, the mean and standard deviation of all these distances are computed in order to determine a distance threshold. 00053 * The distance threshold will be equal to: mean + stddev_mult * stddev. 00054 * The multiplier for the standard deviation can be set using setStddevMulThresh(). 00055 * During the next iteration the points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively. 00056 * <br> 00057 * The neighbors found for each query point will be found amongst ALL points of setInputCloud(), not just those indexed by setIndices(). 00058 * The setIndices() method only indexes the points that will be iterated through as search query points. 00059 * <br><br> 00060 * For more information: 00061 * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz. 00062 * Towards 3D Point Cloud Based Object Maps for Household Environments 00063 * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008. 00064 * <br><br> 00065 * Usage example: 00066 * \code 00067 * pcl::StatisticalOutlierRemoval<PointType> sorfilter (true); // Initializing with true will allow us to extract the removed indices 00068 * sorfilter.setInputCloud (cloud_in); 00069 * sorfilter.setMeanK (8); 00070 * sorfilter.setStddevMulThresh (1.0); 00071 * sorfilter.filter (*cloud_out); 00072 * // The resulting cloud_out contains all points of cloud_in that have an average distance to their 8 nearest neighbors that is below the computed threshold 00073 * // Using a standard deviation multiplier of 1.0 and assuming the average distances are normally distributed there is a 84.1% chance that a point will be an inlier 00074 * indices_rem = sorfilter.getRemovedIndices (); 00075 * // The indices_rem array indexes all points of cloud_in that are outliers 00076 * \endcode 00077 * \author Radu Bogdan Rusu 00078 * \ingroup filters 00079 */ 00080 template<typename PointT> 00081 class StatisticalOutlierRemoval : public FilterIndices<PointT> 00082 { 00083 protected: 00084 typedef typename FilterIndices<PointT>::PointCloud PointCloud; 00085 typedef typename PointCloud::Ptr PointCloudPtr; 00086 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00087 typedef typename pcl::search::Search<PointT>::Ptr SearcherPtr; 00088 00089 public: 00090 00091 typedef boost::shared_ptr< StatisticalOutlierRemoval<PointT> > Ptr; 00092 typedef boost::shared_ptr< const StatisticalOutlierRemoval<PointT> > ConstPtr; 00093 00094 00095 /** \brief Constructor. 00096 * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). 00097 */ 00098 StatisticalOutlierRemoval (bool extract_removed_indices = false) : 00099 FilterIndices<PointT>::FilterIndices (extract_removed_indices), 00100 searcher_ (), 00101 mean_k_ (1), 00102 std_mul_ (0.0) 00103 { 00104 filter_name_ = "StatisticalOutlierRemoval"; 00105 } 00106 00107 /** \brief Set the number of nearest neighbors to use for mean distance estimation. 00108 * \param[in] nr_k The number of points to use for mean distance estimation. 00109 */ 00110 inline void 00111 setMeanK (int nr_k) 00112 { 00113 mean_k_ = nr_k; 00114 } 00115 00116 /** \brief Get the number of nearest neighbors to use for mean distance estimation. 00117 * \return The number of points to use for mean distance estimation. 00118 */ 00119 inline int 00120 getMeanK () 00121 { 00122 return (mean_k_); 00123 } 00124 00125 /** \brief Set the standard deviation multiplier for the distance threshold calculation. 00126 * \details The distance threshold will be equal to: mean + stddev_mult * stddev. 00127 * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively. 00128 * \param[in] stddev_mult The standard deviation multiplier. 00129 */ 00130 inline void 00131 setStddevMulThresh (double stddev_mult) 00132 { 00133 std_mul_ = stddev_mult; 00134 } 00135 00136 /** \brief Get the standard deviation multiplier for the distance threshold calculation. 00137 * \details The distance threshold will be equal to: mean + stddev_mult * stddev. 00138 * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively. 00139 * \param[in] stddev_mult The standard deviation multiplier. 00140 */ 00141 inline double 00142 getStddevMulThresh () 00143 { 00144 return (std_mul_); 00145 } 00146 00147 protected: 00148 using PCLBase<PointT>::input_; 00149 using PCLBase<PointT>::indices_; 00150 using Filter<PointT>::filter_name_; 00151 using Filter<PointT>::getClassName; 00152 using FilterIndices<PointT>::negative_; 00153 using FilterIndices<PointT>::keep_organized_; 00154 using FilterIndices<PointT>::user_filter_value_; 00155 using FilterIndices<PointT>::extract_removed_indices_; 00156 using FilterIndices<PointT>::removed_indices_; 00157 00158 /** \brief Filtered results are stored in a separate point cloud. 00159 * \param[out] output The resultant point cloud. 00160 */ 00161 void 00162 applyFilter (PointCloud &output); 00163 00164 /** \brief Filtered results are indexed by an indices array. 00165 * \param[out] indices The resultant indices. 00166 */ 00167 void 00168 applyFilter (std::vector<int> &indices) 00169 { 00170 applyFilterIndices (indices); 00171 } 00172 00173 /** \brief Filtered results are indexed by an indices array. 00174 * \param[out] indices The resultant indices. 00175 */ 00176 void 00177 applyFilterIndices (std::vector<int> &indices); 00178 00179 private: 00180 /** \brief A pointer to the spatial search object. */ 00181 SearcherPtr searcher_; 00182 00183 /** \brief The number of points to use for mean distance estimation. */ 00184 int mean_k_; 00185 00186 /** \brief Standard deviations threshold (i.e., points outside of 00187 * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */ 00188 double std_mul_; 00189 }; 00190 00191 /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more 00192 * information check: 00193 * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz. 00194 * Towards 3D Point Cloud Based Object Maps for Household Environments 00195 * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008. 00196 * 00197 * \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored. 00198 * \author Radu Bogdan Rusu 00199 * \ingroup filters 00200 */ 00201 template<> 00202 class PCL_EXPORTS StatisticalOutlierRemoval<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2> 00203 { 00204 using Filter<pcl::PCLPointCloud2>::filter_name_; 00205 using Filter<pcl::PCLPointCloud2>::getClassName; 00206 00207 using Filter<pcl::PCLPointCloud2>::removed_indices_; 00208 using Filter<pcl::PCLPointCloud2>::extract_removed_indices_; 00209 00210 typedef pcl::search::Search<pcl::PointXYZ> KdTree; 00211 typedef pcl::search::Search<pcl::PointXYZ>::Ptr KdTreePtr; 00212 00213 typedef pcl::PCLPointCloud2 PCLPointCloud2; 00214 typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; 00215 typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; 00216 00217 public: 00218 /** \brief Empty constructor. */ 00219 StatisticalOutlierRemoval (bool extract_removed_indices = false) : 00220 Filter<pcl::PCLPointCloud2>::Filter (extract_removed_indices), mean_k_ (2), 00221 std_mul_ (0.0), tree_ (), negative_ (false) 00222 { 00223 filter_name_ = "StatisticalOutlierRemoval"; 00224 } 00225 00226 /** \brief Set the number of points (k) to use for mean distance estimation 00227 * \param nr_k the number of points to use for mean distance estimation 00228 */ 00229 inline void 00230 setMeanK (int nr_k) 00231 { 00232 mean_k_ = nr_k; 00233 } 00234 00235 /** \brief Get the number of points to use for mean distance estimation. */ 00236 inline int 00237 getMeanK () 00238 { 00239 return (mean_k_); 00240 } 00241 00242 /** \brief Set the standard deviation multiplier threshold. All points outside the 00243 * \f[ \mu \pm \sigma \cdot std\_mul \f] 00244 * will be considered outliers, where \f$ \mu \f$ is the estimated mean, 00245 * and \f$ \sigma \f$ is the standard deviation. 00246 * \param std_mul the standard deviation multiplier threshold 00247 */ 00248 inline void 00249 setStddevMulThresh (double std_mul) 00250 { 00251 std_mul_ = std_mul; 00252 } 00253 00254 /** \brief Get the standard deviation multiplier threshold as set by the user. */ 00255 inline double 00256 getStddevMulThresh () 00257 { 00258 return (std_mul_); 00259 } 00260 00261 /** \brief Set whether the indices should be returned, or all points \e except the indices. 00262 * \param negative true if all points \e except the input indices will be returned, false otherwise 00263 */ 00264 inline void 00265 setNegative (bool negative) 00266 { 00267 negative_ = negative; 00268 } 00269 00270 /** \brief Get the value of the internal #negative_ parameter. If 00271 * true, all points \e except the input indices will be returned. 00272 * \return The value of the "negative" flag 00273 */ 00274 inline bool 00275 getNegative () 00276 { 00277 return (negative_); 00278 } 00279 00280 protected: 00281 /** \brief The number of points to use for mean distance estimation. */ 00282 int mean_k_; 00283 00284 /** \brief Standard deviations threshold (i.e., points outside of 00285 * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). 00286 */ 00287 double std_mul_; 00288 00289 /** \brief A pointer to the spatial search object. */ 00290 KdTreePtr tree_; 00291 00292 /** \brief If true, the outliers will be returned instead of the inliers (default: false). */ 00293 bool negative_; 00294 00295 void 00296 applyFilter (PCLPointCloud2 &output); 00297 }; 00298 } 00299 00300 #ifdef PCL_NO_PRECOMPILE 00301 #include <pcl/filters/impl/statistical_outlier_removal.hpp> 00302 #endif 00303 00304 #endif // PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ 00305