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_SMOOTHEDSURFACESKEYPOINT_H_
00039 #define PCL_SMOOTHEDSURFACESKEYPOINT_H_
00040
00041 #include <pcl/keypoints/keypoint.h>
00042
00043 namespace pcl
00044 {
00054 template <typename PointT, typename PointNT>
00055 class SmoothedSurfacesKeypoint : public Keypoint <PointT, PointT>
00056 {
00057 public:
00058 typedef boost::shared_ptr<SmoothedSurfacesKeypoint<PointT, PointNT> > Ptr;
00059 typedef boost::shared_ptr<const SmoothedSurfacesKeypoint<PointT, PointNT> > ConstPtr;
00060
00061 using PCLBase<PointT>::input_;
00062 using Keypoint<PointT, PointT>::name_;
00063 using Keypoint<PointT, PointT>::tree_;
00064 using Keypoint<PointT, PointT>::initCompute;
00065
00066 typedef pcl::PointCloud<PointT> PointCloudT;
00067 typedef typename PointCloudT::ConstPtr PointCloudTConstPtr;
00068 typedef pcl::PointCloud<PointNT> PointCloudNT;
00069 typedef typename PointCloudNT::ConstPtr PointCloudNTConstPtr;
00070 typedef typename PointCloudT::Ptr PointCloudTPtr;
00071 typedef typename Keypoint<PointT, PointT>::KdTreePtr KdTreePtr;
00072
00073 SmoothedSurfacesKeypoint ()
00074 : Keypoint<PointT, PointT> (),
00075 neighborhood_constant_ (0.5f),
00076 clouds_ (),
00077 cloud_normals_ (),
00078 cloud_trees_ (),
00079 normals_ (),
00080 scales_ (),
00081 input_scale_ (0.0f),
00082 input_index_ ()
00083 {
00084 name_ = "SmoothedSurfacesKeypoint";
00085
00086
00087 Keypoint<PointT, PointT>::search_radius_ = 0.1;
00088 }
00089
00090 void
00091 addSmoothedPointCloud (const PointCloudTConstPtr &cloud,
00092 const PointCloudNTConstPtr &normals,
00093 KdTreePtr &kdtree,
00094 float &scale);
00095
00096
00097 void
00098 resetClouds ();
00099
00100 inline void
00101 setNeighborhoodConstant (float neighborhood_constant) { neighborhood_constant_ = neighborhood_constant; }
00102
00103 inline float
00104 getNeighborhoodConstant () { return neighborhood_constant_; }
00105
00106 inline void
00107 setInputNormals (const PointCloudNTConstPtr &normals) { normals_ = normals; }
00108
00109 inline void
00110 setInputScale (float input_scale) { input_scale_ = input_scale; }
00111
00112 void
00113 detectKeypoints (PointCloudT &output);
00114
00115 protected:
00116 bool
00117 initCompute ();
00118
00119 private:
00120 float neighborhood_constant_;
00121 std::vector<PointCloudTConstPtr> clouds_;
00122 std::vector<PointCloudNTConstPtr> cloud_normals_;
00123 std::vector<KdTreePtr> cloud_trees_;
00124 PointCloudNTConstPtr normals_;
00125 std::vector<std::pair<float, size_t> > scales_;
00126 float input_scale_;
00127 size_t input_index_;
00128
00129 static bool
00130 compareScalesFunction (const std::pair<float, size_t> &a,
00131 const std::pair<float, size_t> &b) { return a.first < b.first; }
00132 };
00133 }
00134
00135 #endif