harris_6d.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  @author Suat Gedikli
00035  */
00036 
00037 #ifndef PCL_HARRIS_KEYPOINT_6D_H_
00038 #define PCL_HARRIS_KEYPOINT_6D_H_
00039 
00040 #include <pcl/keypoints/keypoint.h>
00041 
00042 namespace pcl
00043 {
00044 
00049   template <typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
00050   class HarrisKeypoint6D : public Keypoint<PointInT, PointOutT>
00051   {
00052     public:
00053       typedef boost::shared_ptr<HarrisKeypoint6D<PointInT, PointOutT, NormalT> > Ptr;
00054       typedef boost::shared_ptr<const HarrisKeypoint6D<PointInT, PointOutT, NormalT> > ConstPtr;
00055 
00056       typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00057       typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00058       typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
00059       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00060 
00061       using Keypoint<PointInT, PointOutT>::name_;
00062       using Keypoint<PointInT, PointOutT>::input_;
00063       using Keypoint<PointInT, PointOutT>::indices_;
00064       using Keypoint<PointInT, PointOutT>::surface_;
00065       using Keypoint<PointInT, PointOutT>::tree_;
00066       using Keypoint<PointInT, PointOutT>::k_;
00067       using Keypoint<PointInT, PointOutT>::search_radius_;
00068       using Keypoint<PointInT, PointOutT>::search_parameter_;
00069 
00076       HarrisKeypoint6D (float radius = 0.01, float threshold = 0.0)
00077       : threshold_ (threshold)
00078       , refine_ (true)
00079       , nonmax_ (true)
00080       , threads_ (0)
00081       , normals_ (new pcl::PointCloud<NormalT>)
00082       , intensity_gradients_ (new pcl::PointCloud<pcl::IntensityGradient>)
00083       {
00084         name_ = "HarrisKeypoint6D";
00085         search_radius_ = radius;
00086       }
00087       
00089       virtual ~HarrisKeypoint6D () {}
00090 
00095       void setRadius (float radius);
00096 
00102       void setThreshold (float threshold);
00103 
00109       void setNonMaxSupression (bool = false);
00110 
00116       void setRefine (bool do_refine);
00117 
00118       virtual void
00119       setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; normals_->clear (); intensity_gradients_->clear ();}
00120 
00124       inline void
00125       setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00126     protected:
00127       void detectKeypoints (PointCloudOut &output);
00128       void responseTomasi (PointCloudOut &output) const;
00129       void refineCorners (PointCloudOut &corners) const;
00130       void calculateCombinedCovar (const std::vector<int>& neighbors, float* coefficients) const;
00131     private:
00132       float threshold_;
00133       bool refine_;
00134       bool nonmax_;
00135       unsigned int threads_;    
00136       boost::shared_ptr<pcl::PointCloud<NormalT> > normals_;
00137       boost::shared_ptr<pcl::PointCloud<pcl::IntensityGradient> > intensity_gradients_;
00138   } ;
00139 }
00140 
00141 #include <pcl/keypoints/impl/harris_6d.hpp>
00142 
00143 #endif // #ifndef PCL_HARRIS_KEYPOINT_6D_H_
00144 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:42