Classes | |
| class | AORB |
Typedefs | |
| typedef AORB | AorbDescriptorExtractor |
| typedef AORB | AorbFeatureDetector |
Functions | |
| static AlgorithmInfo & | aorb_info () |
| static void | computeDescriptors (const Mat &image, vector< KeyPoint > &keypoints, Mat &descriptors, const vector< Point > &pattern, int dsize, int WTA_K) |
| static void | computeKeyPoints (const vector< Mat > &imagePyramid, const vector< Mat > &maskPyramid, vector< vector< KeyPoint > > &allKeypoints, int nfeatures, int firstLevel, double scaleFactor, int edgeThreshold, int patchSize, int scoreType, int fastThreshold) |
| static void | computeOrbDescriptor (const KeyPoint &kpt, const Mat &img, const Point *pattern, uchar *desc, int dsize, int WTA_K) |
| static void | computeOrientation (const Mat &image, vector< KeyPoint > &keypoints, int halfPatchSize, const vector< int > &umax) |
| static Algorithm * | createAORB () |
| static float | getScale (int level, int firstLevel, double scaleFactor) |
| static void | HarrisResponses (const Mat &img, vector< KeyPoint > &pts, int blockSize, float harris_k) |
| static float | IC_Angle (const Mat &image, const int half_k, Point2f pt, const vector< int > &u_max) |
| static void | initializeOrbPattern (const Point *pattern0, vector< Point > &pattern, int ntuples, int tupleSize, int poolSize) |
| static void | makeRandomPattern (int patchSize, Point *pattern, int npoints) |
Variables | |
| static AlgorithmInfo & | aorb_info_auto = aorb_info() |
| static int | bit_pattern_31_ [256 *4] |
| const int | DESCRIPTOR_SIZE = 32 |
| const float | HARRIS_K = 0.04f |
Authors: Ethan Rublee, Vincent Rabaud, Gary Bradski, Felix Endres
Adjustable ORB implementation. Modified from original ORB by Felix Endres
| typedef AORB cv::AorbDescriptorExtractor |
| typedef AORB cv::AorbFeatureDetector |
| static AlgorithmInfo& cv::aorb_info | ( | ) | [static] |
| static void cv::computeDescriptors | ( | const Mat & | image, |
| vector< KeyPoint > & | keypoints, | ||
| Mat & | descriptors, | ||
| const vector< Point > & | pattern, | ||
| int | dsize, | ||
| int | WTA_K | ||
| ) | [static] |
Compute the AORB decriptors
| image | the image to compute the features and descriptors on |
| integral_image | the integral image of the image (can be empty, but the computation will be slower) |
| level | the scale at which we compute the orientation |
| keypoints | the keypoints to use |
| descriptors | the resulting descriptors |
| static void cv::computeKeyPoints | ( | const vector< Mat > & | imagePyramid, |
| const vector< Mat > & | maskPyramid, | ||
| vector< vector< KeyPoint > > & | allKeypoints, | ||
| int | nfeatures, | ||
| int | firstLevel, | ||
| double | scaleFactor, | ||
| int | edgeThreshold, | ||
| int | patchSize, | ||
| int | scoreType, | ||
| int | fastThreshold | ||
| ) | [static] |
| static void cv::computeOrbDescriptor | ( | const KeyPoint & | kpt, |
| const Mat & | img, | ||
| const Point * | pattern, | ||
| uchar * | desc, | ||
| int | dsize, | ||
| int | WTA_K | ||
| ) | [static] |
| static void cv::computeOrientation | ( | const Mat & | image, |
| vector< KeyPoint > & | keypoints, | ||
| int | halfPatchSize, | ||
| const vector< int > & | umax | ||
| ) | [static] |
Compute the AORB keypoint orientations
| image | the image to compute the features and descriptors on |
| integral_image | the integral image of the iamge (can be empty, but the computation will be slower) |
| scale | the scale at which we compute the orientation |
| keypoints | the resulting keypoints |
| static Algorithm* cv::createAORB | ( | ) | [static] |
| static float cv::getScale | ( | int | level, |
| int | firstLevel, | ||
| double | scaleFactor | ||
| ) | [inline, static] |
| static void cv::HarrisResponses | ( | const Mat & | img, |
| vector< KeyPoint > & | pts, | ||
| int | blockSize, | ||
| float | harris_k | ||
| ) | [static] |
| static float cv::IC_Angle | ( | const Mat & | image, |
| const int | half_k, | ||
| Point2f | pt, | ||
| const vector< int > & | u_max | ||
| ) | [static] |
| static void cv::initializeOrbPattern | ( | const Point * | pattern0, |
| vector< Point > & | pattern, | ||
| int | ntuples, | ||
| int | tupleSize, | ||
| int | poolSize | ||
| ) | [static] |
| static void cv::makeRandomPattern | ( | int | patchSize, |
| Point * | pattern, | ||
| int | npoints | ||
| ) | [static] |
AlgorithmInfo& cv::aorb_info_auto = aorb_info() [static] |
int cv::bit_pattern_31_[256 *4] [static] |
| const int cv::DESCRIPTOR_SIZE = 32 |
| const float cv::HARRIS_K = 0.04f |