Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #ifndef PCL_KEYPOINT_H_
00039 #define PCL_KEYPOINT_H_
00040 
00041 
00042 #include <pcl/pcl_base.h>
00043 #include <boost/function.hpp>
00044 #include <boost/bind.hpp>
00045 #include <pcl/search/pcl_search.h>
00046 #include <pcl/pcl_config.h>
00047 
00048 namespace pcl
00049 {
00054   template <typename PointInT, typename PointOutT>
00055   class Keypoint : public PCLBase<PointInT>
00056   {
00057     public:
00058       typedef boost::shared_ptr<Keypoint<PointInT, PointOutT> > Ptr;
00059       typedef boost::shared_ptr<const Keypoint<PointInT, PointOutT> > ConstPtr;
00060 
00061       using PCLBase<PointInT>::indices_;
00062       using PCLBase<PointInT>::input_;
00063 
00064       typedef PCLBase<PointInT> BaseClass;
00065       typedef typename pcl::search::Search<PointInT> KdTree;
00066       typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;
00067       typedef pcl::PointCloud<PointInT> PointCloudIn;
00068       typedef typename PointCloudIn::Ptr PointCloudInPtr;
00069       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00070       typedef pcl::PointCloud<PointOutT> PointCloudOut;
00071       typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00072       typedef boost::function<int (const PointCloudIn &cloud, int index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;
00073 
00074     public:
00076       Keypoint () : 
00077         BaseClass (), 
00078         name_ (),
00079         search_method_ (),
00080         search_method_surface_ (),
00081         surface_ (), 
00082         tree_ (), 
00083         search_parameter_ (0), 
00084         search_radius_ (0), 
00085         k_ (0) 
00086       {};
00087       
00089       virtual ~Keypoint () {}
00090 
00094       virtual void
00095       setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; }
00096 
00098       inline PointCloudInConstPtr
00099       getSearchSurface () { return (surface_); }
00100 
00104       inline void
00105       setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00106 
00108       inline KdTreePtr
00109       getSearchMethod () { return (tree_); }
00110 
00112       inline double
00113       getSearchParameter () { return (search_parameter_); }
00114 
00118       inline void
00119       setKSearch (int k) { k_ = k; }
00120 
00122       inline int
00123       getKSearch () { return (k_); }
00124 
00129       inline void
00130       setRadiusSearch (double radius) { search_radius_ = radius; }
00131 
00133       inline double
00134       getRadiusSearch () { return (search_radius_); }
00135 
00140       inline void
00141       compute (PointCloudOut &output);
00142 
00151       inline int
00152       searchForNeighbors (int index, double parameter, std::vector<int> &indices, std::vector<float> &distances) const
00153       {
00154         if (surface_ == input_)       
00155           return (search_method_ (index, parameter, indices, distances));
00156         else
00157           return (search_method_surface_ (*input_, index, parameter, indices, distances));
00158       }
00159 
00160     protected:
00161       using PCLBase<PointInT>::deinitCompute;
00162 
00163       virtual bool
00164       initCompute ();
00165 
00167       std::string name_;
00168 
00170       SearchMethod search_method_;
00171 
00173       SearchMethodSurface search_method_surface_;
00174 
00176       PointCloudInConstPtr surface_;
00177 
00179       KdTreePtr tree_;
00180 
00182       double search_parameter_;
00183 
00185       double search_radius_;
00186 
00188       int k_;
00189 
00191       inline const std::string&
00192       getClassName () const { return (name_); }
00193 
00195       virtual void
00196       detectKeypoints (PointCloudOut &output) = 0;
00197   };
00198 }
00199 
00200 #include <pcl/keypoints/impl/keypoint.hpp>
00201 
00202 #endif  //#ifndef PCL_KEYPOINT_H_