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  *
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  *  $Id: usc.h 6144 2012-07-04 22:06:28Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FEATURES_USC_H_
00041 #define PCL_FEATURES_USC_H_
00042 
00043 #include <pcl/point_types.h>
00044 #include <pcl/features/feature.h>
00045 
00046 namespace pcl
00047 {
00065   template <typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
00066   class UniqueShapeContext : public Feature<PointInT, PointOutT>,
00067                              public FeatureWithLocalReferenceFrames<PointInT, PointRFT>
00068   {
00069     public:
00070        using Feature<PointInT, PointOutT>::feature_name_;
00071        using Feature<PointInT, PointOutT>::getClassName;
00072        using Feature<PointInT, PointOutT>::indices_;
00073        using Feature<PointInT, PointOutT>::search_parameter_;
00074        using Feature<PointInT, PointOutT>::search_radius_;
00075        using Feature<PointInT, PointOutT>::surface_;
00076        using Feature<PointInT, PointOutT>::fake_surface_;
00077        using Feature<PointInT, PointOutT>::input_;
00078        using Feature<PointInT, PointOutT>::searchForNeighbors;
00079        using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00080 
00081        typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00082        typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00083        typedef typename boost::shared_ptr<UniqueShapeContext<PointInT, PointOutT, PointRFT> > Ptr;
00084        typedef typename boost::shared_ptr<const UniqueShapeContext<PointInT, PointOutT, PointRFT> > ConstPtr;
00085 
00086 
00088        UniqueShapeContext () :
00089          radii_interval_(0), theta_divisions_(0), phi_divisions_(0), volume_lut_(0),
00090          azimuth_bins_(12), elevation_bins_(11), radius_bins_(15),
00091          min_radius_(0.1), point_density_radius_(0.2), descriptor_length_ (), local_radius_ (2.5)
00092        {
00093          feature_name_ = "UniqueShapeContext";
00094          search_radius_ = 2.5;
00095        }
00096 
00097       virtual ~UniqueShapeContext() { }
00098 
00102       inline void
00103       setAzimuthBins (size_t bins) { azimuth_bins_ = bins; }
00104 
00106       inline size_t
00107       getAzimuthBins () const { return (azimuth_bins_); }
00108 
00112       inline void
00113       setElevationBins (size_t bins) { elevation_bins_ = bins; }
00114 
00116       inline size_t
00117       getElevationBins () const { return (elevation_bins_); }
00118 
00122       inline void
00123       setRadiusBins (size_t bins) { radius_bins_ = bins; }
00124 
00126       inline size_t
00127       getRadiusBins () const { return (radius_bins_); }
00128 
00132       inline void
00133       setMinimalRadius (double radius) { min_radius_ = radius; }
00134 
00136       inline double
00137       getMinimalRadius () const { return (min_radius_); }
00138 
00143       inline void
00144       setPointDensityRadius (double radius) { point_density_radius_ = radius; }
00145 
00147       inline double
00148       getPointDensityRadius () const { return (point_density_radius_); }
00149 
00153       inline void
00154       setLocalRadius (double radius) { local_radius_ = radius; }
00155 
00157       inline double
00158       getLocalRadius () const { return (local_radius_); }
00159 
00160     protected:
00165       void
00166       computePointDescriptor (size_t index, std::vector<float> &desc);
00167 
00169       virtual bool
00170       initCompute ();
00171 
00175       virtual void
00176       computeFeature (PointCloudOut &output);
00177 
00179       std::vector<float> radii_interval_;
00180 
00182       std::vector<float> theta_divisions_;
00183 
00185       std::vector<float> phi_divisions_;
00186 
00188       std::vector<float> volume_lut_;
00189 
00191       size_t azimuth_bins_;
00192 
00194       size_t elevation_bins_;
00195 
00197       size_t radius_bins_;
00198 
00200       double min_radius_;
00201 
00203       double point_density_radius_;
00204 
00206       size_t descriptor_length_;
00207 
00209       double local_radius_;
00210    private:
00214       void
00215       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00216   };
00217 
00235   template <typename PointInT, typename PointRFT>
00236   class UniqueShapeContext<PointInT, Eigen::MatrixXf, PointRFT> : public UniqueShapeContext<PointInT, pcl::SHOT, PointRFT>
00237   {
00238     public:
00239       using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00240       using UniqueShapeContext<PointInT, pcl::SHOT, PointRFT>::indices_;
00241       using UniqueShapeContext<PointInT, pcl::SHOT, PointRFT>::descriptor_length_;
00242       using UniqueShapeContext<PointInT, pcl::SHOT, PointRFT>::compute;
00243       using UniqueShapeContext<PointInT, pcl::SHOT, PointRFT>::computePointDescriptor;
00244 
00245     private:
00249       virtual void
00250       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00251 
00255       void
00256       compute (pcl::PointCloud<pcl::SHOT> &) {}
00257   };
00258 }
00259 
00260 #endif  //#ifndef PCL_USC_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:55