Frame.h
Go to the documentation of this file.
1 
21 #ifndef FRAME_H
22 #define FRAME_H
23 
24 #include<vector>
25 
26 #include "MapPoint.h"
29 #include "ORBVocabulary.h"
30 #include "KeyFrame.h"
31 #include "ORBextractor.h"
32 
33 #include <opencv2/opencv.hpp>
34 
35 namespace ORB_SLAM2
36 {
37 #define FRAME_GRID_ROWS 48
38 #define FRAME_GRID_COLS 64
39 
40 class MapPoint;
41 class KeyFrame;
42 
43 class Frame
44 {
45 public:
46  Frame();
47 
48  // Copy constructor.
49  Frame(const Frame &frame);
50 
51  // Constructor for stereo cameras.
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);
53 
54  // Constructor for RGB-D cameras.
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);
56 
57  // Constructor for Monocular cameras.
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);
59 
60  // Extract ORB on the image. 0 for left image and 1 for right image.
61  void ExtractORB(int flag, const cv::Mat &im);
62 
63  // Compute Bag of Words representation.
64  void ComputeBoW();
65 
66  // Set the camera pose.
67  void SetPose(cv::Mat Tcw);
68 
69  // Computes rotation, translation and camera center matrices from the camera pose.
70  void UpdatePoseMatrices();
71 
72  // Returns the camera center.
73  inline cv::Mat GetCameraCenter(){
74  return mOw.clone();
75  }
76 
77  // Returns inverse of rotation
78  inline cv::Mat GetRotationInverse(){
79  return mRwc.clone();
80  }
81 
82  // Check if a MapPoint is in the frustum of the camera
83  // and fill variables of the MapPoint to be used by the tracking
84  bool isInFrustum(MapPoint* pMP, float viewingCosLimit);
85 
86  // Compute the cell of a keypoint (return false if outside the grid)
87  bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY);
88 
89  vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const;
90 
91  // Search a match for each keypoint in the left image to a keypoint in the right image.
92  // If there is a match, depth is computed and the right coordinate associated to the left keypoint is stored.
93  void ComputeStereoMatches();
94 
95  // Associate a "right" coordinate to a keypoint if there is valid depth in the depthmap.
96  void ComputeStereoFromRGBD(const cv::Mat &imDepth);
97 
98  // Backprojects a keypoint (if stereo/depth info available) into 3D world coordinates.
99  cv::Mat UnprojectStereo(const int &i);
100 
101 public:
102 
104  // Vocabulary used for relocalization.
106 
107  // Feature extractor. The right is used only in the stereo case.
109 
110  // Frame timestamp.
111  double mTimeStamp;
112 
113  // Calibration matrix and OpenCV distortion parameters.
114  cv::Mat mK;
115  static float fx;
116  static float fy;
117  static float cx;
118  static float cy;
119  static float invfx;
120  static float invfy;
121  cv::Mat mDistCoef;
122 
123  // Stereo baseline multiplied by fx.
124  float mbf;
125 
126  // Stereo baseline in meters.
127  float mb;
128 
129  // Threshold close/far points. Close points are inserted from 1 view.
130  // Far points are inserted as in the monocular case from 2 views.
131  float mThDepth;
132 
133  // Number of KeyPoints.
134  int N;
135 
136  // Vector of keypoints (original for visualization) and undistorted (actually used by the system).
137  // In the stereo case, mvKeysUn is redundant as images must be rectified.
138  // In the RGB-D case, RGB images can be distorted.
139  std::vector<cv::KeyPoint> mvKeys, mvKeysRight;
140  std::vector<cv::KeyPoint> mvKeysUn;
141 
142  // Corresponding stereo coordinate and depth for each keypoint.
143  // "Monocular" keypoints have a negative value.
144  std::vector<float> mvuRight;
145  std::vector<float> mvDepth;
146 
147  // Bag of Words Vector structures.
150 
151  // ORB descriptor, each row associated to a keypoint.
153 
154  // MapPoints associated to keypoints, NULL pointer if no association.
155  std::vector<MapPoint*> mvpMapPoints;
156 
157  // Flag to identify outlier associations.
158  std::vector<bool> mvbOutlier;
159 
160  // Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints.
161  static float mfGridElementWidthInv;
163  std::vector<std::size_t> mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS];
164 
165  // Camera pose.
166  cv::Mat mTcw;
167 
168  // Current and Next Frame id.
169  static long unsigned int nNextId;
170  long unsigned int mnId;
171 
172  // Reference Keyframe.
174 
175  // Scale pyramid info.
179  vector<float> mvScaleFactors;
180  vector<float> mvInvScaleFactors;
181  vector<float> mvLevelSigma2;
182  vector<float> mvInvLevelSigma2;
183 
184  // Undistorted Image Bounds (computed once).
185  static float mnMinX;
186  static float mnMaxX;
187  static float mnMinY;
188  static float mnMaxY;
189 
191 
192 
193 private:
194 
195  // Undistort keypoints given OpenCV distortion parameters.
196  // Only for the RGB-D case. Stereo must be already rectified!
197  // (called in the constructor).
198  void UndistortKeyPoints();
199 
200  // Computes image bounds for the undistorted image (called in the constructor).
201  void ComputeImageBounds(const cv::Mat &imLeft);
202 
203  // Assign keypoints to the grid for speed up feature matching (called in the constructor).
204  void AssignFeaturesToGrid();
205 
206  // Rotation, translation and camera center
207  cv::Mat mRcw;
208  cv::Mat mtcw;
209  cv::Mat mRwc;
210  cv::Mat mOw; //==mtwc
211 };
212 
213 }// namespace ORB_SLAM
214 
215 #endif // FRAME_H
std::vector< MapPoint * > mvpMapPoints
Definition: Frame.h:155
static float fy
Definition: Frame.h:116
void ComputeImageBounds(const cv::Mat &imLeft)
bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY)
cv::Mat mDistCoef
Definition: Frame.h:121
#define FRAME_GRID_COLS
Definition: Frame.h:38
static float cx
Definition: Frame.h:117
vector< float > mvInvScaleFactors
Definition: Frame.h:180
static float fx
Definition: Frame.h:115
void ComputeStereoFromRGBD(const cv::Mat &imDepth)
static float invfx
Definition: Frame.h:119
static float cy
Definition: Frame.h:118
cv::Mat UnprojectStereo(const int &i)
std::vector< bool > mvbOutlier
Definition: Frame.h:158
cv::Mat GetRotationInverse()
Definition: Frame.h:78
void UpdatePoseMatrices()
static float mfGridElementHeightInv
Definition: Frame.h:162
static float mnMinY
Definition: Frame.h:187
cv::Mat mDescriptorsRight
Definition: Frame.h:152
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< std::size_t > mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]
Definition: Frame.h:163
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:140
static float mfGridElementWidthInv
Definition: Frame.h:161
KeyFrame * mpReferenceKF
Definition: Frame.h:173
static float invfy
Definition: Frame.h:120
DBoW2::FeatureVector mFeatVec
Definition: Frame.h:149
cv::Mat mRwc
Definition: Frame.h:209
cv::Mat GetCameraCenter()
Definition: Frame.h:73
ORBVocabulary * mpORBvocabulary
Definition: Frame.h:105
float mfScaleFactor
Definition: Frame.h:177
std::vector< float > mvuRight
Definition: Frame.h:144
bool isInFrustum(MapPoint *pMP, float viewingCosLimit)
vector< float > mvLevelSigma2
Definition: Frame.h:181
std::vector< float > mvDepth
Definition: Frame.h:145
int mnScaleLevels
Definition: Frame.h:176
std::vector< cv::KeyPoint > mvKeysRight
Definition: Frame.h:139
static bool mbInitialComputations
Definition: Frame.h:190
cv::Mat mTcw
Definition: Frame.h:166
static long unsigned int nNextId
Definition: Frame.h:169
#define FRAME_GRID_ROWS
Definition: Frame.h:37
void AssignFeaturesToGrid()
float mfLogScaleFactor
Definition: Frame.h:178
double mTimeStamp
Definition: Frame.h:111
Vector of words to represent images.
Definition: BowVector.h:56
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< cv::KeyPoint > mvKeys
Definition: Frame.h:139
vector< float > mvScaleFactors
Definition: Frame.h:179
Vector of nodes with indexes of local features.
Definition: FeatureVector.h:21
static float mnMaxY
Definition: Frame.h:188
cv::Mat mK
Definition: Frame.h:114
cv::Mat mtcw
Definition: Frame.h:208
cv::Mat mOw
Definition: Frame.h:210
void ExtractORB(int flag, const cv::Mat &im)
cv::Mat mRcw
Definition: Frame.h:207
void ComputeStereoMatches()
static float mnMinX
Definition: Frame.h:185
vector< float > mvInvLevelSigma2
Definition: Frame.h:182
void UndistortKeyPoints()
bool is_keyframe
Definition: Frame.h:103
void SetPose(cv::Mat Tcw)
long unsigned int mnId
Definition: Frame.h:170
static float mnMaxX
Definition: Frame.h:186
cv::Mat mDescriptors
Definition: Frame.h:152
float mThDepth
Definition: Frame.h:131
ORBextractor * mpORBextractorRight
Definition: Frame.h:108
vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const
DBoW2::BowVector mBowVec
Definition: Frame.h:148
ORBextractor * mpORBextractorLeft
Definition: Frame.h:108


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47