$search
00001 00005 #ifndef _THERMALVIS_FEATURES_H_ 00006 #define _THERMALVIS_FEATURES_H_ 00007 00008 #include "general_resources.hpp" 00009 #include "opencv_resources.hpp" 00010 00011 #include "improc.hpp" 00012 #include "tools.hpp" 00013 #include "camera.hpp" 00014 00015 //HGH 00016 #include <algorithm> 00017 00018 #define MAX_DETECTORS 10 00019 00020 void fadeImage(const Mat& src, Mat& dst); 00021 00022 void drawRichKeypoints(const cv::Mat& src, std::vector<cv::KeyPoint>& kpts, cv::Mat& dst); 00023 void filterKeypoints(std::vector<cv::KeyPoint>& kpts, int maxSize = 0, int maxFeatures = 0); 00024 00025 void crossCheckMatching( Ptr<DescriptorMatcher>& descriptorMatcher, 00026 const Mat& descriptors1, const Mat& descriptors2, 00027 vector<DMatch>& filteredMatches12, int knn ); 00028 00029 void filterTrackingsByRadialProportion(vector<Point2f>& pts1, vector<Point2f>& pts2, Mat& K, Mat& newCamMat, Mat& distCoeffs, Size& imSize, double prop = 1.00); 00030 00032 void transformPoints(vector<Point2f>& pts1, Mat& H); 00033 00035 void trackPoints(const Mat& im1, const Mat& im2, vector<Point2f>& pts1, vector<Point2f>& pts2, int distanceConstraint, double thresh, vector<unsigned int>& lostIndices, Mat H12 = cv::Mat(), cameraParameters camData = cameraParameters()); 00036 00038 void trackPoints2(const Mat& im1, const Mat& im2, vector<Point2f>& pts1, vector<Point2f>& pts2, int distanceConstraint, double thresh, vector<unsigned int>& lostIndices, const Size patternSize, double& errorThreshold); 00039 00041 void sortKeypoints(vector<KeyPoint>& keypoints, unsigned int maxKeypoints = -1); 00042 00044 void displayKeypoints(const Mat& image, const vector<KeyPoint>& keypoints, Mat& outImg, const Scalar& color, int thickness = 1); 00045 00046 void showMatches(const Mat& pim1, vector<Point2f>& pts1, const Mat& pim2, vector<Point2f>& pts2, Mat& drawImg); 00047 00049 void displayKeypoints(const Mat& image, const vector<Point2f>& pts, Mat& outImg, const Scalar& color, int thickness = 1); 00050 00052 void drawMatchPaths(Mat& src, Mat& dst, vector<KeyPoint>& kp1, vector<KeyPoint>& kp2, vector<vector<DMatch> >& matches1to2); 00053 00055 void drawMatchPaths(Mat& src, Mat& dst, vector<Point2f>& kp1, vector<Point2f>& kp2, const Scalar& color = CV_RGB(255, 0, 0)); 00056 00058 void createMatchingMatrix(Mat& matchingMatrix, const Mat& desc1, const Mat& desc2); 00059 00061 void twoWayPriorityMatching(Mat& matchingMatrix, vector<vector<DMatch> >& bestMatches); 00062 00064 double reweightDistanceWithLinearSVM(double dist, double ratio, double gradient); 00065 00067 bool checkSufficientFeatureSpread(vector<Point2f>& pts, Size matSize, int minFeaturesInImage); 00068 00070 double calcDistance(double dist, double ratio, double *coeffs); 00071 00072 void sortMatches(vector<vector<DMatch> >& matches1to2); 00073 void filterMatches(vector<vector<DMatch> >& matches1to2, double threshold); 00074 void constrainMatchingMatrix(Mat& matchingMatrix, vector<KeyPoint>& kp1, vector<KeyPoint>& kp2, int distanceConstraint, double sizeConstraint); 00075 00076 void filterVectors(vector<Point2f>& pts1, vector<Point2f>& pts2, vector<uchar>& statusVec, double distanceConstraint = 10.0, bool epipolarCheck = false); 00077 00078 void assignMinimumRadii(vector<KeyPoint>& pts); 00079 00080 double estimateSalience(Mat& img, Point2f& center, double radius); 00081 double estimateStability(Mat& img, Point2f& center, double radius); 00082 bool constructPatch(Mat& img, Mat& patch, Point2f& center, double radius, int cells = 3); 00083 double getValueFromPatch(Mat& patch); 00084 double getPatchVariance(const Mat& patch) ; 00085 void assignEigenVectorResponses(const Mat& img, vector<KeyPoint>& pts); 00086 void assignStabilityResponses(const Mat& img, vector<KeyPoint>& pts); 00087 void extendKeypoints(Mat& img, vector<KeyPoint>& pts, bool updateStrength, bool updateLocation); 00088 00089 void filterBlandKeypoints(Mat& img, vector<KeyPoint>& pts, double thresh = 3.0); 00090 00091 double distanceBetweenPoints(const KeyPoint& pt1, const KeyPoint& pt2); 00092 double distanceBetweenPoints(const Point2f& pt1, const Point2f& pt2); 00093 00095 void filterTrackedPoints(vector<uchar>& statusVec, vector<float>& err, double maxError); 00096 00097 00098 void randomlyReducePoints(vector<Point2f>& pts, int maxFeatures); 00099 00100 void markStationaryPoints(vector<Point2f>&pts1, vector<Point2f>&pts2, vector<uchar>&statusVec); 00101 00102 void markAbsentPoints(vector<Point2f>&pts1, vector<Point2f>&pts2, vector<uchar>&statusVec, cv::Size imSize); 00103 00104 void initializeDrawingColors(Scalar* kColors, Scalar* tColors, int num); 00105 00106 void concatenateWithExistingPoints(vector<Point2f> &pts, vector<Point2f>& kps, int size, double min_sep = 3); 00107 00108 bool checkRoomForFeature(vector<Point2f>& pts, Point2f& candidate, double dist = 3.0); 00109 00110 void reduceProximalCandidates(vector<Point2f>& existing, vector<Point2f>& candidates); 00111 00112 void reduceEdgyCandidates(vector<Point2f>& candidates, cameraParameters& camData); 00113 00114 void reduceEdgyFeatures(vector<KeyPoint>& keypoints, cameraParameters& camData); 00115 00116 void markBlandTracks(Mat& img, vector<Point2f>& pts, vector<uchar>& statusVec, double thresh = 3.0); 00117 00118 void reduceUnrefinedCandidates(vector<Point2f>& candidates); 00119 00120 void markUnrefinedPoints(vector<Point2f>& pts, vector<uchar>&statusVec); 00121 00122 void markEdgyTracks(vector<Point2f>& pts, vector<uchar>& statusVec, cameraParameters& camData); 00123 00124 void reduceWeakFeatures(Mat& im, vector<KeyPoint>& feats, double minResponse); 00125 00126 #endif