Frame.h 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327
  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. #include<vector>
  21. #include "Thirdparty/DBoW2/DBoW2/BowVector.h"
  22. #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
  23. #include "ImuTypes.h"
  24. #include "ORBVocabulary.h"
  25. #include "Config.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, GeometricCamera* pCamera,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. // Extract ORB on the image. 0 for left image and 1 for right image.
  50. void ExtractORB(int flag, const cv::Mat &im, const int x0, const int x1);
  51. // Compute Bag of Words representation.
  52. void ComputeBoW();
  53. // Set the camera pose. (Imu pose is not modified!)
  54. void SetPose(cv::Mat Tcw);
  55. void GetPose(cv::Mat &Tcw);
  56. // Set IMU velocity
  57. void SetVelocity(const cv::Mat &Vwb);
  58. // Set IMU pose and velocity (implicitly changes camera pose)
  59. void SetImuPoseVelocity(const cv::Mat &Rwb, const cv::Mat &twb, const cv::Mat &Vwb);
  60. // Computes rotation, translation and camera center matrices from the camera pose.
  61. void UpdatePoseMatrices();
  62. // Returns the camera center.
  63. inline cv::Mat GetCameraCenter(){
  64. return mOw.clone();
  65. }
  66. // Returns inverse of rotation
  67. inline cv::Mat GetRotationInverse(){
  68. return mRwc.clone();
  69. }
  70. cv::Mat GetImuPosition();
  71. cv::Mat GetImuRotation();
  72. cv::Mat GetImuPose();
  73. void SetNewBias(const IMU::Bias &b);
  74. // Check if a MapPoint is in the frustum of the camera
  75. // and fill variables of the MapPoint to be used by the tracking
  76. bool isInFrustum(MapPoint* pMP, float viewingCosLimit);
  77. bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
  78. cv::Mat inRefCoordinates(cv::Mat pCw);
  79. // Compute the cell of a keypoint (return false if outside the grid)
  80. bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY);
  81. 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;
  82. // Search a match for each keypoint in the left image to a keypoint in the right image.
  83. // If there is a match, depth is computed and the right coordinate associated to the left keypoint is stored.
  84. void ComputeStereoMatches();
  85. // Associate a "right" coordinate to a keypoint if there is valid depth in the depthmap.
  86. void ComputeStereoFromRGBD(const cv::Mat &imDepth);
  87. // Backprojects a keypoint (if stereo/depth info available) into 3D world coordinates.
  88. cv::Mat UnprojectStereo(const int &i);
  89. ConstraintPoseImu* mpcpi;
  90. bool imuIsPreintegrated();
  91. void setIntegrated();
  92. cv::Mat mRwc;
  93. cv::Mat mOw;
  94. public:
  95. // Vocabulary used for relocalization.
  96. ORBVocabulary* mpORBvocabulary;
  97. // Feature extractor. The right is used only in the stereo case.
  98. ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
  99. // Frame timestamp.
  100. double mTimeStamp;
  101. // Calibration matrix and OpenCV distortion parameters.
  102. cv::Mat mK;
  103. static float fx;
  104. static float fy;
  105. static float cx;
  106. static float cy;
  107. static float invfx;
  108. static float invfy;
  109. cv::Mat mDistCoef;
  110. // Stereo baseline multiplied by fx.
  111. float mbf;
  112. // Stereo baseline in meters.
  113. float mb;
  114. // Threshold close/far points. Close points are inserted from 1 view.
  115. // Far points are inserted as in the monocular case from 2 views.
  116. float mThDepth;
  117. // Number of KeyPoints.
  118. int N;
  119. // Vector of keypoints (original for visualization) and undistorted (actually used by the system).
  120. // In the stereo case, mvKeysUn is redundant as images must be rectified.
  121. // In the RGB-D case, RGB images can be distorted.
  122. std::vector<cv::KeyPoint> mvKeys, mvKeysRight;
  123. std::vector<cv::KeyPoint> mvKeysUn;
  124. // Corresponding stereo coordinate and depth for each keypoint.
  125. std::vector<MapPoint*> mvpMapPoints;
  126. // "Monocular" keypoints have a negative value.
  127. std::vector<float> mvuRight;
  128. std::vector<float> mvDepth;
  129. // Bag of Words Vector structures.
  130. DBoW2::BowVector mBowVec;
  131. DBoW2::FeatureVector mFeatVec;
  132. // ORB descriptor, each row associated to a keypoint.
  133. cv::Mat mDescriptors, mDescriptorsRight;
  134. // MapPoints associated to keypoints, NULL pointer if no association.
  135. // Flag to identify outlier associations.
  136. std::vector<bool> mvbOutlier;
  137. int mnCloseMPs;
  138. // Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints.
  139. static float mfGridElementWidthInv;
  140. static float mfGridElementHeightInv;
  141. std::vector<std::size_t> mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS];
  142. // Camera pose.
  143. cv::Mat mTcw;
  144. // IMU linear velocity
  145. cv::Mat mVw;
  146. cv::Mat mPredRwb, mPredtwb, mPredVwb;
  147. IMU::Bias mPredBias;
  148. // IMU bias
  149. IMU::Bias mImuBias;
  150. // Imu calibration
  151. IMU::Calib mImuCalib;
  152. // Imu preintegration from last keyframe
  153. IMU::Preintegrated* mpImuPreintegrated;
  154. KeyFrame* mpLastKeyFrame;
  155. // Pointer to previous frame
  156. Frame* mpPrevFrame;
  157. IMU::Preintegrated* mpImuPreintegratedFrame;
  158. // Current and Next Frame id.
  159. static long unsigned int nNextId;
  160. long unsigned int mnId;
  161. // Reference Keyframe.
  162. KeyFrame* mpReferenceKF;
  163. // Scale pyramid info.
  164. int mnScaleLevels;
  165. float mfScaleFactor;
  166. float mfLogScaleFactor;
  167. vector<float> mvScaleFactors;
  168. vector<float> mvInvScaleFactors;
  169. vector<float> mvLevelSigma2;
  170. vector<float> mvInvLevelSigma2;
  171. // Undistorted Image Bounds (computed once).
  172. static float mnMinX;
  173. static float mnMaxX;
  174. static float mnMinY;
  175. static float mnMaxY;
  176. static bool mbInitialComputations;
  177. map<long unsigned int, cv::Point2f> mmProjectPoints;
  178. map<long unsigned int, cv::Point2f> mmMatchedInImage;
  179. string mNameFile;
  180. int mnDataset;
  181. #ifdef REGISTER_TIMES
  182. double mTimeORB_Ext;
  183. double mTimeStereoMatch;
  184. #endif
  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. cv::Matx31f mOwx;
  199. cv::Matx33f mRcwx;
  200. cv::Matx31f mtcwx;
  201. bool mbImuPreintegrated;
  202. std::mutex *mpMutexImu;
  203. public:
  204. GeometricCamera* mpCamera, *mpCamera2;
  205. //Number of KeyPoints extracted in the left and right images
  206. int Nleft, Nright;
  207. //Number of Non Lapping Keypoints
  208. int monoLeft, monoRight;
  209. //For stereo matching
  210. std::vector<int> mvLeftToRightMatch, mvRightToLeftMatch;
  211. //For stereo fisheye matching
  212. static cv::BFMatcher BFmatcher;
  213. //Triangulated stereo observations using as reference the left camera. These are
  214. //computed during ComputeStereoFishEyeMatches
  215. std::vector<cv::Mat> mvStereo3Dpoints;
  216. //Grid for the right image
  217. std::vector<std::size_t> mGridRight[FRAME_GRID_COLS][FRAME_GRID_ROWS];
  218. cv::Mat mTlr, mRlr, mtlr, mTrl;
  219. cv::Matx34f mTrlx, mTlrx;
  220. 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());
  221. //Stereo fisheye
  222. void ComputeStereoFishEyeMatches();
  223. bool isInFrustumChecks(MapPoint* pMP, float viewingCosLimit, bool bRight = false);
  224. cv::Mat UnprojectStereoFishEye(const int &i);
  225. cv::Mat imgLeft, imgRight;
  226. void PrintPointDistribution(){
  227. int left = 0, right = 0;
  228. int Nlim = (Nleft != -1) ? Nleft : N;
  229. for(int i = 0; i < N; i++){
  230. if(mvpMapPoints[i] && !mvbOutlier[i]){
  231. if(i < Nlim) left++;
  232. else right++;
  233. }
  234. }
  235. cout << "Point distribution in Frame: left-> " << left << " --- right-> " << right << endl;
  236. }
  237. };
  238. }// namespace ORB_SLAM
  239. #endif // FRAME_H