3dsc.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  *  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 
00041 #ifndef PCL_FEATURES_3DSC_H_
00042 #define PCL_FEATURES_3DSC_H_
00043 
00044 #include <pcl/point_types.h>
00045 #include <pcl/features/boost.h>
00046 #include <pcl/features/feature.h>
00047 
00048 namespace pcl
00049 {
00071   template <typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
00072   class ShapeContext3DEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00073   {
00074     public:
00075       typedef boost::shared_ptr<ShapeContext3DEstimation<PointInT, PointNT, PointOutT> > Ptr;
00076       typedef boost::shared_ptr<const ShapeContext3DEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00077 
00078       using Feature<PointInT, PointOutT>::feature_name_;
00079       using Feature<PointInT, PointOutT>::getClassName;
00080       using Feature<PointInT, PointOutT>::indices_;
00081       using Feature<PointInT, PointOutT>::search_parameter_;
00082       using Feature<PointInT, PointOutT>::search_radius_;
00083       using Feature<PointInT, PointOutT>::surface_;
00084       using Feature<PointInT, PointOutT>::input_;
00085       using Feature<PointInT, PointOutT>::searchForNeighbors;
00086       using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00087 
00088       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00089       typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00090 
00095       ShapeContext3DEstimation (bool random = false) :
00096         radii_interval_(0),
00097         theta_divisions_(0),
00098         phi_divisions_(0),
00099         volume_lut_(0),
00100         azimuth_bins_(12),
00101         elevation_bins_(11),
00102         radius_bins_(15),
00103         min_radius_(0.1),
00104         point_density_radius_(0.2),
00105         descriptor_length_ (),
00106         rng_alg_ (),
00107         rng_ (new boost::uniform_01<boost::mt19937> (rng_alg_))
00108       {
00109         feature_name_ = "ShapeContext3DEstimation";
00110         search_radius_ = 2.5;
00111 
00112         // Create a random number generator object
00113         if (random)
00114           rng_->base ().seed (static_cast<unsigned> (std::time(0)));
00115         else
00116           rng_->base ().seed (12345u);
00117       }
00118 
00119       virtual ~ShapeContext3DEstimation() {}
00120 
00121       //inline void
00122       //setAzimuthBins (size_t bins) { azimuth_bins_ = bins; }
00123 
00125       inline size_t
00126       getAzimuthBins () { return (azimuth_bins_); }
00127 
00128       //inline void
00129       //setElevationBins (size_t bins) { elevation_bins_ = bins; }
00130 
00132       inline size_t
00133       getElevationBins () { return (elevation_bins_); }
00134 
00135       //inline void
00136       //setRadiusBins (size_t bins) { radius_bins_ = bins; }
00137 
00139       inline size_t
00140       getRadiusBins () { return (radius_bins_); }
00141 
00145       inline void
00146       setMinimalRadius (double radius) { min_radius_ = radius; }
00147 
00149       inline double
00150       getMinimalRadius () { return (min_radius_); }
00151 
00156       inline void
00157       setPointDensityRadius (double radius) { point_density_radius_ = radius; }
00158 
00160       inline double
00161       getPointDensityRadius () { return (point_density_radius_); }
00162 
00163     protected:
00165       bool
00166       initCompute ();
00167 
00176       bool
00177       computePoint (size_t index, const pcl::PointCloud<PointNT> &normals, float rf[9], std::vector<float> &desc);
00178 
00182       void
00183       computeFeature (PointCloudOut &output);
00184 
00186       std::vector<float> radii_interval_;
00187 
00189       std::vector<float> theta_divisions_;
00190 
00192       std::vector<float> phi_divisions_;
00193 
00195       std::vector<float> volume_lut_;
00196 
00198       size_t azimuth_bins_;
00199 
00201       size_t elevation_bins_;
00202 
00204       size_t radius_bins_;
00205 
00207       double min_radius_;
00208 
00210       double point_density_radius_;
00211 
00213       size_t descriptor_length_;
00214 
00216       boost::mt19937 rng_alg_;
00217 
00219       boost::shared_ptr<boost::uniform_01<boost::mt19937> > rng_;
00220 
00226       //void
00227       //shiftAlongAzimuth (size_t block_size, std::vector<float>& desc);
00228 
00230       inline double
00231       rnd ()
00232       {
00233         return ((*rng_) ());
00234       }
00235   };
00236 }
00237 
00238 #ifdef PCL_NO_PRECOMPILE
00239 #include <pcl/features/impl/3dsc.hpp>
00240 #endif
00241 
00242 #endif  //#ifndef PCL_3DSC_H_


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