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  // Vocabulary used for relocalization.
104 
105  // Feature extractor. The right is used only in the stereo case.
107 
108  // Frame timestamp.
109  double mTimeStamp;
110 
111  // Calibration matrix and OpenCV distortion parameters.
112  cv::Mat mK;
113  static float fx;
114  static float fy;
115  static float cx;
116  static float cy;
117  static float invfx;
118  static float invfy;
119  cv::Mat mDistCoef;
120 
121  // Stereo baseline multiplied by fx.
122  float mbf;
123 
124  // Stereo baseline in meters.
125  float mb;
126 
127  // Threshold close/far points. Close points are inserted from 1 view.
128  // Far points are inserted as in the monocular case from 2 views.
129  float mThDepth;
130 
131  // Number of KeyPoints.
132  int N;
133 
134  // Vector of keypoints (original for visualization) and undistorted (actually used by the system).
135  // In the stereo case, mvKeysUn is redundant as images must be rectified.
136  // In the RGB-D case, RGB images can be distorted.
137  std::vector<cv::KeyPoint> mvKeys, mvKeysRight;
138  std::vector<cv::KeyPoint> mvKeysUn;
139 
140  // Corresponding stereo coordinate and depth for each keypoint.
141  // "Monocular" keypoints have a negative value.
142  std::vector<float> mvuRight;
143  std::vector<float> mvDepth;
144 
145  // Bag of Words Vector structures.
148 
149  // ORB descriptor, each row associated to a keypoint.
151 
152  // MapPoints associated to keypoints, NULL pointer if no association.
153  std::vector<MapPoint*> mvpMapPoints;
154 
155  // Flag to identify outlier associations.
156  std::vector<bool> mvbOutlier;
157 
158  // Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints.
159  static float mfGridElementWidthInv;
161  std::vector<std::size_t> mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS];
162 
163  // Camera pose.
164  cv::Mat mTcw;
165 
166  // Current and Next Frame id.
167  static long unsigned int nNextId;
168  long unsigned int mnId;
169 
170  // Reference Keyframe.
172 
173  // Scale pyramid info.
177  vector<float> mvScaleFactors;
178  vector<float> mvInvScaleFactors;
179  vector<float> mvLevelSigma2;
180  vector<float> mvInvLevelSigma2;
181 
182  // Undistorted Image Bounds (computed once).
183  static float mnMinX;
184  static float mnMaxX;
185  static float mnMinY;
186  static float mnMaxY;
187 
189 
190 
191 private:
192 
193  // Undistort keypoints given OpenCV distortion parameters.
194  // Only for the RGB-D case. Stereo must be already rectified!
195  // (called in the constructor).
196  void UndistortKeyPoints();
197 
198  // Computes image bounds for the undistorted image (called in the constructor).
199  void ComputeImageBounds(const cv::Mat &imLeft);
200 
201  // Assign keypoints to the grid for speed up feature matching (called in the constructor).
202  void AssignFeaturesToGrid();
203 
204  // Rotation, translation and camera center
205  cv::Mat mRcw;
206  cv::Mat mtcw;
207  cv::Mat mRwc;
208  cv::Mat mOw; //==mtwc
209 };
210 
211 }// namespace ORB_SLAM
212 
213 #endif // FRAME_H
std::vector< MapPoint * > mvpMapPoints
Definition: Frame.h:153
void ComputeBoW()
Definition: Frame.cc:395
static float fy
Definition: Frame.h:114
void ComputeImageBounds(const cv::Mat &imLeft)
Definition: Frame.cc:436
bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY)
Definition: Frame.cc:382
cv::Mat mDistCoef
Definition: Frame.h:119
#define FRAME_GRID_COLS
Definition: Frame.h:38
static float cx
Definition: Frame.h:115
vector< float > mvInvScaleFactors
Definition: Frame.h:178
static float fx
Definition: Frame.h:113
void ComputeStereoFromRGBD(const cv::Mat &imDepth)
Definition: Frame.cc:643
static float invfx
Definition: Frame.h:117
static float cy
Definition: Frame.h:116
cv::Mat UnprojectStereo(const int &i)
Definition: Frame.cc:666
std::vector< bool > mvbOutlier
Definition: Frame.h:156
cv::Mat GetRotationInverse()
Definition: Frame.h:78
void UpdatePoseMatrices()
Definition: Frame.cc:261
static float mfGridElementHeightInv
Definition: Frame.h:160
static float mnMinY
Definition: Frame.h:185
cv::Mat mDescriptorsRight
Definition: Frame.h:150
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< std::size_t > mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]
Definition: Frame.h:161
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:138
static float mfGridElementWidthInv
Definition: Frame.h:159
KeyFrame * mpReferenceKF
Definition: Frame.h:171
static float invfy
Definition: Frame.h:118
DBoW2::FeatureVector mFeatVec
Definition: Frame.h:147
cv::Mat mRwc
Definition: Frame.h:207
cv::Mat GetCameraCenter()
Definition: Frame.h:73
ORBVocabulary * mpORBvocabulary
Definition: Frame.h:103
float mfScaleFactor
Definition: Frame.h:175
std::vector< float > mvuRight
Definition: Frame.h:142
bool isInFrustum(MapPoint *pMP, float viewingCosLimit)
Definition: Frame.cc:269
vector< float > mvLevelSigma2
Definition: Frame.h:179
std::vector< float > mvDepth
Definition: Frame.h:143
int mnScaleLevels
Definition: Frame.h:174
std::vector< cv::KeyPoint > mvKeysRight
Definition: Frame.h:137
static bool mbInitialComputations
Definition: Frame.h:188
cv::Mat mTcw
Definition: Frame.h:164
static long unsigned int nNextId
Definition: Frame.h:167
#define FRAME_GRID_ROWS
Definition: Frame.h:37
void AssignFeaturesToGrid()
Definition: Frame.cc:230
float mfLogScaleFactor
Definition: Frame.h:176
double mTimeStamp
Definition: Frame.h:109
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:137
vector< float > mvScaleFactors
Definition: Frame.h:177
Vector of nodes with indexes of local features.
Definition: FeatureVector.h:21
static float mnMaxY
Definition: Frame.h:186
cv::Mat mK
Definition: Frame.h:112
cv::Mat mtcw
Definition: Frame.h:206
cv::Mat mOw
Definition: Frame.h:208
void ExtractORB(int flag, const cv::Mat &im)
Definition: Frame.cc:247
cv::Mat mRcw
Definition: Frame.h:205
void ComputeStereoMatches()
Definition: Frame.cc:466
static float mnMinX
Definition: Frame.h:183
vector< float > mvInvLevelSigma2
Definition: Frame.h:180
void UndistortKeyPoints()
Definition: Frame.cc:404
void SetPose(cv::Mat Tcw)
Definition: Frame.cc:255
long unsigned int mnId
Definition: Frame.h:168
static float mnMaxX
Definition: Frame.h:184
cv::Mat mDescriptors
Definition: Frame.h:150
float mThDepth
Definition: Frame.h:129
ORBextractor * mpORBextractorRight
Definition: Frame.h:106
DBoW2::BowVector mBowVec
Definition: Frame.h:146
vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const
Definition: Frame.cc:327
ORBextractor * mpORBextractorLeft
Definition: Frame.h:106


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05