convolution.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-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_CONVOLUTION_H_
00041 #define PCL_FILTERS_CONVOLUTION_H_
00042 
00043 #include <pcl/common/eigen.h>
00044 #include <pcl/common/point_operators.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/exceptions.h>
00047 #include <pcl/pcl_base.h>
00048 
00049 namespace pcl
00050 {
00051   namespace filters
00052   {
00076     template <typename PointIn, typename PointOut>
00077     class Convolution
00078     {
00079       public:
00080         typedef typename pcl::PointCloud<PointIn> PointCloudIn;
00081         typedef typename PointCloudIn::Ptr PointCloudInPtr;
00082         typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00083         typedef typename pcl::PointCloud<PointOut> PointCloudOut;
00084         typedef boost::shared_ptr< Convolution<PointIn, PointOut> > Ptr;
00085         typedef boost::shared_ptr< const Convolution<PointIn, PointOut> > ConstPtr;
00086 
00087 
00089         enum BORDERS_POLICY
00090         {
00091           BORDERS_POLICY_IGNORE = -1,
00092           BORDERS_POLICY_MIRROR = 0,
00093           BORDERS_POLICY_DUPLICATE = 1
00094         };
00096         Convolution ();
00098         ~Convolution () {}
00103         inline void
00104         setInputCloud (const PointCloudInConstPtr& cloud) { input_ = cloud; }
00108         inline void
00109         setKernel (const Eigen::ArrayXf& kernel) { kernel_ = kernel; }
00111         void
00112         setBordersPolicy (int policy) { borders_policy_ = policy; }
00114         int
00115         getBordersPolicy () { return (borders_policy_); }
00123         inline void
00124         setDistanceThreshold (const float& threshold) { distance_threshold_ = threshold; }
00126         inline const float &
00127         getDistanceThreshold () const { return (distance_threshold_); }
00131         inline void
00132         setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00139         inline void
00140         convolveRows (PointCloudOut& output);
00147         inline void
00148         convolveCols (PointCloudOut& output);
00157         inline void
00158         convolve (const Eigen::ArrayXf& h_kernel, const Eigen::ArrayXf& v_kernel, PointCloudOut& output);
00164         inline void
00165         convolve (PointCloudOut& output);
00166 
00167       protected:
00169         void
00170         convolve_rows (PointCloudOut& output);
00172         void
00173         convolve_cols (PointCloudOut& output);
00175         void
00176         convolve_rows_mirror (PointCloudOut& output);
00178         void
00179         convolve_cols_mirror (PointCloudOut& output);
00181         void
00182         convolve_rows_duplicate (PointCloudOut& output);
00184         void
00185         convolve_cols_duplicate (PointCloudOut& output);
00190         void
00191         initCompute (PointCloudOut& output);
00192       private:
00196         inline PointOut
00197         convolveOneRowDense (int i, int j);
00201         inline PointOut
00202         convolveOneColDense (int i, int j);
00206         inline PointOut
00207         convolveOneRowNonDense (int i, int j);
00211         inline PointOut
00212         convolveOneColNonDense (int i, int j);
00213 
00215         int borders_policy_;
00217         float distance_threshold_;
00219         PointCloudInConstPtr input_;
00221         Eigen::ArrayXf kernel_;
00223         int half_width_;
00225         int kernel_width_;
00226       protected:
00228         unsigned int threads_;
00229 
00230         void
00231         makeInfinite (PointOut& p)
00232         {
00233           p.x = p.y = p.z = std::numeric_limits<float>::quiet_NaN ();
00234         }      
00235     };
00236   }
00237 }
00238 
00239 #include <pcl/filters/impl/convolution.hpp>
00240 
00241 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:55