harris_keypoint3D.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  */
00037 
00038 #ifndef PCL_HARRIS_KEYPOINT_3D_H_
00039 #define PCL_HARRIS_KEYPOINT_3D_H_
00040 
00041 #include <pcl/keypoints/keypoint.h>
00042 
00043 namespace pcl
00044 {
00051   template <typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
00052   class HarrisKeypoint3D : public Keypoint<PointInT, PointOutT>
00053   {
00054     public:
00055       typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00056       typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00057       typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
00058       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00059 
00060       typedef typename pcl::PointCloud<NormalT> PointCloudN;
00061       typedef typename PointCloudN::Ptr PointCloudNPtr;
00062       typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00063 
00064       using Keypoint<PointInT, PointOutT>::name_;
00065       using Keypoint<PointInT, PointOutT>::input_;
00066       using Keypoint<PointInT, PointOutT>::indices_;
00067       using Keypoint<PointInT, PointOutT>::surface_;
00068       using Keypoint<PointInT, PointOutT>::tree_;
00069       using Keypoint<PointInT, PointOutT>::k_;
00070       using Keypoint<PointInT, PointOutT>::search_radius_;
00071       using Keypoint<PointInT, PointOutT>::search_parameter_;
00072       using Keypoint<PointInT, PointOutT>::initCompute;
00073 
00074       typedef enum {HARRIS = 1, NOBLE, LOWE, TOMASI, CURVATURE} ResponseMethod;
00075 
00081       HarrisKeypoint3D (ResponseMethod method = HARRIS, float radius = 0.01f, float threshold = 0.0f)
00082       : threshold_ (threshold)
00083       , refine_ (true)
00084       , nonmax_ (true)
00085       , method_ (method)
00086       , normals_ (new pcl::PointCloud<NormalT>)
00087       , threads_ (1)
00088       {
00089         name_ = "HarrisKeypoint3D";
00090         search_radius_ = radius;
00091       }
00092 
00096       void 
00097       setMethod (ResponseMethod type);
00098 
00102       void 
00103       setRadius (float radius);
00104 
00109       void 
00110       setThreshold (float threshold);
00111 
00116       void 
00117       setNonMaxSupression (bool = false);
00118 
00123       void 
00124       setRefine (bool do_refine);
00125 
00129       void 
00130       setNormals (const PointCloudNPtr &normals);
00131 
00139       virtual void
00140       setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; normals_->clear (); }
00141 
00145       inline void
00146       setNumberOfThreads (int nr_threads)
00147       {
00148         if (nr_threads == 0)
00149           nr_threads = 1;
00150         threads_ = nr_threads;
00151       }
00152     protected:
00153       bool
00154       initCompute ();
00155       void detectKeypoints (PointCloudOut &output);
00157       void responseHarris (PointCloudOut &output) const;
00158       void responseNoble (PointCloudOut &output) const;
00159       void responseLowe (PointCloudOut &output) const;
00160       void responseTomasi (PointCloudOut &output) const;
00161       void responseCurvature (PointCloudOut &output) const;
00162       void refineCorners (PointCloudOut &corners) const;
00164       void calculateNormalCovar (const std::vector<int>& neighbors, float* coefficients) const;
00165     private:
00166       float threshold_;
00167       bool refine_;
00168       bool nonmax_;
00169       ResponseMethod method_;
00170       PointCloudNPtr normals_;
00171       int threads_;
00172   };
00173 }
00174 
00175 #include <pcl/keypoints/impl/harris_keypoint3D.hpp>
00176 
00177 #endif // #ifndef PCL_HARRIS_KEYPOINT_3D_H_
00178 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:24