#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <vector>
#include "ORBextractor.h"
Go to the source code of this file.
|
static void | ORB_SLAM2::computeDescriptors (const Mat &image, vector< KeyPoint > &keypoints, Mat &descriptors, const vector< Point > &pattern) |
|
static void | ORB_SLAM2::computeOrbDescriptor (const KeyPoint &kpt, const Mat &img, const Point *pattern, uchar *desc) |
|
static void | ORB_SLAM2::computeOrientation (const Mat &image, vector< KeyPoint > &keypoints, const vector< int > &umax) |
|
static float | ORB_SLAM2::IC_Angle (const Mat &image, Point2f pt, const vector< int > &u_max) |
|
Value:center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*
step + \
cvRound(pattern[idx].x*a - pattern[idx].y*b)]