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 using PCLBase<PointInT>::indices_;
00059 using PCLBase<PointInT>::input_;
00060
00061 typedef PCLBase<PointInT> BaseClass;
00062 typedef typename pcl::search::Search<PointInT> KdTree;
00063 typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;
00064 typedef pcl::PointCloud<PointInT> PointCloudIn;
00065 typedef typename PointCloudIn::Ptr PointCloudInPtr;
00066 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00067 typedef pcl::PointCloud<PointOutT> PointCloudOut;
00068 typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00069 typedef boost::function<int (const PointCloudIn &cloud, int index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;
00070
00071 public:
00073 Keypoint () :
00074 BaseClass (),
00075 name_ (),
00076 search_method_ (),
00077 search_method_surface_ (),
00078 surface_ (),
00079 tree_ (),
00080 search_parameter_ (0),
00081 search_radius_ (0),
00082 k_ (0)
00083 {};
00084
00088 virtual void
00089 setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; }
00090
00092 inline PointCloudInConstPtr
00093 getSearchSurface () { return (surface_); }
00094
00098 inline void
00099 setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00100
00102 inline KdTreePtr
00103 getSearchMethod () { return (tree_); }
00104
00106 inline double
00107 getSearchParameter () { return (search_parameter_); }
00108
00112 inline void
00113 setKSearch (int k) { k_ = k; }
00114
00116 inline int
00117 getKSearch () { return (k_); }
00118
00123 inline void
00124 setRadiusSearch (double radius) { search_radius_ = radius; }
00125
00127 inline double
00128 getRadiusSearch () { return (search_radius_); }
00129
00134 inline void
00135 compute (PointCloudOut &output);
00136
00145 inline int
00146 searchForNeighbors (int index, double parameter, std::vector<int> &indices, std::vector<float> &distances) const
00147 {
00148 if (surface_ == input_)
00149 return (search_method_ (index, parameter, indices, distances));
00150 else
00151 return (search_method_surface_ (*input_, index, parameter, indices, distances));
00152 }
00153
00154 protected:
00155 using PCLBase<PointInT>::deinitCompute;
00156
00157 virtual bool
00158 initCompute ();
00159
00161 std::string name_;
00162
00164 SearchMethod search_method_;
00165
00167 SearchMethodSurface search_method_surface_;
00168
00170 PointCloudInConstPtr surface_;
00171
00173 KdTreePtr tree_;
00174
00176 double search_parameter_;
00177
00179 double search_radius_;
00180
00182 int k_;
00183
00185 inline const std::string&
00186 getClassName () const { return (name_); }
00187
00189 virtual void
00190 detectKeypoints (PointCloudOut &output) = 0;
00191 };
00192 }
00193
00194 #include <pcl/keypoints/impl/keypoint.hpp>
00195
00196 #endif //#ifndef PCL_KEYPOINT_H_