00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2010-2011, 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_BILATERAL_H_ 00041 #define PCL_FILTERS_BILATERAL_H_ 00042 00043 #include <pcl/filters/filter.h> 00044 #include <pcl/search/pcl_search.h> 00045 00046 namespace pcl 00047 { 00056 template<typename PointT> 00057 class BilateralFilter : public Filter<PointT> 00058 { 00059 using Filter<PointT>::input_; 00060 using Filter<PointT>::indices_; 00061 typedef typename Filter<PointT>::PointCloud PointCloud; 00062 typedef typename pcl::search::Search<PointT>::Ptr KdTreePtr; 00063 00064 public: 00065 00066 typedef boost::shared_ptr< BilateralFilter<PointT> > Ptr; 00067 typedef boost::shared_ptr< const BilateralFilter<PointT> > ConstPtr; 00068 00069 00073 BilateralFilter () : sigma_s_ (0), 00074 sigma_r_ (std::numeric_limits<double>::max ()), 00075 tree_ () 00076 { 00077 } 00078 00079 00083 void 00084 applyFilter (PointCloud &output); 00085 00092 double 00093 computePointWeight (const int pid, const std::vector<int> &indices, const std::vector<float> &distances); 00094 00098 inline void 00099 setHalfSize (const double sigma_s) 00100 { sigma_s_ = sigma_s; } 00101 00103 inline double 00104 getHalfSize () const 00105 { return (sigma_s_); } 00106 00110 inline void 00111 setStdDev (const double sigma_r) 00112 { sigma_r_ = sigma_r;} 00113 00115 inline double 00116 getStdDev () const 00117 { return (sigma_r_); } 00118 00122 inline void 00123 setSearchMethod (const KdTreePtr &tree) 00124 { tree_ = tree; } 00125 00126 private: 00127 00132 inline double 00133 kernel (double x, double sigma) 00134 { return (exp (- (x*x)/(2*sigma*sigma))); } 00135 00137 double sigma_s_; 00139 double sigma_r_; 00140 00142 KdTreePtr tree_; 00143 }; 00144 } 00145 00146 #ifdef PCL_NO_PRECOMPILE 00147 #include <pcl/filters/impl/bilateral.hpp> 00148 #endif 00149 00150 #endif // PCL_FILTERS_BILATERAL_H_