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
00039 #ifndef PCL_SUSAN_KEYPOINT_H_
00040 #define PCL_SUSAN_KEYPOINT_H_
00041
00042 #include <pcl/keypoints/keypoint.h>
00043 #include <pcl/common/intensity.h>
00044
00045 namespace pcl
00046 {
00056 template <typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT= pcl::common::IntensityFieldAccessor<PointInT> >
00057 class SUSANKeypoint : public Keypoint<PointInT, PointOutT>
00058 {
00059 public:
00060 typedef boost::shared_ptr<SUSANKeypoint<PointInT, PointOutT, NormalT, IntensityT> > Ptr;
00061 typedef boost::shared_ptr<const SUSANKeypoint<PointInT, PointOutT, NormalT, Intensity> > ConstPtr;
00062
00063 typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00064 typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00065 typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
00066 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00067
00068 typedef typename pcl::PointCloud<NormalT> PointCloudN;
00069 typedef typename PointCloudN::Ptr PointCloudNPtr;
00070 typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00071
00072 using Keypoint<PointInT, PointOutT>::name_;
00073 using Keypoint<PointInT, PointOutT>::input_;
00074 using Keypoint<PointInT, PointOutT>::indices_;
00075 using Keypoint<PointInT, PointOutT>::surface_;
00076 using Keypoint<PointInT, PointOutT>::tree_;
00077 using Keypoint<PointInT, PointOutT>::k_;
00078 using Keypoint<PointInT, PointOutT>::search_radius_;
00079 using Keypoint<PointInT, PointOutT>::search_parameter_;
00080 using Keypoint<PointInT, PointOutT>::initCompute;
00081
00088 SUSANKeypoint (float radius = 0.01f,
00089 float distance_threshold = 0.001f,
00090 float angular_threshold = 0.0001f,
00091 float intensity_threshold = 7.0f)
00092 : distance_threshold_ (distance_threshold)
00093 , angular_threshold_ (angular_threshold)
00094 , intensity_threshold_ (intensity_threshold)
00095 , normals_ (new pcl::PointCloud<NormalT>)
00096 , threads_ (0)
00097 , label_idx_ (-1)
00098 , out_fields_ ()
00099 {
00100 name_ = "SUSANKeypoint";
00101 search_radius_ = radius;
00102 geometric_validation_ = false;
00103 tolerance_ = 2 * distance_threshold_;
00104 }
00105
00107 virtual ~SUSANKeypoint () {}
00108
00112 void
00113 setRadius (float radius);
00114
00115 void
00116 setDistanceThreshold (float distance_threshold);
00117
00122 void
00123 setAngularThreshold (float angular_threshold);
00124
00128 void
00129 setIntensityThreshold (float intensity_threshold);
00130
00135 void
00136 setNormals (const PointCloudNConstPtr &normals);
00137
00138 virtual void
00139 setSearchSurface (const PointCloudInConstPtr &cloud);
00140
00144 void
00145 setNumberOfThreads (unsigned int nr_threads);
00146
00150 void
00151 setNonMaxSupression (bool nonmax);
00152
00158 void
00159 setGeometricValidation (bool validate);
00160
00161 protected:
00162 bool
00163 initCompute ();
00164
00165 void
00166 detectKeypoints (PointCloudOut &output);
00175 bool
00176 isWithinNucleusCentroid (const Eigen::Vector3f& nucleus,
00177 const Eigen::Vector3f& centroid,
00178 const Eigen::Vector3f& nc,
00179 const PointInT& point) const;
00180 private:
00181 float distance_threshold_;
00182 float angular_threshold_;
00183 float intensity_threshold_;
00184 float tolerance_;
00185 PointCloudNConstPtr normals_;
00186 unsigned int threads_;
00187 bool geometric_validation_;
00188 bool nonmax_;
00190 IntensityT intensity_;
00194 int label_idx_;
00196 std::vector<pcl::PCLPointField> out_fields_;
00197 pcl::common::IntensityFieldAccessor<PointOutT> intensity_out_;
00198 };
00199 }
00200
00201 #include <pcl/keypoints/impl/susan.hpp>
00202
00203 #endif // #ifndef PCL_SUSAN_KEYPOINT_H_