00001 00024 #ifndef CCNY_RGBD_FEATURE_DETECTOR_H 00025 #define CCNY_RGBD_FEATURE_DETECTOR_H 00026 00027 #include <vector> 00028 #include <ros/ros.h> 00029 #include <pcl/ros/conversions.h> 00030 #include <pcl_ros/point_cloud.h> 00031 00032 #include "ccny_rgbd/rgbd_util.h" 00033 #include "ccny_rgbd/structures/rgbd_frame.h" 00034 00035 namespace ccny_rgbd { 00036 00039 class FeatureDetector 00040 { 00041 public: 00042 00045 FeatureDetector(); 00046 00049 virtual ~FeatureDetector(); 00050 00055 void findFeatures(RGBDFrame& frame); 00056 00066 inline int getSmooth() const; 00067 00071 inline double getMaxRange() const; 00072 00076 inline double getMaxStDev() const; 00077 00087 void setSmooth(int smooth); 00088 00092 void setMaxRange(double max_range); 00093 00097 void setMaxStDev(double max_stdev); 00098 00099 protected: 00100 00101 boost::mutex mutex_; 00102 00103 bool compute_descriptors_; 00104 00110 virtual void findFeatures(RGBDFrame& frame, const cv::Mat& input_img) = 0; 00111 00112 private: 00113 00114 int smooth_; 00115 double max_range_; 00116 double max_stdev_; 00117 }; 00118 00119 typedef boost::shared_ptr<FeatureDetector> FeatureDetectorPtr; 00120 00121 } // namespace ccny_rgbd 00122 00123 #endif // CCNY_RGBD_FEATURE_DETECTOR_H