Declarations for local feature detection, description and cv::Matching. More...
#include "general_resources.hpp"
#include "opencv_resources.hpp"
#include "improc.hpp"
#include "tools.hpp"
#include "camera.hpp"
#include <algorithm>
Go to the source code of this file.
Defines | |
#define | MATCHING_MODE_NN 0 |
#define | MATCHING_MODE_NNDR 1 |
#define | MATCHING_MODE_SVM 2 |
#define | MAX_DETECTORS 10 |
Functions | |
void | assignEigenVectorResponses (const cv::Mat &img, vector< cv::KeyPoint > &pts) |
void | assignMinimumRadii (vector< cv::KeyPoint > &pts) |
void | assignStabilityResponses (const cv::Mat &img, vector< cv::KeyPoint > &pts) |
double | calcDistance (double dist, double ratio, double *coeffs) |
Calculates linear SVM cv::Match distance. | |
double | calculateFeatureSpeeds (const vector< cv::Point2f > &pts1, const vector< cv::Point2f > &pts2, vector< cv::Point2f > &velocities, double time1, double time2) |
Calculates velocities of features. | |
void | checkDistances (vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, vector< uchar > &statusVec, double distanceConstraint) |
bool | checkRoomForFeature (vector< cv::Point2f > &pts, cv::Point2f &candidate, double dist=3.0) |
bool | checkSufficientFeatureSpread (vector< cv::Point2f > &pts, cv::Size matSize, int minFeaturesInImage) |
Checks whether there is sufficient spread of features in an image for effective tracking. | |
void | concatenateWithExistingPoints (vector< cv::Point2f > &pts, vector< cv::Point2f > &kps, int size, double min_sep=3, bool debug=false) |
void | constrainMatchingMatrix (cv::Mat &MatchingMatrix, vector< cv::KeyPoint > &kp1, vector< cv::KeyPoint > &kp2, int distanceConstraint, double sizeConstraint=0.0) |
bool | constructPatch (cv::Mat &img, cv::Mat &patch, cv::Point2f ¢er, double radius, int cells=3) |
void | createMatchingMatrix (cv::Mat &MatchingMatrix, const cv::Mat &desc1, const cv::Mat &desc2) |
Creates cv::Matrix representing descriptor distance between sets of features. | |
void | crossCheckMatching (cv::Ptr< cv::DescriptorMatcher > &descriptorMatcher, const cv::Mat &descriptors1, const cv::Mat &descriptors2, vector< cv::DMatch > &filteredMatches12, int knn) |
void | displayKeyPoints (const cv::Mat &image, const vector< cv::KeyPoint > &KeyPoints, cv::Mat &outImg, const cv::Scalar &color, int thickness=1, bool pointsOnly=false) |
Prints KeyPoints onto a copy of an image. | |
void | displayKeyPoints (const cv::Mat &image, const vector< cv::Point2f > &pts, cv::Mat &outImg, cv::Scalar color, int thickness=1, bool pointsOnly=false) |
Prints KeyPoints onto a copy of an image. | |
double | distanceBetweenPoints (const cv::KeyPoint &pt1, const cv::KeyPoint &pt2) |
double | distanceBetweenPoints (const cv::Point2f &pt1, const cv::Point2f &pt2) |
void | drawMatchPaths (cv::Mat &src, cv::Mat &dst, vector< cv::KeyPoint > &kp1, vector< cv::KeyPoint > &kp2, vector< vector< cv::DMatch > > &matches1to2) |
Prints cv::Match paths onto a copy of an image, given unfiltered points and cv::Matches structure. | |
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)) |
Prints cv::Match paths onto a copy of an image, given vectors containing corresponding points. | |
void | drawRichKeyPoints (const cv::Mat &src, std::vector< cv::KeyPoint > &kpts, cv::Mat &dst) |
double | estimateSalience (cv::Mat &img, cv::Point2f ¢er, double radius) |
double | estimateStability (cv::Mat &img, cv::Point2f ¢er, double radius) |
void | extendKeyPoints (cv::Mat &img, vector< cv::KeyPoint > &pts, bool updateStrength, bool updateLocation) |
void | fadeImage (const cv::Mat &src, cv::Mat &dst) |
void | filterBlandKeyPoints (cv::Mat &img, vector< cv::KeyPoint > &pts, double thresh=3.0) |
void | filterKeyPoints (std::vector< cv::KeyPoint > &kpts, unsigned int maxSize=0, unsigned int maxFeatures=0) |
void | filterMatches (vector< vector< cv::DMatch > > &matches1to2, double threshold) |
void | filterTrackedPoints (vector< uchar > &statusVec, vector< float > &err, double maxError) |
Sets flags to zero for tracked features that have too high an error. | |
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) |
void | filterVectors (vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, vector< uchar > &statusVec, double distanceConstraint=10.0, bool epipolarCheck=false) |
double | generateVirtualPointset (const vector< cv::Point2f > &pts1, const vector< cv::Point2f > &pts2, vector< cv::Point2f > &virtual_pts, double bias_fraction=0.5) |
double | getPatchVariance (const cv::Mat &patch) |
double | getValueFromPatch (cv::Mat &patch) |
void | initializeDrawingColors (cv::Scalar *kColors, cv::Scalar *tColors, int num) |
void | markAbsentPoints (vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, vector< uchar > &statusVec, cv::Size imSize) |
void | markBlandTracks (cv::Mat &img, vector< cv::Point2f > &pts, vector< uchar > &statusVec, double thresh=3.0) |
void | markEdgyTracks (vector< cv::Point2f > &pts, vector< uchar > &statusVec, cameraParameters &camData) |
void | markStationaryPoints (vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, vector< uchar > &statusVec) |
void | markUnrefinedPoints (vector< cv::Point2f > &pts, vector< uchar > &statusVec) |
void | randomlyReducePoints (vector< cv::Point2f > &pts, int maxFeatures) |
void | reduceEdgyCandidates (vector< cv::Point2f > &candidates, cameraParameters &camData) |
void | reduceEdgyFeatures (vector< cv::KeyPoint > &KeyPoints, cameraParameters &camData) |
void | reduceProximalCandidates (vector< cv::Point2f > &existing, vector< cv::Point2f > &candidates) |
void | reduceUnrefinedCandidates (vector< cv::Point2f > &candidates) |
void | reduceWeakFeatures (cv::Mat &im, vector< cv::KeyPoint > &feats, double minResponse) |
double | reweightDistanceWithLinearSVM (double dist, double ratio, double gradient) |
Uses a linear SVM to reweight the cv::Match distances so that they can be more effectively sorted. | |
void | showMatches (const cv::Mat &pim1, vector< cv::Point2f > &pts1, const cv::Mat &pim2, vector< cv::Point2f > &pts2, cv::Mat &drawImg) |
void | sortKeyPoints (vector< cv::KeyPoint > &KeyPoints, unsigned int maxKeyPoints=-1) |
Sorts features in descending order of strength, and culls beyond a certain quantity. | |
void | sortMatches (vector< vector< cv::DMatch > > &matches1to2) |
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()) |
Implement optical flow algorithm and filtering. | |
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) |
Implement optical flow algorithm and filtering for calibrating stereo cameras. | |
void | transformPoints (vector< cv::Point2f > &pts1, cv::Mat &H) |
Transforms points using homography. | |
void | twoWayPriorityMatching (cv::Mat &matchingMatrix, vector< vector< cv::DMatch > > &bestMatches, int mode=MATCHING_MODE_NN) |
cv::Matches features between images given a cv::Matching cv::Matrix |
Declarations for local feature detection, description and cv::Matching.
Definition in file features.hpp.
#define MATCHING_MODE_NN 0 |
Definition at line 20 of file features.hpp.
#define MATCHING_MODE_NNDR 1 |
Definition at line 21 of file features.hpp.
#define MATCHING_MODE_SVM 2 |
Definition at line 22 of file features.hpp.
#define MAX_DETECTORS 10 |
Definition at line 18 of file features.hpp.
void assignEigenVectorResponses | ( | const cv::Mat & | img, |
vector< cv::KeyPoint > & | pts | ||
) |
void assignMinimumRadii | ( | vector< cv::KeyPoint > & | pts | ) |
void assignStabilityResponses | ( | const cv::Mat & | img, |
vector< cv::KeyPoint > & | pts | ||
) |
double calcDistance | ( | double | dist, |
double | ratio, | ||
double * | coeffs | ||
) |
Calculates linear SVM cv::Match distance.
Definition at line 1634 of file features.cpp.
double calculateFeatureSpeeds | ( | const vector< cv::Point2f > & | pts1, |
const vector< cv::Point2f > & | pts2, | ||
vector< cv::Point2f > & | velocities, | ||
double | time1, | ||
double | time2 | ||
) |
Calculates velocities of features.
Definition at line 8 of file features.cpp.
void checkDistances | ( | vector< cv::Point2f > & | pts1, |
vector< cv::Point2f > & | pts2, | ||
vector< uchar > & | statusVec, | ||
double | distanceConstraint | ||
) |
Definition at line 1775 of file features.cpp.
bool checkRoomForFeature | ( | vector< cv::Point2f > & | pts, |
cv::Point2f & | candidate, | ||
double | dist = 3.0 |
||
) |
Definition at line 392 of file features.cpp.
bool checkSufficientFeatureSpread | ( | vector< cv::Point2f > & | pts, |
cv::Size | matSize, | ||
int | minFeaturesInImage | ||
) |
Checks whether there is sufficient spread of features in an image for effective tracking.
Definition at line 1853 of file features.cpp.
void concatenateWithExistingPoints | ( | vector< cv::Point2f > & | pts, |
vector< cv::Point2f > & | kps, | ||
int | size, | ||
double | min_sep = 3 , |
||
bool | debug = false |
||
) |
Definition at line 441 of file features.cpp.
void constrainMatchingMatrix | ( | cv::Mat & | MatchingMatrix, |
vector< cv::KeyPoint > & | kp1, | ||
vector< cv::KeyPoint > & | kp2, | ||
int | distanceConstraint, | ||
double | sizeConstraint = 0.0 |
||
) |
Definition at line 1479 of file features.cpp.
bool constructPatch | ( | cv::Mat & | img, |
cv::Mat & | patch, | ||
cv::Point2f & | center, | ||
double | radius, | ||
int | cells = 3 |
||
) |
Definition at line 1006 of file features.cpp.
void createMatchingMatrix | ( | cv::Mat & | MatchingMatrix, |
const cv::Mat & | desc1, | ||
const cv::Mat & | desc2 | ||
) |
Creates cv::Matrix representing descriptor distance between sets of features.
Definition at line 1691 of file features.cpp.
void crossCheckMatching | ( | cv::Ptr< cv::DescriptorMatcher > & | descriptorMatcher, |
const cv::Mat & | descriptors1, | ||
const cv::Mat & | descriptors2, | ||
vector< cv::DMatch > & | filteredMatches12, | ||
int | knn | ||
) |
Definition at line 259 of file features.cpp.
void displayKeyPoints | ( | const cv::Mat & | image, |
const vector< cv::KeyPoint > & | KeyPoints, | ||
cv::Mat & | outImg, | ||
const cv::Scalar & | color, | ||
int | thickness = 1 , |
||
bool | pointsOnly = false |
||
) |
Prints KeyPoints onto a copy of an image.
Definition at line 1228 of file features.cpp.
void displayKeyPoints | ( | const cv::Mat & | image, |
const vector< cv::Point2f > & | pts, | ||
cv::Mat & | outImg, | ||
cv::Scalar | color, | ||
int | thickness = 1 , |
||
bool | pointsOnly = false |
||
) |
Prints KeyPoints onto a copy of an image.
Definition at line 1312 of file features.cpp.
double distanceBetweenPoints | ( | const cv::KeyPoint & | pt1, |
const cv::KeyPoint & | pt2 | ||
) |
Definition at line 1462 of file features.cpp.
double distanceBetweenPoints | ( | const cv::Point2f & | pt1, |
const cv::Point2f & | pt2 | ||
) |
Definition at line 1453 of file features.cpp.
void drawMatchPaths | ( | cv::Mat & | src, |
cv::Mat & | dst, | ||
vector< cv::KeyPoint > & | kp1, | ||
vector< cv::KeyPoint > & | kp2, | ||
vector< vector< cv::DMatch > > & | matches1to2 | ||
) |
Prints cv::Match paths onto a copy of an image, given unfiltered points and cv::Matches structure.
Definition at line 1906 of file features.cpp.
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) |
||
) |
Prints cv::Match paths onto a copy of an image, given vectors containing corresponding points.
Definition at line 1889 of file features.cpp.
void drawRichKeyPoints | ( | const cv::Mat & | src, |
std::vector< cv::KeyPoint > & | kpts, | ||
cv::Mat & | dst | ||
) |
Definition at line 61 of file features.cpp.
double estimateSalience | ( | cv::Mat & | img, |
cv::Point2f & | center, | ||
double | radius | ||
) |
Definition at line 1077 of file features.cpp.
double estimateStability | ( | cv::Mat & | img, |
cv::Point2f & | center, | ||
double | radius | ||
) |
Definition at line 1975 of file features.cpp.
void extendKeyPoints | ( | cv::Mat & | img, |
vector< cv::KeyPoint > & | pts, | ||
bool | updateStrength, | ||
bool | updateLocation | ||
) |
Definition at line 1046 of file features.cpp.
void fadeImage | ( | const cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Definition at line 166 of file features.cpp.
void filterBlandKeyPoints | ( | cv::Mat & | img, |
vector< cv::KeyPoint > & | pts, | ||
double | thresh = 3.0 |
||
) |
Definition at line 1190 of file features.cpp.
void filterKeyPoints | ( | std::vector< cv::KeyPoint > & | kpts, |
unsigned int | maxSize = 0 , |
||
unsigned int | maxFeatures = 0 |
||
) |
Definition at line 199 of file features.cpp.
void filterMatches | ( | vector< vector< cv::DMatch > > & | matches1to2, |
double | threshold | ||
) |
Definition at line 1429 of file features.cpp.
void filterTrackedPoints | ( | vector< uchar > & | statusVec, |
vector< float > & | err, | ||
double | maxError | ||
) |
Sets flags to zero for tracked features that have too high an error.
Definition at line 1748 of file features.cpp.
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 |
||
) |
Definition at line 316 of file features.cpp.
void filterVectors | ( | vector< cv::Point2f > & | pts1, |
vector< cv::Point2f > & | pts2, | ||
vector< uchar > & | statusVec, | ||
double | distanceConstraint = 10.0 , |
||
bool | epipolarCheck = false |
||
) |
Definition at line 1791 of file features.cpp.
double generateVirtualPointset | ( | const vector< cv::Point2f > & | pts1, |
const vector< cv::Point2f > & | pts2, | ||
vector< cv::Point2f > & | virtual_pts, | ||
double | bias_fraction = 0.5 |
||
) |
Definition at line 32 of file features.cpp.
double getPatchVariance | ( | const cv::Mat & | patch | ) |
Definition at line 2009 of file features.cpp.
double getValueFromPatch | ( | cv::Mat & | patch | ) |
Definition at line 1110 of file features.cpp.
void initializeDrawingColors | ( | cv::Scalar * | kColors, |
cv::Scalar * | tColors, | ||
int | num | ||
) |
Definition at line 466 of file features.cpp.
void markAbsentPoints | ( | vector< cv::Point2f > & | pts1, |
vector< cv::Point2f > & | pts2, | ||
vector< uchar > & | statusVec, | ||
cv::Size | imSize | ||
) |
Definition at line 981 of file features.cpp.
void markBlandTracks | ( | cv::Mat & | img, |
vector< cv::Point2f > & | pts, | ||
vector< uchar > & | statusVec, | ||
double | thresh = 3.0 |
||
) |
Definition at line 1160 of file features.cpp.
void markEdgyTracks | ( | vector< cv::Point2f > & | pts, |
vector< uchar > & | statusVec, | ||
cameraParameters & | camData | ||
) |
Definition at line 1928 of file features.cpp.
void markStationaryPoints | ( | vector< cv::Point2f > & | pts1, |
vector< cv::Point2f > & | pts2, | ||
vector< uchar > & | statusVec | ||
) |
Definition at line 1208 of file features.cpp.
void markUnrefinedPoints | ( | vector< cv::Point2f > & | pts, |
vector< uchar > & | statusVec | ||
) |
Definition at line 1139 of file features.cpp.
void randomlyReducePoints | ( | vector< cv::Point2f > & | pts, |
int | maxFeatures | ||
) |
Definition at line 1758 of file features.cpp.
void reduceEdgyCandidates | ( | vector< cv::Point2f > & | candidates, |
cameraParameters & | camData | ||
) |
Definition at line 372 of file features.cpp.
void reduceEdgyFeatures | ( | vector< cv::KeyPoint > & | KeyPoints, |
cameraParameters & | camData | ||
) |
Definition at line 347 of file features.cpp.
void reduceProximalCandidates | ( | vector< cv::Point2f > & | existing, |
vector< cv::Point2f > & | candidates | ||
) |
Definition at line 426 of file features.cpp.
void reduceUnrefinedCandidates | ( | vector< cv::Point2f > & | candidates | ) |
Definition at line 410 of file features.cpp.
void reduceWeakFeatures | ( | cv::Mat & | im, |
vector< cv::KeyPoint > & | feats, | ||
double | minResponse | ||
) |
Definition at line 526 of file features.cpp.
double reweightDistanceWithLinearSVM | ( | double | dist, |
double | ratio, | ||
double | gradient | ||
) |
Uses a linear SVM to reweight the cv::Match distances so that they can be more effectively sorted.
Definition at line 1642 of file features.cpp.
void showMatches | ( | const cv::Mat & | pim1, |
vector< cv::Point2f > & | pts1, | ||
const cv::Mat & | pim2, | ||
vector< cv::Point2f > & | pts2, | ||
cv::Mat & | drawImg | ||
) |
Definition at line 221 of file features.cpp.
void sortKeyPoints | ( | vector< cv::KeyPoint > & | KeyPoints, |
unsigned int | maxKeyPoints = -1 |
||
) |
Sorts features in descending order of strength, and culls beyond a certain quantity.
Definition at line 1357 of file features.cpp.
void sortMatches | ( | vector< vector< cv::DMatch > > & | matches1to2 | ) |
Definition at line 1401 of file features.cpp.
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() |
||
) |
Implement optical flow algorithm and filtering.
Definition at line 561 of file features.cpp.
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 | ||
) |
Implement optical flow algorithm and filtering for calibrating stereo cameras.
Definition at line 913 of file features.cpp.
void transformPoints | ( | vector< cv::Point2f > & | pts1, |
cv::Mat & | H | ||
) |
Transforms points using homography.
Definition at line 504 of file features.cpp.
void twoWayPriorityMatching | ( | cv::Mat & | matchingMatrix, |
vector< vector< cv::DMatch > > & | bestMatches, | ||
int | mode = MATCHING_MODE_NN |
||
) |
cv::Matches features between images given a cv::Matching cv::Matrix
Definition at line 1513 of file features.cpp.