forked from raulmur/ORB_SLAM
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Frame.h
142 lines (108 loc) · 3.8 KB
/
Frame.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
/**
* This file is part of ORB-SLAM.
*
* Copyright (C) 2014 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <http://webdiis.unizar.es/~raulmur/orbslam/>
*
* ORB-SLAM is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef FRAME_H
#define FRAME_H
#include "MapPoint.h"
#include "Thirdparty/DBoW2/DBoW2/BowVector.h"
#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
#include "ORBVocabulary.h"
#include "KeyFrame.h"
#include "ORBextractor.h"
#include <opencv2/opencv.hpp>
namespace ORB_SLAM
{
#define FRAME_GRID_ROWS 48
#define FRAME_GRID_COLS 64
class tracking;
class MapPoint;
class KeyFrame;
class KeyFrameDatabase;
class Frame
{
public:
Frame();
Frame(const Frame &frame);
Frame(cv::Mat &im, const double &timeStamp, ORBextractor* extractor, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef);
ORBVocabulary* mpORBvocabulary;
ORBextractor* mpORBextractor;
// Frame image
cv::Mat im;
// Frame timestamp
double mTimeStamp;
// Calibration Matrix and k1,k2,p1,p2 Distortion Parameters
cv::Mat mK;
static float fx;
static float fy;
static float cx;
static float cy;
cv::Mat mDistCoef;
// Number of KeyPoints
int N;
// Vector of keypoints (original for visualization) and undistorted (actually used by the system)
std::vector<cv::KeyPoint> mvKeys;
std::vector<cv::KeyPoint> mvKeysUn;
// Bag of Words Vector structures
DBoW2::BowVector mBowVec;
DBoW2::FeatureVector mFeatVec;
// ORB descriptor, each row associated to a keypoint
cv::Mat mDescriptors;
// MapPoints associated to keypoints, NULL pointer if not association
std::vector<MapPoint*> mvpMapPoints;
// Flag to identify outlier associations
std::vector<bool> mvbOutlier;
// Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints
static float mfGridElementWidthInv;
static float mfGridElementHeightInv;
std::vector<std::size_t> mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS];
// Camera Pose
cv::Mat mTcw;
// Current and Next Frame id
static long unsigned int nNextId;
long unsigned int mnId;
KeyFrame* mpReferenceKF;
void ComputeBoW();
void UpdatePoseMatrices();
// Check if a MapPoint is in the frustum of the camera and also fills variables of the MapPoint to be used by the tracking
bool isInFrustum(MapPoint* pMP, float viewingCosLimit);
// Compute the cell of a keypoint (return false if outside the grid)
bool PosInGrid(cv::KeyPoint &kp, int &posX, int &posY);
vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const;
// Scale Pyramid Info
int mnScaleLevels;
float mfScaleFactor;
vector<float> mvScaleFactors;
vector<float> mvLevelSigma2;
vector<float> mvInvLevelSigma2;
// Undistorted Image Bounds (computed once)
static int mnMinX;
static int mnMaxX;
static int mnMinY;
static int mnMaxY;
static bool mbInitialComputations;
private:
void UndistortKeyPoints();
void ComputeImageBounds();
// Call UpdatePoseMatrices(), before using
cv::Mat mOw;
cv::Mat mRcw;
cv::Mat mtcw;
};
}// namespace ORB_SLAM
#endif // FRAME_H