$search
Declarations for local feature detection, description and 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 | MAX_DETECTORS 10 |
Functions | |
| void | assignEigenVectorResponses (const Mat &img, vector< KeyPoint > &pts) |
| void | assignMinimumRadii (vector< KeyPoint > &pts) |
| void | assignStabilityResponses (const Mat &img, vector< KeyPoint > &pts) |
| double | calcDistance (double dist, double ratio, double *coeffs) |
| Calculates linear SVM match distance. | |
| bool | checkRoomForFeature (vector< Point2f > &pts, Point2f &candidate, double dist=3.0) |
| bool | checkSufficientFeatureSpread (vector< Point2f > &pts, Size matSize, int minFeaturesInImage) |
| Checks whether there is sufficient spread of features in an image for effective tracking. | |
| void | concatenateWithExistingPoints (vector< Point2f > &pts, vector< Point2f > &kps, int size, double min_sep=3) |
| void | constrainMatchingMatrix (Mat &matchingMatrix, vector< KeyPoint > &kp1, vector< KeyPoint > &kp2, int distanceConstraint, double sizeConstraint) |
| bool | constructPatch (Mat &img, Mat &patch, Point2f ¢er, double radius, int cells=3) |
| void | createMatchingMatrix (Mat &matchingMatrix, const Mat &desc1, const Mat &desc2) |
| Creates matrix representing descriptor distance between sets of features. | |
| void | crossCheckMatching (Ptr< DescriptorMatcher > &descriptorMatcher, const Mat &descriptors1, const Mat &descriptors2, vector< DMatch > &filteredMatches12, int knn) |
| void | displayKeypoints (const Mat &image, const vector< Point2f > &pts, Mat &outImg, const Scalar &color, int thickness=1) |
| Prints keypoints onto a copy of an image. | |
| void | displayKeypoints (const Mat &image, const vector< KeyPoint > &keypoints, Mat &outImg, const Scalar &color, int thickness=1) |
| Prints keypoints onto a copy of an image. | |
| double | distanceBetweenPoints (const Point2f &pt1, const Point2f &pt2) |
| double | distanceBetweenPoints (const KeyPoint &pt1, const KeyPoint &pt2) |
| void | drawMatchPaths (Mat &src, Mat &dst, vector< Point2f > &kp1, vector< Point2f > &kp2, const Scalar &color=CV_RGB(255, 0, 0)) |
| Prints match paths onto a copy of an image, given vectors containing corresponding points. | |
| void | drawMatchPaths (Mat &src, Mat &dst, vector< KeyPoint > &kp1, vector< KeyPoint > &kp2, vector< vector< DMatch > > &matches1to2) |
| Prints match paths onto a copy of an image, given unfiltered points and matches structure. | |
| void | drawRichKeypoints (const cv::Mat &src, std::vector< cv::KeyPoint > &kpts, cv::Mat &dst) |
| double | estimateSalience (Mat &img, Point2f ¢er, double radius) |
| double | estimateStability (Mat &img, Point2f ¢er, double radius) |
| void | extendKeypoints (Mat &img, vector< KeyPoint > &pts, bool updateStrength, bool updateLocation) |
| void | fadeImage (const Mat &src, Mat &dst) |
| void | filterBlandKeypoints (Mat &img, vector< KeyPoint > &pts, double thresh=3.0) |
| void | filterKeypoints (std::vector< cv::KeyPoint > &kpts, int maxSize=0, int maxFeatures=0) |
| void | filterMatches (vector< vector< 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< Point2f > &pts1, vector< Point2f > &pts2, Mat &K, Mat &newCamMat, Mat &distCoeffs, Size &imSize, double prop=1.00) |
| void | filterVectors (vector< Point2f > &pts1, vector< Point2f > &pts2, vector< uchar > &statusVec, double distanceConstraint=10.0, bool epipolarCheck=false) |
| double | getPatchVariance (const Mat &patch) |
| double | getValueFromPatch (Mat &patch) |
| void | initializeDrawingColors (Scalar *kColors, Scalar *tColors, int num) |
| void | markAbsentPoints (vector< Point2f > &pts1, vector< Point2f > &pts2, vector< uchar > &statusVec, cv::Size imSize) |
| void | markBlandTracks (Mat &img, vector< Point2f > &pts, vector< uchar > &statusVec, double thresh=3.0) |
| void | markEdgyTracks (vector< Point2f > &pts, vector< uchar > &statusVec, cameraParameters &camData) |
| void | markStationaryPoints (vector< Point2f > &pts1, vector< Point2f > &pts2, vector< uchar > &statusVec) |
| void | markUnrefinedPoints (vector< Point2f > &pts, vector< uchar > &statusVec) |
| void | randomlyReducePoints (vector< Point2f > &pts, int maxFeatures) |
| void | reduceEdgyCandidates (vector< Point2f > &candidates, cameraParameters &camData) |
| void | reduceEdgyFeatures (vector< KeyPoint > &keypoints, cameraParameters &camData) |
| void | reduceProximalCandidates (vector< Point2f > &existing, vector< Point2f > &candidates) |
| void | reduceUnrefinedCandidates (vector< Point2f > &candidates) |
| void | reduceWeakFeatures (Mat &im, vector< KeyPoint > &feats, double minResponse) |
| double | reweightDistanceWithLinearSVM (double dist, double ratio, double gradient) |
| Uses a linear SVM to reweight the match distances so that they can be more effectively sorted. | |
| void | showMatches (const Mat &pim1, vector< Point2f > &pts1, const Mat &pim2, vector< Point2f > &pts2, Mat &drawImg) |
| void | sortKeypoints (vector< KeyPoint > &keypoints, unsigned int maxKeypoints=-1) |
| Sorts features in descending order of strength, and culls beyond a certain quantity. | |
| void | sortMatches (vector< vector< DMatch > > &matches1to2) |
| 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()) |
| Implement optical flow algorithm and filtering. | |
| 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) |
| Implement optical flow algorithm and filtering for calibrating stereo cameras. | |
| void | transformPoints (vector< Point2f > &pts1, Mat &H) |
| Transforms points using homography. | |
| void | twoWayPriorityMatching (Mat &matchingMatrix, vector< vector< DMatch > > &bestMatches) |
| Matches features between images given a matching matrix. | |
Declarations for local feature detection, description and matching.
Definition in file features.hpp.
| #define MAX_DETECTORS 10 |
Definition at line 18 of file features.hpp.
| void assignEigenVectorResponses | ( | const Mat & | img, | |
| vector< KeyPoint > & | pts | |||
| ) |
| void assignMinimumRadii | ( | vector< KeyPoint > & | pts | ) |
| void assignStabilityResponses | ( | const Mat & | img, | |
| vector< KeyPoint > & | pts | |||
| ) |
| double calcDistance | ( | double | dist, | |
| double | ratio, | |||
| double * | coeffs | |||
| ) |
Calculates linear SVM match distance.
Definition at line 1500 of file features.cpp.
| bool checkRoomForFeature | ( | vector< Point2f > & | pts, | |
| Point2f & | candidate, | |||
| double | dist = 3.0 | |||
| ) |
Definition at line 341 of file features.cpp.
| bool checkSufficientFeatureSpread | ( | vector< Point2f > & | pts, | |
| Size | matSize, | |||
| int | minFeaturesInImage | |||
| ) |
Checks whether there is sufficient spread of features in an image for effective tracking.
Definition at line 1691 of file features.cpp.
| void concatenateWithExistingPoints | ( | vector< Point2f > & | pts, | |
| vector< Point2f > & | kps, | |||
| int | size, | |||
| double | min_sep = 3 | |||
| ) |
Definition at line 390 of file features.cpp.
| void constrainMatchingMatrix | ( | Mat & | matchingMatrix, | |
| vector< KeyPoint > & | kp1, | |||
| vector< KeyPoint > & | kp2, | |||
| int | distanceConstraint, | |||
| double | sizeConstraint | |||
| ) |
Definition at line 1355 of file features.cpp.
| bool constructPatch | ( | Mat & | img, | |
| Mat & | patch, | |||
| Point2f & | center, | |||
| double | radius, | |||
| int | cells = 3 | |||
| ) |
Definition at line 893 of file features.cpp.
| void createMatchingMatrix | ( | Mat & | matchingMatrix, | |
| const Mat & | desc1, | |||
| const Mat & | desc2 | |||
| ) |
Creates matrix representing descriptor distance between sets of features.
Definition at line 1557 of file features.cpp.
| void crossCheckMatching | ( | Ptr< DescriptorMatcher > & | descriptorMatcher, | |
| const Mat & | descriptors1, | |||
| const Mat & | descriptors2, | |||
| vector< DMatch > & | filteredMatches12, | |||
| int | knn | |||
| ) |
Definition at line 208 of file features.cpp.
| void displayKeypoints | ( | const Mat & | image, | |
| const vector< Point2f > & | pts, | |||
| Mat & | outImg, | |||
| const Scalar & | color, | |||
| int | thickness = 1 | |||
| ) |
Prints keypoints onto a copy of an image.
Definition at line 1193 of file features.cpp.
| void displayKeypoints | ( | const Mat & | image, | |
| const vector< KeyPoint > & | keypoints, | |||
| Mat & | outImg, | |||
| const Scalar & | color, | |||
| int | thickness = 1 | |||
| ) |
Prints keypoints onto a copy of an image.
Definition at line 1115 of file features.cpp.
| double distanceBetweenPoints | ( | const Point2f & | pt1, | |
| const Point2f & | pt2 | |||
| ) |
Definition at line 1329 of file features.cpp.
| double distanceBetweenPoints | ( | const KeyPoint & | pt1, | |
| const KeyPoint & | pt2 | |||
| ) |
Definition at line 1338 of file features.cpp.
| void drawMatchPaths | ( | Mat & | src, | |
| Mat & | dst, | |||
| vector< Point2f > & | kp1, | |||
| vector< Point2f > & | kp2, | |||
| const Scalar & | color = CV_RGB(255, 0, 0) | |||
| ) |
Prints match paths onto a copy of an image, given vectors containing corresponding points.
Definition at line 1727 of file features.cpp.
| void drawMatchPaths | ( | Mat & | src, | |
| Mat & | dst, | |||
| vector< KeyPoint > & | kp1, | |||
| vector< KeyPoint > & | kp2, | |||
| vector< vector< DMatch > > & | matches1to2 | |||
| ) |
Prints match paths onto a copy of an image, given unfiltered points and matches structure.
Definition at line 1744 of file features.cpp.
| void drawRichKeypoints | ( | const cv::Mat & | src, | |
| std::vector< cv::KeyPoint > & | kpts, | |||
| cv::Mat & | dst | |||
| ) |
Definition at line 10 of file features.cpp.
| double estimateSalience | ( | Mat & | img, | |
| Point2f & | center, | |||
| double | radius | |||
| ) |
Definition at line 964 of file features.cpp.
| double estimateStability | ( | Mat & | img, | |
| Point2f & | center, | |||
| double | radius | |||
| ) |
Definition at line 1835 of file features.cpp.
| void extendKeypoints | ( | Mat & | img, | |
| vector< KeyPoint > & | pts, | |||
| bool | updateStrength, | |||
| bool | updateLocation | |||
| ) |
Definition at line 933 of file features.cpp.
| void fadeImage | ( | const Mat & | src, | |
| Mat & | dst | |||
| ) |
Definition at line 115 of file features.cpp.
| void filterBlandKeypoints | ( | Mat & | img, | |
| vector< KeyPoint > & | pts, | |||
| double | thresh = 3.0 | |||
| ) |
Definition at line 1077 of file features.cpp.
| void filterKeypoints | ( | std::vector< cv::KeyPoint > & | kpts, | |
| int | maxSize = 0, |
|||
| int | maxFeatures = 0 | |||
| ) |
Definition at line 148 of file features.cpp.
| void filterMatches | ( | vector< vector< DMatch > > & | matches1to2, | |
| double | threshold | |||
| ) |
Definition at line 1305 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 1614 of file features.cpp.
| void filterTrackingsByRadialProportion | ( | vector< Point2f > & | pts1, | |
| vector< Point2f > & | pts2, | |||
| Mat & | K, | |||
| Mat & | newCamMat, | |||
| Mat & | distCoeffs, | |||
| Size & | imSize, | |||
| double | prop = 1.00 | |||
| ) |
Definition at line 265 of file features.cpp.
| void filterVectors | ( | vector< Point2f > & | pts1, | |
| vector< Point2f > & | pts2, | |||
| vector< uchar > & | statusVec, | |||
| double | distanceConstraint = 10.0, |
|||
| bool | epipolarCheck = false | |||
| ) |
Definition at line 1641 of file features.cpp.
| double getPatchVariance | ( | const Mat & | patch | ) |
Definition at line 1869 of file features.cpp.
| double getValueFromPatch | ( | Mat & | patch | ) |
Definition at line 997 of file features.cpp.
| void initializeDrawingColors | ( | Scalar * | kColors, | |
| Scalar * | tColors, | |||
| int | num | |||
| ) |
Definition at line 414 of file features.cpp.
| void markAbsentPoints | ( | vector< Point2f > & | pts1, | |
| vector< Point2f > & | pts2, | |||
| vector< uchar > & | statusVec, | |||
| cv::Size | imSize | |||
| ) |
Definition at line 868 of file features.cpp.
| void markBlandTracks | ( | Mat & | img, | |
| vector< Point2f > & | pts, | |||
| vector< uchar > & | statusVec, | |||
| double | thresh = 3.0 | |||
| ) |
Definition at line 1047 of file features.cpp.
| void markEdgyTracks | ( | vector< Point2f > & | pts, | |
| vector< uchar > & | statusVec, | |||
| cameraParameters & | camData | |||
| ) |
Definition at line 1788 of file features.cpp.
| void markStationaryPoints | ( | vector< Point2f > & | pts1, | |
| vector< Point2f > & | pts2, | |||
| vector< uchar > & | statusVec | |||
| ) |
Definition at line 1095 of file features.cpp.
| void markUnrefinedPoints | ( | vector< Point2f > & | pts, | |
| vector< uchar > & | statusVec | |||
| ) |
Definition at line 1026 of file features.cpp.
| void randomlyReducePoints | ( | vector< Point2f > & | pts, | |
| int | maxFeatures | |||
| ) |
Definition at line 1624 of file features.cpp.
| void reduceEdgyCandidates | ( | vector< Point2f > & | candidates, | |
| cameraParameters & | camData | |||
| ) |
Definition at line 321 of file features.cpp.
| void reduceEdgyFeatures | ( | vector< KeyPoint > & | keypoints, | |
| cameraParameters & | camData | |||
| ) |
Definition at line 296 of file features.cpp.
| void reduceProximalCandidates | ( | vector< Point2f > & | existing, | |
| vector< Point2f > & | candidates | |||
| ) |
Definition at line 375 of file features.cpp.
| void reduceUnrefinedCandidates | ( | vector< Point2f > & | candidates | ) |
Definition at line 359 of file features.cpp.
| void reduceWeakFeatures | ( | Mat & | im, | |
| vector< KeyPoint > & | feats, | |||
| double | minResponse | |||
| ) |
Definition at line 474 of file features.cpp.
| double reweightDistanceWithLinearSVM | ( | double | dist, | |
| double | ratio, | |||
| double | gradient | |||
| ) |
Uses a linear SVM to reweight the match distances so that they can be more effectively sorted.
Definition at line 1508 of file features.cpp.
| void showMatches | ( | const Mat & | pim1, | |
| vector< Point2f > & | pts1, | |||
| const Mat & | pim2, | |||
| vector< Point2f > & | pts2, | |||
| Mat & | drawImg | |||
| ) |
Definition at line 170 of file features.cpp.
| void sortKeypoints | ( | vector< KeyPoint > & | keypoints, | |
| unsigned int | maxKeypoints = -1 | |||
| ) |
Sorts features in descending order of strength, and culls beyond a certain quantity.
Definition at line 1233 of file features.cpp.
| void sortMatches | ( | vector< vector< DMatch > > & | matches1to2 | ) |
Definition at line 1277 of file features.cpp.
| 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() | |||
| ) |
Implement optical flow algorithm and filtering.
Definition at line 509 of file features.cpp.
| 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 | |||
| ) |
Implement optical flow algorithm and filtering for calibrating stereo cameras.
Definition at line 801 of file features.cpp.
| void transformPoints | ( | vector< Point2f > & | pts1, | |
| Mat & | H | |||
| ) |
Transforms points using homography.
Definition at line 452 of file features.cpp.
| void twoWayPriorityMatching | ( | Mat & | matchingMatrix, | |
| vector< vector< DMatch > > & | bestMatches | |||
| ) |
Matches features between images given a matching matrix.
Definition at line 1388 of file features.cpp.