usc.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_USC_H_
00042 #define PCL_FEATURES_USC_H_
00043 
00044 #include <pcl/point_types.h>
00045 #include <pcl/features/feature.h>
00046 
00047 namespace pcl
00048 {
00063   template <typename PointInT, typename PointOutT = pcl::ShapeContext1980, typename PointRFT = pcl::ReferenceFrame>
00064   class UniqueShapeContext : public Feature<PointInT, PointOutT>,
00065                              public FeatureWithLocalReferenceFrames<PointInT, PointRFT>
00066   {
00067     public:
00068       using Feature<PointInT, PointOutT>::feature_name_;
00069       using Feature<PointInT, PointOutT>::getClassName;
00070       using Feature<PointInT, PointOutT>::indices_;
00071       using Feature<PointInT, PointOutT>::search_parameter_;
00072       using Feature<PointInT, PointOutT>::search_radius_;
00073       using Feature<PointInT, PointOutT>::surface_;
00074       using Feature<PointInT, PointOutT>::fake_surface_;
00075       using Feature<PointInT, PointOutT>::input_;
00076       using Feature<PointInT, PointOutT>::searchForNeighbors;
00077       using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00078 
00079       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00080       typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00081       typedef typename boost::shared_ptr<UniqueShapeContext<PointInT, PointOutT, PointRFT> > Ptr;
00082       typedef typename boost::shared_ptr<const UniqueShapeContext<PointInT, PointOutT, PointRFT> > ConstPtr;
00083 
00084 
00086       UniqueShapeContext () :
00087         radii_interval_(0), theta_divisions_(0), phi_divisions_(0), volume_lut_(0),
00088         azimuth_bins_(12), elevation_bins_(11), radius_bins_(15),
00089         min_radius_(0.1), point_density_radius_(0.2), descriptor_length_ (), local_radius_ (2.5)
00090       {
00091         feature_name_ = "UniqueShapeContext";
00092         search_radius_ = 2.5;
00093       }
00094 
00095       virtual ~UniqueShapeContext() { }
00096 
00097       //inline void
00098       //setAzimuthBins (size_t bins) { azimuth_bins_ = bins; }
00099 
00101       inline size_t
00102       getAzimuthBins () const { return (azimuth_bins_); }
00103 
00104       //inline void
00105       //setElevationBins (size_t bins) { elevation_bins_ = bins; }
00106 
00108       inline size_t
00109       getElevationBins () const { return (elevation_bins_); }
00110 
00111       //inline void
00112       //setRadiusBins (size_t bins) { radius_bins_ = bins; }
00113 
00115       inline size_t
00116       getRadiusBins () const { return (radius_bins_); }
00117 
00121       inline void
00122       setMinimalRadius (double radius) { min_radius_ = radius; }
00123 
00125       inline double
00126       getMinimalRadius () const { return (min_radius_); }
00127 
00132       inline void
00133       setPointDensityRadius (double radius) { point_density_radius_ = radius; }
00134 
00136       inline double
00137       getPointDensityRadius () const { return (point_density_radius_); }
00138 
00142       inline void
00143       setLocalRadius (double radius) { local_radius_ = radius; }
00144 
00146       inline double
00147       getLocalRadius () const { return (local_radius_); }
00148 
00149     protected:
00154       void
00155       computePointDescriptor (size_t index, std::vector<float> &desc);
00156 
00158       virtual bool
00159       initCompute ();
00160 
00164       virtual void
00165       computeFeature (PointCloudOut &output);
00166 
00168       std::vector<float> radii_interval_;
00169 
00171       std::vector<float> theta_divisions_;
00172 
00174       std::vector<float> phi_divisions_;
00175 
00177       std::vector<float> volume_lut_;
00178 
00180       size_t azimuth_bins_;
00181 
00183       size_t elevation_bins_;
00184 
00186       size_t radius_bins_;
00187 
00189       double min_radius_;
00190 
00192       double point_density_radius_;
00193 
00195       size_t descriptor_length_;
00196 
00198       double local_radius_;
00199   };
00200 }
00201 
00202 #ifdef PCL_NO_PRECOMPILE
00203 #include <pcl/features/impl/usc.hpp>
00204 #endif
00205 
00206 #endif  //#ifndef PCL_USC_H_


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