fast_bilateral.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) 2012-, Open Perception, Inc.
00006  * Copyright (c) 2004, Sylvain Paris and Francois Sillion
00007 
00008  * All rights reserved.
00009 
00010  * Redistribution and use in source and binary forms, with or without
00011  * modification, are permitted provided that the following conditions
00012  * are met:
00013  *
00014  *  * Redistributions of source code must retain the above copyright
00015  *    notice, this list of conditions and the following disclaimer.
00016  *  * Redistributions in binary form must reproduce the above
00017  *    copyright notice, this list of conditions and the following
00018  *    disclaimer in the documentation and/or other materials provided
00019  *    with the distribution.
00020  * * Neither the name of the copyright holder(s) nor the names of its
00021  *    contributors may be used to endorse or promote products derived
00022  *    from this software without specific prior written permission.
00023  *
00024  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  * POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 
00042 #ifndef PCL_FILTERS_FAST_BILATERAL_H_
00043 #define PCL_FILTERS_FAST_BILATERAL_H_
00044 
00045 #include <pcl/filters/filter.h>
00046 
00047 namespace pcl
00048 {
00057   template<typename PointT>
00058   class FastBilateralFilter : public Filter<PointT>
00059   {
00060     protected:
00061       using Filter<PointT>::input_;
00062       typedef typename Filter<PointT>::PointCloud PointCloud;
00063 
00064     public:
00065     
00066       typedef boost::shared_ptr< FastBilateralFilter<PointT> > Ptr;
00067       typedef boost::shared_ptr< const FastBilateralFilter<PointT> > ConstPtr;
00068 
00070       FastBilateralFilter ()
00071         : sigma_s_ (15.0f)
00072         , sigma_r_ (0.05f)
00073         , early_division_ (false)
00074       { }
00075       
00077       virtual ~FastBilateralFilter () {}
00078 
00083       inline void
00084       setSigmaS (float sigma_s)
00085       { sigma_s_ = sigma_s; }
00086 
00088       inline float
00089       getSigmaS () const
00090       { return sigma_s_; }
00091 
00092 
00097       inline void
00098       setSigmaR (float sigma_r)
00099       { sigma_r_ = sigma_r; }
00100 
00102       inline float
00103       getSigmaR () const
00104       { return sigma_r_; }
00105 
00109       virtual void
00110       applyFilter (PointCloud &output);
00111 
00112     protected:
00113       float sigma_s_;
00114       float sigma_r_;
00115       bool early_division_;
00116 
00117       class Array3D
00118       {
00119         public:
00120           Array3D (const size_t width, const size_t height, const size_t depth)
00121           {
00122             x_dim_ = width;
00123             y_dim_ = height;
00124             z_dim_ = depth;
00125             v_ = std::vector<Eigen::Vector2f> (width*height*depth, Eigen::Vector2f (0.0f, 0.0f));
00126           }
00127 
00128           inline Eigen::Vector2f&
00129           operator () (const size_t x, const size_t y, const size_t z)
00130           { return v_[(x * y_dim_ + y) * z_dim_ + z]; }
00131 
00132           inline const Eigen::Vector2f&
00133           operator () (const size_t x, const size_t y, const size_t z) const
00134           { return v_[(x * y_dim_ + y) * z_dim_ + z]; }
00135 
00136           inline void
00137           resize (const size_t width, const size_t height, const size_t depth)
00138           {
00139             x_dim_ = width;
00140             y_dim_ = height;
00141             z_dim_ = depth;
00142             v_.resize (x_dim_ * y_dim_ * z_dim_);
00143           }
00144 
00145           Eigen::Vector2f
00146           trilinear_interpolation (const float x,
00147                                    const float y,
00148                                    const float z);
00149 
00150           static inline size_t
00151           clamp (const size_t min_value,
00152                  const size_t max_value,
00153                  const size_t x);
00154 
00155           inline size_t
00156           x_size () const
00157           { return x_dim_; }
00158 
00159           inline size_t
00160           y_size () const
00161           { return y_dim_; }
00162 
00163           inline size_t
00164           z_size () const
00165           { return z_dim_; }
00166 
00167           inline std::vector<Eigen::Vector2f >::iterator
00168           begin ()
00169           { return v_.begin (); }
00170 
00171           inline std::vector<Eigen::Vector2f >::iterator
00172           end ()
00173           { return v_.end (); }
00174 
00175           inline std::vector<Eigen::Vector2f >::const_iterator
00176           begin () const
00177           { return v_.begin (); }
00178 
00179           inline std::vector<Eigen::Vector2f >::const_iterator
00180           end () const
00181           { return v_.end (); }
00182 
00183         private:
00184           std::vector<Eigen::Vector2f > v_;
00185           size_t x_dim_, y_dim_, z_dim_;
00186       };
00187 
00188 
00189   };
00190 }
00191 
00192 #ifdef PCL_NO_PRECOMPILE
00193 #include <pcl/filters/impl/fast_bilateral.hpp>
00194 #else
00195 #define PCL_INSTANTIATE_FastBilateralFilter(T) template class PCL_EXPORTS pcl::FastBilateralFilter<T>;
00196 #endif
00197 
00198 
00199 #endif /* PCL_FILTERS_FAST_BILATERAL_H_ */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:56