feature_utils.h
Go to the documentation of this file.
00001 /*
00002  * feature_utils.h
00003  *
00004  *  Created on: Oct 17, 2010
00005  *      Author: ethan
00006  */
00007 
00008 #ifndef FEATURE_UTILS_H_
00009 #define FEATURE_UTILS_H_
00010 
00011 #include <opencv2/core/core.hpp>
00012 #include <opencv2/features2d/features2d.hpp>
00013 
00014 #include <limits>
00015 #include <string>
00016 #include <vector>
00017 #include <cmath>
00018 
00019 namespace pano {
00020 template<typename T, const int NORM_TYPE = cv::NORM_L2>
00021 struct _RadiusPoint {
00022         const float r;
00023         const T&pt2;
00024         float n;
00025         _RadiusPoint(float r, const T&pt2) :
00026                 r(r), pt2(pt2), n(0) {
00027         }
00028         bool cp(const T& pt1) {
00029                 n = norm(cv::Mat(pt1), cv::Mat(pt2), NORM_TYPE);
00030                 return r > n;
00031         }
00032 
00033 };
00034 template<typename T>
00035 _RadiusPoint<T> RadiusPoint(float r, const T&pt2) {
00036         return _RadiusPoint<T> (r, pt2);
00037 }
00038 
00039 inline bool operator==(const cv::Point2f& pt1, _RadiusPoint<cv::Point2f> pt2) {
00040         return pt2.cp(pt1);
00041 }
00042 inline bool operator==(const cv::Point3f& pt1, _RadiusPoint<cv::Point3f> pt2) {
00043         return pt2.cp(pt1);
00044 }
00045 
00048 typedef std::vector<cv::KeyPoint> KeypointVector;
00049 
00052 typedef std::vector<cv::DMatch> MatchesVector;
00053 
00056 void KeyPointsToPoints(const KeypointVector& keypts,
00057                 std::vector<cv::Point2f>& pts);
00058 void PointsToKeyPoints(const std::vector<cv::Point2f>& keypts,
00059                 KeypointVector& pts);
00060 
00063 void matches2points(const KeypointVector& train, const KeypointVector& query,
00064                 const MatchesVector& matches, std::vector<cv::Point2f>& pts_train,
00065                 std::vector<cv::Point2f>& pts_query);
00066 
00067 inline float scorematch(const std::vector<cv::DMatch>& matches) {
00068         float s = 0;
00069         std::vector<cv::DMatch>::const_iterator it = matches.begin();
00070         while (it != matches.end()) {
00071                 s += it->distance;
00072                 ++it;
00073         }
00074         return s / matches.size();
00075 }
00076 
00077 
00078 class GriddedDynamicDetectorAdaptor: public cv::FeatureDetector {
00079 public:
00080         template<typename Adjuster>
00081         GriddedDynamicDetectorAdaptor(int max_total_keypoints, int escape_iters_per_cell, int _gridRows,
00082                         int _gridCols, const Adjuster& adjuster) :
00083                 maxTotalKeypoints(max_total_keypoints), gridRows(_gridRows), gridCols(
00084                                 _gridCols), detectors_(gridCols * gridRows) {
00085                 int maxPerCell = maxTotalKeypoints / (gridRows * gridCols);
00086                 for (int i = 0; i < (int) detectors_.size(); ++i) {
00087                         detectors_[i] = new cv::DynamicAdaptedFeatureDetector(new Adjuster(adjuster),maxPerCell
00088                                         * 0.8, maxPerCell * 1.2,escape_iters_per_cell);
00089                 }
00090         }
00091         virtual ~GriddedDynamicDetectorAdaptor() {
00092         }
00093 
00094 protected:
00095         virtual void detectImpl(const cv::Mat& image,
00096                         std::vector<cv::KeyPoint>& keypoints, const cv::Mat& mask =
00097                                         cv::Mat()) const;
00098         int maxTotalKeypoints;
00099         int gridRows;
00100         int gridCols;
00101         std::vector<cv::Ptr<FeatureDetector> > detectors_;
00102 };
00103 
00104 }
00105 
00106 #endif /* FEATURE_UTILS_H_ */


pano_core
Author(s): Ethan Rublee
autogenerated on Wed Aug 26 2015 16:34:01