Frame.h 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #ifndef FRAME_H
  19. #define FRAME_H
  20. //#define SAVE_TIMES
  21. #include<vector>
  22. #include "Thirdparty/DBoW2/DBoW2/BowVector.h"
  23. #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
  24. #include "ImuTypes.h"
  25. #include "ORBVocabulary.h"
  26. #include <mutex>
  27. #include <opencv2/opencv.hpp>
  28. namespace ORB_SLAM3
  29. {
  30. #define FRAME_GRID_ROWS 48
  31. #define FRAME_GRID_COLS 64
  32. class MapPoint;
  33. class KeyFrame;
  34. class ConstraintPoseImu;
  35. class GeometricCamera;
  36. class ORBextractor;
  37. class Frame
  38. {
  39. public:
  40. Frame();
  41. // Copy constructor.
  42. Frame(const Frame &frame);
  43. // Constructor for stereo cameras.
  44. 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, GeometricCamera* pCamera,Frame* pPrevF = static_cast<Frame*>(NULL), const IMU::Calib &ImuCalib = IMU::Calib());
  45. // Constructor for RGB-D cameras.
  46. 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, Frame* pPrevF = static_cast<Frame*>(NULL), const IMU::Calib &ImuCalib = IMU::Calib());
  47. // Constructor for Monocular cameras.
  48. Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, GeometricCamera* pCamera, cv::Mat &distCoef, const float &bf, const float &thDepth, Frame* pPrevF = static_cast<Frame*>(NULL), const IMU::Calib &ImuCalib = IMU::Calib());
  49. // Destructor
  50. // ~Frame();
  51. // Extract ORB on the image. 0 for left image and 1 for right image.
  52. void ExtractORB(int flag, const cv::Mat &im, const int x0, const int x1);
  53. // Compute Bag of Words representation.
  54. void ComputeBoW();
  55. // Set the camera pose. (Imu pose is not modified!)
  56. void SetPose(cv::Mat Tcw);
  57. void GetPose(cv::Mat &Tcw);
  58. // Set IMU velocity
  59. void SetVelocity(const cv::Mat &Vwb);
  60. // Set IMU pose and velocity (implicitly changes camera pose)
  61. void SetImuPoseVelocity(const cv::Mat &Rwb, const cv::Mat &twb, const cv::Mat &Vwb);
  62. // Computes rotation, translation and camera center matrices from the camera pose.
  63. void UpdatePoseMatrices();
  64. // Returns the camera center.
  65. inline cv::Mat GetCameraCenter(){
  66. return mOw.clone();
  67. }
  68. // Returns inverse of rotation
  69. inline cv::Mat GetRotationInverse(){
  70. return mRwc.clone();
  71. }
  72. cv::Mat GetImuPosition();
  73. cv::Mat GetImuRotation();
  74. cv::Mat GetImuPose();
  75. void SetNewBias(const IMU::Bias &b);
  76. // Check if a MapPoint is in the frustum of the camera
  77. // and fill variables of the MapPoint to be used by the tracking
  78. bool isInFrustum(MapPoint* pMP, float viewingCosLimit);
  79. bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
  80. cv::Mat inRefCoordinates(cv::Mat pCw);
  81. // Compute the cell of a keypoint (return false if outside the grid)
  82. bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY);
  83. vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1, const bool bRight = false) const;
  84. // Search a match for each keypoint in the left image to a keypoint in the right image.
  85. // If there is a match, depth is computed and the right coordinate associated to the left keypoint is stored.
  86. void ComputeStereoMatches();
  87. // Associate a "right" coordinate to a keypoint if there is valid depth in the depthmap.
  88. void ComputeStereoFromRGBD(const cv::Mat &imDepth);
  89. // Backprojects a keypoint (if stereo/depth info available) into 3D world coordinates.
  90. cv::Mat UnprojectStereo(const int &i);
  91. ConstraintPoseImu* mpcpi;
  92. bool imuIsPreintegrated();
  93. void setIntegrated();
  94. cv::Mat mRwc;
  95. cv::Mat mOw;
  96. public:
  97. // Vocabulary used for relocalization.
  98. ORBVocabulary* mpORBvocabulary;
  99. // Feature extractor. The right is used only in the stereo case.
  100. ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
  101. // Frame timestamp.
  102. double mTimeStamp;
  103. // Calibration matrix and OpenCV distortion parameters.
  104. cv::Mat mK;
  105. static float fx;
  106. static float fy;
  107. static float cx;
  108. static float cy;
  109. static float invfx;
  110. static float invfy;
  111. cv::Mat mDistCoef;
  112. // Stereo baseline multiplied by fx.
  113. float mbf;
  114. // Stereo baseline in meters.
  115. float mb;
  116. // Threshold close/far points. Close points are inserted from 1 view.
  117. // Far points are inserted as in the monocular case from 2 views.
  118. float mThDepth;
  119. // Number of KeyPoints.
  120. int N;
  121. // Vector of keypoints (original for visualization) and undistorted (actually used by the system).
  122. // In the stereo case, mvKeysUn is redundant as images must be rectified.
  123. // In the RGB-D case, RGB images can be distorted.
  124. std::vector<cv::KeyPoint> mvKeys, mvKeysRight;
  125. std::vector<cv::KeyPoint> mvKeysUn;
  126. // Corresponding stereo coordinate and depth for each keypoint.
  127. std::vector<MapPoint*> mvpMapPoints;
  128. // "Monocular" keypoints have a negative value.
  129. std::vector<float> mvuRight;
  130. std::vector<float> mvDepth;
  131. // Bag of Words Vector structures.
  132. DBoW2::BowVector mBowVec;
  133. DBoW2::FeatureVector mFeatVec;
  134. // ORB descriptor, each row associated to a keypoint.
  135. cv::Mat mDescriptors, mDescriptorsRight;
  136. // MapPoints associated to keypoints, NULL pointer if no association.
  137. // Flag to identify outlier associations.
  138. std::vector<bool> mvbOutlier;
  139. int mnCloseMPs;
  140. // Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints.
  141. static float mfGridElementWidthInv;
  142. static float mfGridElementHeightInv;
  143. std::vector<std::size_t> mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS];
  144. // Camera pose.
  145. cv::Mat mTcw;
  146. // IMU linear velocity
  147. cv::Mat mVw;
  148. cv::Mat mPredRwb, mPredtwb, mPredVwb;
  149. IMU::Bias mPredBias;
  150. // IMU bias
  151. IMU::Bias mImuBias;
  152. // Imu calibration
  153. IMU::Calib mImuCalib;
  154. // Imu preintegration from last keyframe
  155. IMU::Preintegrated* mpImuPreintegrated;
  156. KeyFrame* mpLastKeyFrame;
  157. // Pointer to previous frame
  158. Frame* mpPrevFrame;
  159. IMU::Preintegrated* mpImuPreintegratedFrame;
  160. // Current and Next Frame id.
  161. static long unsigned int nNextId;
  162. long unsigned int mnId;
  163. // Reference Keyframe.
  164. KeyFrame* mpReferenceKF;
  165. // Scale pyramid info.
  166. int mnScaleLevels;
  167. float mfScaleFactor;
  168. float mfLogScaleFactor;
  169. vector<float> mvScaleFactors;
  170. vector<float> mvInvScaleFactors;
  171. vector<float> mvLevelSigma2;
  172. vector<float> mvInvLevelSigma2;
  173. // Undistorted Image Bounds (computed once).
  174. static float mnMinX;
  175. static float mnMaxX;
  176. static float mnMinY;
  177. static float mnMaxY;
  178. static bool mbInitialComputations;
  179. map<long unsigned int, cv::Point2f> mmProjectPoints;
  180. map<long unsigned int, cv::Point2f> mmMatchedInImage;
  181. string mNameFile;
  182. int mnDataset;
  183. double mTimeStereoMatch;
  184. double mTimeORB_Ext;
  185. private:
  186. // Undistort keypoints given OpenCV distortion parameters.
  187. // Only for the RGB-D case. Stereo must be already rectified!
  188. // (called in the constructor).
  189. void UndistortKeyPoints();
  190. // Computes image bounds for the undistorted image (called in the constructor).
  191. void ComputeImageBounds(const cv::Mat &imLeft);
  192. // Assign keypoints to the grid for speed up feature matching (called in the constructor).
  193. void AssignFeaturesToGrid();
  194. // Rotation, translation and camera center
  195. cv::Mat mRcw;
  196. cv::Mat mtcw;
  197. //==mtwc
  198. bool mbImuPreintegrated;
  199. std::mutex *mpMutexImu;
  200. public:
  201. GeometricCamera* mpCamera, *mpCamera2;
  202. //Number of KeyPoints extracted in the left and right images
  203. int Nleft, Nright;
  204. //Number of Non Lapping Keypoints
  205. int monoLeft, monoRight;
  206. //For stereo matching
  207. std::vector<int> mvLeftToRightMatch, mvRightToLeftMatch;
  208. //For stereo fisheye matching
  209. static cv::BFMatcher BFmatcher;
  210. //Triangulated stereo observations using as reference the left camera. These are
  211. //computed during ComputeStereoFishEyeMatches
  212. std::vector<cv::Mat> mvStereo3Dpoints;
  213. //Grid for the right image
  214. std::vector<std::size_t> mGridRight[FRAME_GRID_COLS][FRAME_GRID_ROWS];
  215. cv::Mat mTlr, mRlr, mtlr, mTrl;
  216. 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, GeometricCamera* pCamera, GeometricCamera* pCamera2, cv::Mat& Tlr,Frame* pPrevF = static_cast<Frame*>(NULL), const IMU::Calib &ImuCalib = IMU::Calib());
  217. //Stereo fisheye
  218. void ComputeStereoFishEyeMatches();
  219. bool isInFrustumChecks(MapPoint* pMP, float viewingCosLimit, bool bRight = false);
  220. cv::Mat UnprojectStereoFishEye(const int &i);
  221. cv::Mat imgLeft, imgRight;
  222. void PrintPointDistribution(){
  223. int left = 0, right = 0;
  224. int Nlim = (Nleft != -1) ? Nleft : N;
  225. for(int i = 0; i < N; i++){
  226. if(mvpMapPoints[i] && !mvbOutlier[i]){
  227. if(i < Nlim) left++;
  228. else right++;
  229. }
  230. }
  231. cout << "Point distribution in Frame: left-> " << left << " --- right-> " << right << endl;
  232. }
  233. };
  234. }// namespace ORB_SLAM
  235. #endif // FRAME_H