feature_adjuster.h
Go to the documentation of this file.
00001 #ifndef FEATUREADJUSTER_H
00002 #define FEATUREADJUSTER_H
00003 #include <opencv2/features2d/features2d.hpp>
00004 
00011 class DetectorAdjuster: public cv::AdjusterAdapter
00012 {
00013 public:
00015     DetectorAdjuster(const char* detector_name, double initial_thresh=200.f, double min_thresh=2, double max_thresh=10000, double increase_factor=1.3, double decrease_factor=0.7 );
00016     
00017     virtual void tooFew(int minv, int n_detected);
00018     virtual void tooMany(int maxv, int n_detected);
00019     virtual bool good() const;
00020 
00021     virtual cv::Ptr<cv::AdjusterAdapter> clone() const;
00022 
00023     void setIncreaseFactor(double new_factor);
00024     void setDecreaseFactor(double new_factor);
00025 protected:
00026     virtual void detectImpl( const cv::Mat& image, std::vector<cv::KeyPoint>& keypoints, const cv::Mat& mask=cv::Mat() ) const;
00027 
00028     double thresh_, min_thresh_, max_thresh_;
00029     double increase_factor_, decrease_factor_;
00030     const char* detector_name_;
00031 };
00032 
00035 class StatefulFeatureDetector : public cv::FeatureDetector {
00036   public:
00037     virtual cv::Ptr<StatefulFeatureDetector> clone() const = 0;
00038 };
00039 
00053 class VideoDynamicAdaptedFeatureDetector: public StatefulFeatureDetector
00054 {
00055 public:
00056 
00063      VideoDynamicAdaptedFeatureDetector( cv::Ptr<cv::AdjusterAdapter> adjuster, int min_features=400, int max_features=500, int max_iters=5);
00064 
00065     virtual cv::Ptr<StatefulFeatureDetector> clone() const;
00066     virtual bool empty() const;
00067 
00068 protected:
00069     virtual void detectImpl( const cv::Mat& image, std::vector<cv::KeyPoint>& keypoints, const cv::Mat& mask=cv::Mat() ) const;
00070 
00071 private:
00072     VideoDynamicAdaptedFeatureDetector& operator=(const VideoDynamicAdaptedFeatureDetector&);
00073     VideoDynamicAdaptedFeatureDetector(const VideoDynamicAdaptedFeatureDetector&);
00074 
00075     int escape_iters_;
00076     int min_features_, max_features_;
00077     mutable cv::Ptr<cv::AdjusterAdapter> adjuster_;
00078 };
00079 
00080 
00081 
00082 
00083 
00084 
00085 /*
00086  * Adapts a detector to partition the source image into a grid and detect
00087  * points in each cell. Considers the overlap between cells required for
00088  * not losing keypoints
00089  */
00090 class VideoGridAdaptedFeatureDetector : public StatefulFeatureDetector
00091 {
00092 public:
00093     /*
00094      * \param detector            Detector that will be adapted.
00095      * \param maxTotalKeypoints   Maximum count of keypoints detected on the image. Only the strongest keypoints will be keeped.
00096      *  \param gridRows           Grid rows count.
00097      *  \param gridCols           Grid column count.
00098      *  \param edgeThreshold     how much overlap is needed, to not lose keypoints at the inner borders of the grid (should be the same value, e.g., as edgeThreshold for ORB)
00099      */
00100     VideoGridAdaptedFeatureDetector(const cv::Ptr<StatefulFeatureDetector>& detector,
00101                                     int maxTotalKeypoints=1000, int gridRows=4, 
00102                                     int gridCols=4, int edgeThreshold=31 );
00103     
00104     // TODO implement read/write
00105     virtual bool empty() const;
00106     virtual cv::Ptr<StatefulFeatureDetector> clone() const;
00107 
00108 protected:
00109     VideoGridAdaptedFeatureDetector& operator=(const VideoGridAdaptedFeatureDetector&);
00110     VideoGridAdaptedFeatureDetector(const VideoGridAdaptedFeatureDetector&);
00111 
00112     virtual void detectImpl( const cv::Mat& image, std::vector<cv::KeyPoint>& keypoints, const cv::Mat& mask=cv::Mat() ) const;
00113 
00114     std::vector<cv::Ptr<StatefulFeatureDetector> > detectors;
00115     int maxTotalKeypoints;
00116     int gridRows;
00117     int gridCols;
00118     int edgeThreshold; 
00119 };
00120 
00121 
00122 #endif


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45