27 #include "Thirdparty/DBoW2/DBoW2/BowVector.h" 28 #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" 29 #include "ORBVocabulary.h" 31 #include "ORBextractor.h" 33 #include <opencv2/opencv.hpp> 37 #define FRAME_GRID_ROWS 48 38 #define FRAME_GRID_COLS 64 52 Frame(
const cv::Mat &imLeft,
const cv::Mat &imRight,
const double &timeStamp,
ORBextractor* extractorLeft,
ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef,
const float &bf,
const float &thDepth);
55 Frame(
const cv::Mat &imGray,
const cv::Mat &imDepth,
const double &timeStamp,
ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef,
const float &bf,
const float &thDepth);
58 Frame(
const cv::Mat &imGray,
const double &timeStamp,
ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef,
const float &bf,
const float &thDepth);
61 void ExtractORB(
int flag,
const cv::Mat &im);
67 void SetPose(cv::Mat Tcw);
70 void UpdatePoseMatrices();
73 inline cv::Mat GetCameraCenter(){
78 inline cv::Mat GetRotationInverse(){
84 bool isInFrustum(
MapPoint* pMP,
float viewingCosLimit);
87 bool PosInGrid(
const cv::KeyPoint &kp,
int &posX,
int &posY);
89 vector<size_t> GetFeaturesInArea(
const float &x,
const float &y,
const float &r,
const int minLevel=-1,
const int maxLevel=-1)
const;
93 void ComputeStereoMatches();
96 void ComputeStereoFromRGBD(
const cv::Mat &imDepth);
99 cv::Mat UnprojectStereo(
const int &i);
103 ORBVocabulary* mpORBvocabulary;
137 std::vector<cv::KeyPoint> mvKeys, mvKeysRight;
138 std::vector<cv::KeyPoint> mvKeysUn;
142 std::vector<float> mvuRight;
143 std::vector<float> mvDepth;
146 DBoW2::BowVector mBowVec;
147 DBoW2::FeatureVector mFeatVec;
150 cv::Mat mDescriptors, mDescriptorsRight;
153 std::vector<MapPoint*> mvpMapPoints;
156 std::vector<bool> mvbOutlier;
159 static float mfGridElementWidthInv;
160 static float mfGridElementHeightInv;
161 std::vector<std::size_t> mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS];
167 static long unsigned int nNextId;
168 long unsigned int mnId;
176 float mfLogScaleFactor;
177 vector<float> mvScaleFactors;
178 vector<float> mvInvScaleFactors;
179 vector<float> mvLevelSigma2;
180 vector<float> mvInvLevelSigma2;
188 static bool mbInitialComputations;
196 void UndistortKeyPoints();
199 void ComputeImageBounds(
const cv::Mat &imLeft);
202 void AssignFeaturesToGrid();
Definition: KeyFrame.h:43
Definition: Converter.cpp:24
Definition: MapPoint.h:39