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
00016 #include <algorithm>
00017
00018 #define MAX_DETECTORS 10
00019
00020 #define MATCHING_MODE_NN 0
00021 #define MATCHING_MODE_NNDR 1
00022 #define MATCHING_MODE_SVM 2
00023
00024 void fadeImage(const cv::Mat& src, cv::Mat& dst);
00025
00026 void drawRichKeyPoints(const cv::Mat& src, std::vector<cv::KeyPoint>& kpts, cv::Mat& dst);
00027 void filterKeyPoints(std::vector<cv::KeyPoint>& kpts, unsigned int maxSize = 0, unsigned int maxFeatures = 0);
00028
00030 double calculateFeatureSpeeds(const vector<cv::Point2f>& pts1, const vector<cv::Point2f>& pts2, vector<cv::Point2f>& velocities, double time1, double time2);
00031
00032 void crossCheckMatching( cv::Ptr<cv::DescriptorMatcher>& descriptorMatcher,
00033 const cv::Mat& descriptors1, const cv::Mat& descriptors2,
00034 vector<cv::DMatch>& filteredMatches12, int knn );
00035
00036 void filterTrackingsByRadialProportion(vector<cv::Point2f>& pts1, vector<cv::Point2f>& pts2, cv::Mat& K, cv::Mat& newCamMat, cv::Mat& distCoeffs, cv::Size& imSize, double prop = 1.00);
00037
00038 double generateVirtualPointset(const vector<cv::Point2f>& pts1, const vector<cv::Point2f>& pts2, vector<cv::Point2f>& virtual_pts, double bias_fraction = 0.5);
00039
00041 void transformPoints(vector<cv::Point2f>& pts1, cv::Mat& H);
00042
00044 void trackPoints(const cv::Mat& im1, const cv::Mat& im2, vector<cv::Point2f>& pts1, vector<cv::Point2f>& pts2, int distanceConstraint, double thresh, vector<unsigned int>& lostIndices, cv::Mat H12 = cv::Mat(), cameraParameters camData = cameraParameters());
00045
00047 void trackPoints2(const cv::Mat& im1, const cv::Mat& im2, vector<cv::Point2f>& pts1, vector<cv::Point2f>& pts2, int distanceConstraint, double thresh, vector<unsigned int>& lostIndices, const cv::Size patternSize, double& errorThreshold);
00048
00050 void sortKeyPoints(vector<cv::KeyPoint>& KeyPoints, unsigned int maxKeyPoints = -1);
00051
00052 void checkDistances(vector<cv::Point2f>& pts1, vector<cv::Point2f>& pts2, vector<uchar>& statusVec, double distanceConstraint);
00053
00055 void displayKeyPoints(const cv::Mat& image, const vector<cv::KeyPoint>& KeyPoints, cv::Mat& outImg, const cv::Scalar& color, int thickness = 1, bool pointsOnly = false);
00056
00057 void showMatches(const cv::Mat& pim1, vector<cv::Point2f>& pts1, const cv::Mat& pim2, vector<cv::Point2f>& pts2, cv::Mat& drawImg);
00058
00060 void displayKeyPoints(const cv::Mat& image, const vector<cv::Point2f>& pts, cv::Mat& outImg, cv::Scalar color, int thickness = 1, bool pointsOnly = false);
00061
00063 void drawMatchPaths(cv::Mat& src, cv::Mat& dst, vector<cv::KeyPoint>& kp1, vector<cv::KeyPoint>& kp2, vector<vector<cv::DMatch> >& matches1to2);
00064
00066 void drawMatchPaths(cv::Mat& src, cv::Mat& dst, vector<cv::Point2f>& kp1, vector<cv::Point2f>& kp2, const cv::Scalar& color = CV_RGB(255, 0, 0));
00067
00069 void createMatchingMatrix(cv::Mat& MatchingMatrix, const cv::Mat& desc1, const cv::Mat& desc2);
00070
00072 void twoWayPriorityMatching(cv::Mat& matchingMatrix, vector<vector<cv::DMatch> >& bestMatches, int mode = MATCHING_MODE_NN);
00073
00075 double reweightDistanceWithLinearSVM(double dist, double ratio, double gradient);
00076
00078 bool checkSufficientFeatureSpread(vector<cv::Point2f>& pts, cv::Size matSize, int minFeaturesInImage);
00079
00081 double calcDistance(double dist, double ratio, double *coeffs);
00082
00083 void sortMatches(vector<vector<cv::DMatch> >& matches1to2);
00084 void filterMatches(vector<vector<cv::DMatch> >& matches1to2, double threshold);
00085 void constrainMatchingMatrix(cv::Mat& MatchingMatrix, vector<cv::KeyPoint>& kp1, vector<cv::KeyPoint>& kp2, int distanceConstraint, double sizeConstraint = 0.0);
00086
00087 void filterVectors(vector<cv::Point2f>& pts1, vector<cv::Point2f>& pts2, vector<uchar>& statusVec, double distanceConstraint = 10.0, bool epipolarCheck = false);
00088
00089 void assignMinimumRadii(vector<cv::KeyPoint>& pts);
00090
00091 double estimateSalience(cv::Mat& img, cv::Point2f& center, double radius);
00092 double estimateStability(cv::Mat& img, cv::Point2f& center, double radius);
00093 bool constructPatch(cv::Mat& img, cv::Mat& patch, cv::Point2f& center, double radius, int cells = 3);
00094 double getValueFromPatch(cv::Mat& patch);
00095 double getPatchVariance(const cv::Mat& patch) ;
00096 void assignEigenVectorResponses(const cv::Mat& img, vector<cv::KeyPoint>& pts);
00097 void assignStabilityResponses(const cv::Mat& img, vector<cv::KeyPoint>& pts);
00098 void extendKeyPoints(cv::Mat& img, vector<cv::KeyPoint>& pts, bool updateStrength, bool updateLocation);
00099
00100 void filterBlandKeyPoints(cv::Mat& img, vector<cv::KeyPoint>& pts, double thresh = 3.0);
00101
00102 double distanceBetweenPoints(const cv::KeyPoint& pt1, const cv::KeyPoint& pt2);
00103 double distanceBetweenPoints(const cv::Point2f& pt1, const cv::Point2f& pt2);
00104
00106 void filterTrackedPoints(vector<uchar>& statusVec, vector<float>& err, double maxError);
00107
00108
00109 void randomlyReducePoints(vector<cv::Point2f>& pts, int maxFeatures);
00110
00111 void markStationaryPoints(vector<cv::Point2f>&pts1, vector<cv::Point2f>&pts2, vector<uchar>&statusVec);
00112
00113 void markAbsentPoints(vector<cv::Point2f>&pts1, vector<cv::Point2f>&pts2, vector<uchar>&statusVec, cv::Size imSize);
00114
00115 void initializeDrawingColors(cv::Scalar* kColors, cv::Scalar* tColors, int num);
00116
00117 void concatenateWithExistingPoints(vector<cv::Point2f> &pts, vector<cv::Point2f>& kps, int size, double min_sep = 3, bool debug = false);
00118
00119 bool checkRoomForFeature(vector<cv::Point2f>& pts, cv::Point2f& candidate, double dist = 3.0);
00120
00121 void reduceProximalCandidates(vector<cv::Point2f>& existing, vector<cv::Point2f>& candidates);
00122
00123 void reduceEdgyCandidates(vector<cv::Point2f>& candidates, cameraParameters& camData);
00124
00125 void reduceEdgyFeatures(vector<cv::KeyPoint>& KeyPoints, cameraParameters& camData);
00126
00127 void markBlandTracks(cv::Mat& img, vector<cv::Point2f>& pts, vector<uchar>& statusVec, double thresh = 3.0);
00128
00129 void reduceUnrefinedCandidates(vector<cv::Point2f>& candidates);
00130
00131 void markUnrefinedPoints(vector<cv::Point2f>& pts, vector<uchar>&statusVec);
00132
00133 void markEdgyTracks(vector<cv::Point2f>& pts, vector<uchar>& statusVec, cameraParameters& camData);
00134
00135 void reduceWeakFeatures(cv::Mat& im, vector<cv::KeyPoint>& feats, double minResponse);
00136
00137 #endif