rsd.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, 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_RSD_H_
00042 #define PCL_RSD_H_
00043 
00044 #include <pcl/features/feature.h>
00045 
00046 namespace pcl
00047 {
00055   template <int N> void
00056   getFeaturePointCloud (const std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > &histograms2D, PointCloud<Histogram<N> > &histogramsPC)
00057   {
00058     histogramsPC.points.resize (histograms2D.size ());
00059     histogramsPC.width    = histograms2D.size ();
00060     histogramsPC.height   = 1;
00061     histogramsPC.is_dense = true;
00062 
00063     const int rows  = histograms2D.at(0).rows();
00064     const int cols = histograms2D.at(0).cols();
00065 
00066     typename PointCloud<Histogram<N> >::VectorType::iterator it = histogramsPC.points.begin ();
00067     BOOST_FOREACH (Eigen::MatrixXf h, histograms2D)
00068     {
00069       Eigen::Map<Eigen::MatrixXf> histogram (&(it->histogram[0]), rows, cols);
00070       histogram = h;
00071       ++it;
00072     }
00073   }
00074 
00086   template <typename PointInT, typename PointNT, typename PointOutT> Eigen::MatrixXf
00087   computeRSD (boost::shared_ptr<const pcl::PointCloud<PointInT> > &surface, boost::shared_ptr<const pcl::PointCloud<PointNT> > &normals,
00088              const std::vector<int> &indices, double max_dist,
00089              int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);
00090 
00102   template <typename PointNT, typename PointOutT> Eigen::MatrixXf
00103   computeRSD (boost::shared_ptr<const pcl::PointCloud<PointNT> > &normals,
00104              const std::vector<int> &indices, const std::vector<float> &sqr_dists, double max_dist,
00105              int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);
00106 
00129   template <typename PointInT, typename PointNT, typename PointOutT>
00130   class RSDEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00131   {
00132     public:
00133       using Feature<PointInT, PointOutT>::feature_name_;
00134       using Feature<PointInT, PointOutT>::getClassName;
00135       using Feature<PointInT, PointOutT>::indices_;
00136       using Feature<PointInT, PointOutT>::search_radius_;
00137       using Feature<PointInT, PointOutT>::search_parameter_;
00138       using Feature<PointInT, PointOutT>::surface_;
00139       using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00140 
00141       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00142       typedef typename Feature<PointInT, PointOutT>::PointCloudIn  PointCloudIn;
00143 
00144       typedef typename boost::shared_ptr<RSDEstimation<PointInT, PointNT, PointOutT> > Ptr;
00145       typedef typename boost::shared_ptr<const RSDEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00146 
00147 
00149       RSDEstimation () : nr_subdiv_ (5), plane_radius_ (0.2), save_histograms_ (false)
00150       {
00151         feature_name_ = "RadiusSurfaceDescriptor";
00152       };
00153 
00157       inline void 
00158       setNrSubdivisions (int nr_subdiv) { nr_subdiv_ = nr_subdiv; }
00159 
00161       inline int 
00162       getNrSubdivisions () const { return (nr_subdiv_); }
00163 
00169       inline void 
00170       setPlaneRadius (double plane_radius) { plane_radius_ = plane_radius; }
00171 
00173       inline double 
00174       getPlaneRadius () const { return (plane_radius_); }
00175 
00177       inline void 
00178       setKSearch (int) 
00179       {
00180         PCL_ERROR ("[pcl::%s::setKSearch] RSD does not work with k nearest neighbor search. Use setRadiusSearch() instead!\n", getClassName ().c_str ());
00181       }
00182 
00187       inline void
00188       setSaveHistograms (bool save) { save_histograms_ = save; }
00189 
00191       inline bool
00192       getSaveHistograms () const { return (save_histograms_); }
00193 
00195       inline boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > >
00196       getHistograms () const { return (histograms_); }
00197 
00198     protected:
00199 
00205       void 
00206       computeFeature (PointCloudOut &output);
00207 
00209       boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > > histograms_;
00210 
00211     private:
00213       int nr_subdiv_;
00214 
00216       double plane_radius_;
00217 
00219       bool save_histograms_;
00220 
00221     public:
00222       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00223   };
00224 }
00225 
00226 #ifdef PCL_NO_PRECOMPILE
00227 #include <pcl/features/impl/rsd.hpp>
00228 #endif
00229 
00230 #endif  //#ifndef PCL_RSD_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:32:10