normal_space.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  * 
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  */
00037 
00038 #ifndef PCL_FILTERS_NORMAL_SUBSAMPLE_H_
00039 #define PCL_FILTERS_NORMAL_SUBSAMPLE_H_
00040 
00041 #include <pcl/filters/boost.h>
00042 #include <pcl/filters/filter_indices.h>
00043 #include <time.h>
00044 #include <limits.h>
00045 
00046 namespace pcl
00047 {
00051   template<typename PointT, typename NormalT>
00052   class NormalSpaceSampling : public FilterIndices<PointT>
00053   {
00054     using FilterIndices<PointT>::filter_name_;
00055     using FilterIndices<PointT>::getClassName;
00056     using FilterIndices<PointT>::indices_;
00057     using FilterIndices<PointT>::input_;
00058     using FilterIndices<PointT>::keep_organized_;
00059     using FilterIndices<PointT>::extract_removed_indices_;
00060     using FilterIndices<PointT>::removed_indices_;
00061     using FilterIndices<PointT>::user_filter_value_;
00062 
00063     typedef typename FilterIndices<PointT>::PointCloud PointCloud;
00064     typedef typename PointCloud::Ptr PointCloudPtr;
00065     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00066     typedef typename pcl::PointCloud<NormalT>::ConstPtr NormalsConstPtr;
00067 
00068     public:
00069       
00070       typedef boost::shared_ptr<NormalSpaceSampling<PointT, NormalT> > Ptr;
00071       typedef boost::shared_ptr<const NormalSpaceSampling<PointT, NormalT> > ConstPtr;
00072 
00074       NormalSpaceSampling ()
00075         : sample_ (std::numeric_limits<unsigned int>::max ())
00076         , seed_ (static_cast<unsigned int> (time (NULL)))
00077         , binsx_ ()
00078         , binsy_ ()
00079         , binsz_ ()
00080         , input_normals_ ()
00081         , rng_uniform_distribution_ (NULL)
00082       {
00083         filter_name_ = "NormalSpaceSampling";
00084       }
00085 
00087       ~NormalSpaceSampling ()
00088       {
00089         if (rng_uniform_distribution_ != NULL)
00090           delete rng_uniform_distribution_;
00091       }
00092 
00096       inline void
00097       setSample (unsigned int sample)
00098       { sample_ = sample; }
00099 
00101       inline unsigned int
00102       getSample () const
00103       { return (sample_); }
00104 
00108       inline void
00109       setSeed (unsigned int seed)
00110       { seed_ = seed; }
00111 
00113       inline unsigned int
00114       getSeed () const
00115       { return (seed_); }
00116 
00122       inline void 
00123       setBins (unsigned int binsx, unsigned int binsy, unsigned int binsz)
00124       {
00125         binsx_ = binsx;
00126         binsy_ = binsy;
00127         binsz_ = binsz;
00128       }
00129 
00135       inline void 
00136       getBins (unsigned int& binsx, unsigned int& binsy, unsigned int& binsz) const
00137       {
00138         binsx = binsx_;
00139         binsy = binsy_;
00140         binsz = binsz_;
00141       }
00142 
00146       inline void 
00147       setNormals (const NormalsConstPtr &normals) { input_normals_ = normals; }
00148 
00150       inline NormalsConstPtr
00151       getNormals () const { return (input_normals_); }
00152 
00153     protected:
00155       unsigned int sample_;
00157       unsigned int seed_;
00158 
00160       unsigned int binsx_;
00162       unsigned int binsy_;
00164       unsigned int binsz_;
00165      
00167       NormalsConstPtr input_normals_;
00168 
00172       void
00173       applyFilter (PointCloud &output);
00174 
00178       void
00179       applyFilter (std::vector<int> &indices);
00180 
00181       bool
00182       initCompute ();
00183 
00184     private:
00189       unsigned int 
00190       findBin (const float *normal, unsigned int nbins);
00191 
00197       bool
00198       isEntireBinSampled (boost::dynamic_bitset<> &array, unsigned int start_index, unsigned int length);
00199 
00201       boost::variate_generator<boost::mt19937, boost::uniform_int<uint32_t> > *rng_uniform_distribution_;
00202   };
00203 }
00204 
00205 #ifdef PCL_NO_PRECOMPILE
00206 #include <pcl/filters/impl/normal_space.hpp>
00207 #endif
00208 
00209 #endif  //#ifndef PCL_FILTERS_NORMAL_SPACE_SUBSAMPLE_H_


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