spin_image.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: spin_image.h 6144 2012-07-04 22:06:28Z rusu $
00037  */
00038 
00039 #ifndef PCL_SPIN_IMAGE_H_
00040 #define PCL_SPIN_IMAGE_H_
00041 
00042 #include <pcl/point_types.h>
00043 #include <pcl/features/feature.h>
00044 
00045 namespace pcl
00046 {
00086   template <typename PointInT, typename PointNT, typename PointOutT>
00087   class SpinImageEstimation : public Feature<PointInT, PointOutT>
00088   {
00089     public:
00090       using Feature<PointInT, PointOutT>::feature_name_;
00091       using Feature<PointInT, PointOutT>::getClassName;
00092       using Feature<PointInT, PointOutT>::indices_;
00093       using Feature<PointInT, PointOutT>::search_radius_;
00094       using Feature<PointInT, PointOutT>::k_;
00095       using Feature<PointInT, PointOutT>::surface_;
00096       using Feature<PointInT, PointOutT>::fake_surface_;
00097       using PCLBase<PointInT>::input_;
00098 
00099       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00100 
00101       typedef typename pcl::PointCloud<PointNT> PointCloudN;
00102       typedef typename PointCloudN::Ptr PointCloudNPtr;
00103       typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00104 
00105       typedef typename pcl::PointCloud<PointInT> PointCloudIn;
00106       typedef typename PointCloudIn::Ptr PointCloudInPtr;
00107       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00108       
00109       typedef typename boost::shared_ptr<SpinImageEstimation<PointInT, PointNT, PointOutT> > Ptr;
00110       typedef typename boost::shared_ptr<const SpinImageEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00111 
00121       SpinImageEstimation (unsigned int image_width = 8,
00122                            double support_angle_cos = 0.0,   // when 0, this is bogus, so not applied
00123                            unsigned int min_pts_neighb = 0);
00124 
00129       void 
00130       setImageWidth (unsigned int bin_count)
00131       {
00132         image_width_ = bin_count;
00133       }
00134 
00141       void 
00142       setSupportAngle (double support_angle_cos)
00143       {
00144         if (0.0 > support_angle_cos || support_angle_cos > 1.0)  // may be permit negative cosine?
00145         {
00146           throw PCLException ("Cosine of support angle should be between 0 and 1",
00147             "spin_image.h", "setSupportAngle");
00148         }
00149 
00150         support_angle_cos_ = support_angle_cos;
00151       }
00152 
00158       void 
00159       setMinPointCountInNeighbourhood (unsigned int min_pts_neighb)
00160       {
00161         min_pts_neighb_ = min_pts_neighb;
00162       }
00163 
00174       inline void 
00175       setInputNormals (const PointCloudNConstPtr &normals)
00176       { 
00177         input_normals_ = normals; 
00178       }
00179 
00185       void 
00186       setRotationAxis (const PointNT& axis)
00187       {
00188         rotation_axis_ = axis;
00189         use_custom_axis_ = true;
00190         use_custom_axes_cloud_ = false;
00191       }
00192 
00199       void 
00200       setInputRotationAxes (const PointCloudNConstPtr& axes)
00201       {
00202         rotation_axes_cloud_ = axes;
00203 
00204         use_custom_axes_cloud_ = true;
00205         use_custom_axis_ = false;
00206       }
00207 
00209       void 
00210       useNormalsAsRotationAxis () 
00211       { 
00212         use_custom_axis_ = false; 
00213         use_custom_axes_cloud_ = false;
00214       }
00215 
00227       void 
00228       setAngularDomain (bool is_angular = true) { is_angular_ = is_angular; }
00229 
00237       void 
00238       setRadialStructure (bool is_radial = true) { is_radial_ = is_radial; }
00239 
00240     protected:
00245       virtual void 
00246       computeFeature (PointCloudOut &output); 
00247 
00252       virtual bool
00253       initCompute ();
00254 
00259       Eigen::ArrayXXd 
00260       computeSiForPoint (int index) const;
00261 
00262     private:
00263       PointCloudNConstPtr input_normals_;
00264       PointCloudNConstPtr rotation_axes_cloud_;
00265       
00266       bool is_angular_;
00267 
00268       PointNT rotation_axis_;
00269       bool use_custom_axis_;
00270       bool use_custom_axes_cloud_;
00271 
00272       bool is_radial_;
00273 
00274       unsigned int image_width_;
00275       double support_angle_cos_;
00276       unsigned int min_pts_neighb_;
00277 
00281       void 
00282       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00283   };
00284 
00315   template <typename PointInT, typename PointNT>
00316   class SpinImageEstimation<PointInT, PointNT, Eigen::MatrixXf> : public SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> >
00317   {
00318     public:
00319       using SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> >::indices_;
00320       using SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> >::search_radius_;
00321       using SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> >::k_;
00322       using SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> >::surface_;
00323       using SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> >::fake_surface_;
00324       using SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> >::compute;
00325 
00335       SpinImageEstimation (unsigned int image_width = 8,
00336                            double support_angle_cos = 0.0,   // when 0, this is bogus, so not applied
00337                            unsigned int min_pts_neighb = 0) : 
00338         SpinImageEstimation<PointInT, PointNT, pcl::Histogram<153> > (image_width, support_angle_cos, min_pts_neighb) {}
00339 
00340     private:
00345       virtual void 
00346       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output); 
00347 
00351       void 
00352       compute (pcl::PointCloud<pcl::Normal> &) {}
00353   };
00354 }
00355 
00356 #endif  //#ifndef PCL_SPIN_IMAGE_H_
00357 
00358 


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