Go to the documentation of this file.00001
00024 #ifndef RGBDTOOLS_FEATURE_DETECTOR_H
00025 #define RGBDTOOLS_FEATURE_DETECTOR_H
00026
00027 #include <vector>
00028 #include <boost/thread/mutex.hpp>
00029
00030 #include "rgbdtools/types.h"
00031 #include "rgbdtools/rgbd_frame.h"
00032
00033 namespace rgbdtools {
00034
00037 class FeatureDetector
00038 {
00039 public:
00040
00043 FeatureDetector();
00044
00047 virtual ~FeatureDetector();
00048
00053 void findFeatures(RGBDFrame& frame);
00054
00064 inline int getSmooth() const;
00065
00069 inline double getMaxRange() const;
00070
00074 inline double getMaxStDev() const;
00075
00085 void setSmooth(int smooth);
00086
00090 void setMaxRange(double max_range);
00091
00095 void setMaxStDev(double max_stdev);
00096
00097 void setComputeDescriptors(bool compute_descriptors);
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 }
00122
00123 #endif // RGBDTOOLS_FEATURE_DETECTOR_H