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: fast_bilateral_omp.h 8379 2013-01-02 23:12:21Z sdmiller $ 00038 * 00039 */ 00040 00041 00042 #ifndef PCL_FILTERS_FAST_BILATERAL_OMP_H_ 00043 #define PCL_FILTERS_FAST_BILATERAL_OMP_H_ 00044 00045 #include <pcl/filters/filter.h> 00046 #include <pcl/filters/fast_bilateral.h> 00047 00048 namespace pcl 00049 { 00058 template<typename PointT> 00059 class FastBilateralFilterOMP : public FastBilateralFilter<PointT> 00060 { 00061 protected: 00062 using FastBilateralFilter<PointT>::input_; 00063 using FastBilateralFilter<PointT>::sigma_s_; 00064 using FastBilateralFilter<PointT>::sigma_r_; 00065 using FastBilateralFilter<PointT>::early_division_; 00066 typedef typename FastBilateralFilter<PointT>::Array3D Array3D; 00067 00068 typedef typename Filter<PointT>::PointCloud PointCloud; 00069 00070 public: 00071 00072 typedef boost::shared_ptr< FastBilateralFilterOMP<PointT> > Ptr; 00073 typedef boost::shared_ptr< const FastBilateralFilterOMP<PointT> > ConstPtr; 00074 00076 FastBilateralFilterOMP (unsigned int nr_threads = 0) 00077 : threads_ (nr_threads) 00078 { } 00079 00083 inline void 00084 setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } 00085 00089 void 00090 applyFilter (PointCloud &output); 00091 00092 protected: 00094 unsigned int threads_; 00095 00096 }; 00097 } 00098 00099 #ifdef PCL_NO_PRECOMPILE 00100 #include <pcl/filters/impl/fast_bilateral_omp.hpp> 00101 #else 00102 #define PCL_INSTANTIATE_FastBilateralFilterOMP(T) template class PCL_EXPORTS pcl::FastBilateralFilterOMP<T>; 00103 #endif 00104 00105 00106 #endif /* PCL_FILTERS_FAST_BILATERAL_OMP_H_ */ 00107