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 #ifndef feature_tracker_h_DEFINED
00036 #define feature_tracker_h_DEFINED
00037 
00038 
00039 #include <opencv2/core/core.hpp>
00040 #include <opencv2/features2d/features2d.hpp>
00041 #include <opencv2/nonfree/features2d.hpp>
00042 
00043 #include <vector>
00044 #include <deque>
00045 #include <cpl_visual_features/motion/flow_types.h>
00046 #include <utility>
00047 
00048 namespace cpl_visual_features
00049 {
00050 
00051 typedef std::vector<float> Descriptor;
00052 typedef std::vector<Descriptor> Descriptors;
00053 typedef std::vector<cv::KeyPoint> KeyPoints;
00054 
00055 class FeatureTracker
00056 {
00057  public:
00058   FeatureTracker(std::string name, double hessian_thresh=250, int num_octaves=4,
00059                  int num_layers=2, bool extended=true, bool upright=false,
00060                  bool use_fast=false);
00061 
00062   
00063   
00064   
00065 
00066   void initTracks(cv::Mat& frame);
00067 
00068   AffineFlowMeasures updateTracksLK(cv::Mat& cur_frame, cv::Mat& prev_frame);
00069 
00070   AffineFlowMeasures updateTracks(const cv::Mat& frame);
00071 
00072   AffineFlowMeasures updateTracks(const cv::Mat& frame, const cv::Mat& mask);
00073 
00074   
00075   
00076   
00077  protected:
00078   
00079 
00080 
00081 
00082 
00083 
00084 
00085 
00086   double SSD(Descriptor& a, Descriptor& b);
00087 
00088   
00089 
00090 
00091 
00092 
00093 
00094 
00095 
00096 
00097 
00098   std::pair<int, float> ratioTest(Descriptor& a, std::vector<Descriptor>& bList,
00099                                   double threshold);
00100 
00109   void findMatches(Descriptors& descriptors1, Descriptors& descriptors2,
00110                    std::vector<int>& matches1, std::vector<int>& matches2,
00111                    std::vector<float>& scores);
00112 
00113   
00114   
00115   
00116 
00117   void updateCurrentDescriptors(const cv::Mat& frame, const cv::Mat& mask);
00118 
00119  public:
00120   
00121   
00122   
00123 
00124   bool isInitialized() const
00125   {
00126     return initialized_;
00127   }
00128 
00129   void setMinFlowThresh(int min_thresh)
00130   {
00131     min_flow_thresh_= min_thresh;
00132   }
00133 
00134   void setKLTCornerThresh(double corner_thresh)
00135   {
00136     klt_corner_thresh_ = corner_thresh;
00137   }
00138 
00139   void setKLTCornerMinDist(double min_dist)
00140   {
00141     klt_corner_min_dist_ = min_dist;
00142   }
00143 
00144   void setKLTMaxCorners(int max_corners)
00145   {
00146     max_corners_ = max_corners;
00147   }
00148 
00149   void setUseFast(bool use_fast)
00150   {
00151     use_fast_ = use_fast;
00152   }
00153   void stop() { initialized_ = false; }
00154 
00155   AffineFlowMeasures getMostRecentFlow() const
00156   {
00157     return cur_flow_;
00158   }
00159 
00160   Descriptors getMostRecentDescriptors() const
00161   {
00162     return cur_descriptors_;
00163   }
00164 
00165   KeyPoints getMostRecentKeyPoints() const
00166   {
00167     return cur_keypoints_;
00168   }
00169 
00170   std::vector<float> getMostRecentScores() const
00171   {
00172     return cur_scores_;
00173   }
00174 
00175  public:
00176   cv::SURF surf_;
00177  protected:
00178   KeyPoints prev_keypoints_;
00179   KeyPoints cur_keypoints_;
00180   Descriptors prev_descriptors_;
00181   Descriptors cur_descriptors_;
00182   AffineFlowMeasures cur_flow_;
00183   std::vector<float> cur_scores_;
00184   bool initialized_;
00185   double ratio_threshold_;
00186   std::string window_name_;
00187   int min_flow_thresh_;
00188   int max_corners_;
00189   double klt_corner_thresh_;
00190   double klt_corner_min_dist_;
00191   bool use_fast_;
00192 };
00193 }
00194 #endif // feature_tracker_h_DEFINED