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) 2009-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 Willow Garage, Inc. 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/filter_indices.h>
00042 #include <time.h>
00043 #include <limits.h>
00044 
00045 #include <boost/dynamic_bitset.hpp>
00046 
00047 namespace pcl
00048 {
00052   template<typename PointT, typename NormalT>
00053   class NormalSpaceSampling : public FilterIndices<PointT>
00054   {
00055     using FilterIndices<PointT>::filter_name_;
00056     using FilterIndices<PointT>::getClassName;
00057     using FilterIndices<PointT>::indices_;
00058     using FilterIndices<PointT>::input_;
00059 
00060     typedef typename FilterIndices<PointT>::PointCloud PointCloud;
00061     typedef typename PointCloud::Ptr PointCloudPtr;
00062     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00063     typedef typename pcl::PointCloud<NormalT>::Ptr NormalsPtr;
00064 
00065     public:
00067       NormalSpaceSampling () : 
00068         sample_ (UINT_MAX), seed_ (static_cast<unsigned int> (time (NULL))), binsx_ (), binsy_ (), binsz_ (), input_normals_ ()
00069       {
00070         filter_name_ = "NormalSpaceSampling";
00071       }
00072 
00076       inline void
00077       setSample (unsigned int sample)
00078       {
00079         sample_ = sample;
00080       }
00081 
00083       inline unsigned int
00084       getSample () const
00085       {
00086         return (sample_);
00087       }
00088 
00092       inline void
00093       setSeed (unsigned int seed)
00094       {
00095         seed_ = seed;
00096       }
00097 
00099       inline unsigned int
00100       getSeed () const
00101       {
00102         return (seed_);
00103       }
00104 
00110       inline void 
00111       setBins (unsigned int binsx, unsigned int binsy, unsigned int binsz)
00112       {
00113         binsx_ = binsx;
00114         binsy_ = binsy;
00115         binsz_ = binsz;
00116       }
00117 
00123       inline void 
00124       getBins (unsigned int& binsx, unsigned int& binsy, unsigned int& binsz) const
00125       {
00126         binsx = binsx_;
00127         binsy = binsy_;
00128         binsz = binsz_;
00129       }
00130 
00134       inline void 
00135       setNormals (const NormalsPtr &normals) { input_normals_ = normals; }
00136 
00138       inline NormalsPtr
00139       getNormals () const { return (input_normals_); }
00140 
00141     protected:
00143       unsigned int sample_;
00145       unsigned int seed_;
00146 
00148       unsigned int binsx_;
00150       unsigned int binsy_;
00152       unsigned int binsz_;
00153      
00155       NormalsPtr input_normals_; 
00156 
00160       void
00161       applyFilter (PointCloud &output);
00162 
00166       void
00167       applyFilter (std::vector<int> &indices);
00168 
00169     private:
00174       unsigned int 
00175       findBin (float *normal, unsigned int nbins);
00176 
00182       bool
00183       isEntireBinSampled (boost::dynamic_bitset<> &array, unsigned int start_index, unsigned int length);
00184 
00185   };
00186 }
00187 #endif  //#ifndef PCL_FILTERS_NORMAL_SPACE_SUBSAMPLE_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:54