normal_based_signature.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) 2011, Alexandru-Eugen Ichim
00006  *  Copyright (c) 2012-, Open Perception, Inc.
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 #ifndef PCL_NORMAL_BASED_SIGNATURE_H_
00041 #define PCL_NORMAL_BASED_SIGNATURE_H_
00042 
00043 #include <pcl/features/feature.h>
00044 
00045 namespace pcl
00046 {
00060   template <typename PointT, typename PointNT, typename PointFeature>
00061   class NormalBasedSignatureEstimation : public FeatureFromNormals<PointT, PointNT, PointFeature>
00062   {
00063     public:
00064       using Feature<PointT, PointFeature>::input_;
00065       using Feature<PointT, PointFeature>::tree_;
00066       using Feature<PointT, PointFeature>::search_radius_;
00067       using PCLBase<PointT>::indices_;
00068       using FeatureFromNormals<PointT, PointNT, PointFeature>::normals_;
00069 
00070       typedef pcl::PointCloud<PointFeature> FeatureCloud;
00071       typedef typename boost::shared_ptr<NormalBasedSignatureEstimation<PointT, PointNT, PointFeature> > Ptr;
00072       typedef typename boost::shared_ptr<const NormalBasedSignatureEstimation<PointT, PointNT, PointFeature> > ConstPtr;
00073 
00074 
00075 
00078       NormalBasedSignatureEstimation ()
00079         : FeatureFromNormals<PointT, PointNT, PointFeature> (),
00080           scale_h_ (),
00081           N_ (36),
00082           M_ (8),
00083           N_prime_ (4),
00084           M_prime_ (3)
00085       {
00086       }
00087 
00091       inline void
00092       setN (size_t n) { N_ = n; }
00093 
00095       inline size_t
00096       getN () { return N_; }
00097 
00101       inline void
00102       setM (size_t m) { M_ = m; }
00103 
00105       inline size_t
00106       getM () { return M_; }
00107 
00113       inline void
00114       setNPrime (size_t n_prime) { N_prime_ = n_prime; }
00115 
00120       inline size_t
00121       getNPrime () { return N_prime_; }
00122 
00128       inline void
00129       setMPrime (size_t m_prime) { M_prime_ = m_prime; }
00130 
00135       inline size_t
00136       getMPrime () { return M_prime_; }
00137 
00141       inline void
00142       setScale (float scale) { scale_h_ = scale; }
00143 
00147       inline float
00148       getScale () { return scale_h_; }
00149 
00150 
00151     protected:
00152       void
00153       computeFeature (FeatureCloud &output);
00154 
00155     private:
00156       float scale_h_;
00157       size_t N_, M_, N_prime_, M_prime_;
00158   };
00159 }
00160 
00161 #ifdef PCL_NO_PRECOMPILE
00162 #include <pcl/features/impl/normal_based_signature.hpp>
00163 #endif
00164 
00165 #endif /* PCL_NORMAL_BASED_SIGNATURE_H_ */


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