KeyFrame.h 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389
  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 KEYFRAME_H
  19. #define KEYFRAME_H
  20. #include "MapPoint.h"
  21. #include "Thirdparty/DBoW2/DBoW2/BowVector.h"
  22. #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
  23. #include "ORBVocabulary.h"
  24. #include "ORBextractor.h"
  25. #include "Frame.h"
  26. #include "KeyFrameDatabase.h"
  27. #include "ImuTypes.h"
  28. #include "GeometricCamera.h"
  29. #include <mutex>
  30. #include <boost/serialization/base_object.hpp>
  31. #include <boost/serialization/vector.hpp>
  32. #include <boost/serialization/map.hpp>
  33. namespace ORB_SLAM3
  34. {
  35. class Map;
  36. class MapPoint;
  37. class Frame;
  38. class KeyFrameDatabase;
  39. class GeometricCamera;
  40. class KeyFrame
  41. {
  42. public:
  43. KeyFrame();
  44. KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB);
  45. // Pose functions
  46. void SetPose(const cv::Mat &Tcw);
  47. void SetVelocity(const cv::Mat &Vw_);
  48. cv::Mat GetPose();
  49. cv::Mat GetPoseInverse();
  50. cv::Mat GetCameraCenter();
  51. cv::Mat GetImuPosition();
  52. cv::Mat GetImuRotation();
  53. cv::Mat GetImuPose();
  54. cv::Mat GetStereoCenter();
  55. cv::Mat GetRotation();
  56. cv::Mat GetTranslation();
  57. cv::Mat GetVelocity();
  58. cv::Matx33f GetRotation_();
  59. cv::Matx31f GetTranslation_();
  60. cv::Matx31f GetCameraCenter_();
  61. cv::Matx33f GetRightRotation_();
  62. cv::Matx31f GetRightTranslation_();
  63. cv::Matx44f GetRightPose_();
  64. cv::Matx31f GetRightCameraCenter_();
  65. cv::Matx44f GetPose_();
  66. // Bag of Words Representation
  67. void ComputeBoW();
  68. // Covisibility graph functions
  69. void AddConnection(KeyFrame* pKF, const int &weight);
  70. void EraseConnection(KeyFrame* pKF);
  71. void UpdateConnections(bool upParent=true);
  72. void UpdateBestCovisibles();
  73. std::set<KeyFrame *> GetConnectedKeyFrames();
  74. std::vector<KeyFrame* > GetVectorCovisibleKeyFrames();
  75. std::vector<KeyFrame*> GetBestCovisibilityKeyFrames(const int &N);
  76. std::vector<KeyFrame*> GetCovisiblesByWeight(const int &w);
  77. int GetWeight(KeyFrame* pKF);
  78. // Spanning tree functions
  79. void AddChild(KeyFrame* pKF);
  80. void EraseChild(KeyFrame* pKF);
  81. void ChangeParent(KeyFrame* pKF);
  82. std::set<KeyFrame*> GetChilds();
  83. KeyFrame* GetParent();
  84. bool hasChild(KeyFrame* pKF);
  85. void SetFirstConnection(bool bFirst);
  86. // Loop Edges
  87. void AddLoopEdge(KeyFrame* pKF);
  88. std::set<KeyFrame*> GetLoopEdges();
  89. // Merge Edges
  90. void AddMergeEdge(KeyFrame* pKF);
  91. set<KeyFrame*> GetMergeEdges();
  92. // MapPoint observation functions
  93. int GetNumberMPs();
  94. void AddMapPoint(MapPoint* pMP, const size_t &idx);
  95. void EraseMapPointMatch(const int &idx);
  96. void EraseMapPointMatch(MapPoint* pMP);
  97. void ReplaceMapPointMatch(const int &idx, MapPoint* pMP);
  98. std::set<MapPoint*> GetMapPoints();
  99. std::vector<MapPoint*> GetMapPointMatches();
  100. int TrackedMapPoints(const int &minObs);
  101. MapPoint* GetMapPoint(const size_t &idx);
  102. // KeyPoint functions
  103. std::vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r, const bool bRight = false) const;
  104. cv::Mat UnprojectStereo(int i);
  105. cv::Matx31f UnprojectStereo_(int i);
  106. // Image
  107. bool IsInImage(const float &x, const float &y) const;
  108. // Enable/Disable bad flag changes
  109. void SetNotErase();
  110. void SetErase();
  111. // Set/check bad flag
  112. void SetBadFlag();
  113. bool isBad();
  114. // Compute Scene Depth (q=2 median). Used in monocular.
  115. float ComputeSceneMedianDepth(const int q);
  116. static bool weightComp( int a, int b){
  117. return a>b;
  118. }
  119. static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){
  120. return pKF1->mnId<pKF2->mnId;
  121. }
  122. Map* GetMap();
  123. void UpdateMap(Map* pMap);
  124. void SetNewBias(const IMU::Bias &b);
  125. cv::Mat GetGyroBias();
  126. cv::Mat GetAccBias();
  127. IMU::Bias GetImuBias();
  128. bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
  129. bool ProjectPointUnDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
  130. void SetORBVocabulary(ORBVocabulary* pORBVoc);
  131. void SetKeyFrameDatabase(KeyFrameDatabase* pKFDB);
  132. bool bImu;
  133. // The following variables are accesed from only 1 thread or never change (no mutex needed).
  134. public:
  135. static long unsigned int nNextId;
  136. long unsigned int mnId;
  137. const long unsigned int mnFrameId;
  138. const double mTimeStamp;
  139. // Grid (to speed up feature matching)
  140. const int mnGridCols;
  141. const int mnGridRows;
  142. const float mfGridElementWidthInv;
  143. const float mfGridElementHeightInv;
  144. // Variables used by the tracking
  145. long unsigned int mnTrackReferenceForFrame;
  146. long unsigned int mnFuseTargetForKF;
  147. // Variables used by the local mapping
  148. long unsigned int mnBALocalForKF;
  149. long unsigned int mnBAFixedForKF;
  150. //Number of optimizations by BA(amount of iterations in BA)
  151. long unsigned int mnNumberOfOpt;
  152. // Variables used by the keyframe database
  153. long unsigned int mnLoopQuery;
  154. int mnLoopWords;
  155. float mLoopScore;
  156. long unsigned int mnRelocQuery;
  157. int mnRelocWords;
  158. float mRelocScore;
  159. long unsigned int mnMergeQuery;
  160. int mnMergeWords;
  161. float mMergeScore;
  162. long unsigned int mnPlaceRecognitionQuery;
  163. int mnPlaceRecognitionWords;
  164. float mPlaceRecognitionScore;
  165. bool mbCurrentPlaceRecognition;
  166. // Variables used by loop closing
  167. cv::Mat mTcwGBA;
  168. cv::Mat mTcwBefGBA;
  169. cv::Mat mVwbGBA;
  170. cv::Mat mVwbBefGBA;
  171. IMU::Bias mBiasGBA;
  172. long unsigned int mnBAGlobalForKF;
  173. // Variables used by merging
  174. cv::Mat mTcwMerge;
  175. cv::Mat mTcwBefMerge;
  176. cv::Mat mTwcBefMerge;
  177. cv::Mat mVwbMerge;
  178. cv::Mat mVwbBefMerge;
  179. IMU::Bias mBiasMerge;
  180. long unsigned int mnMergeCorrectedForKF;
  181. long unsigned int mnMergeForKF;
  182. float mfScaleMerge;
  183. long unsigned int mnBALocalForMerge;
  184. float mfScale;
  185. // Calibration parameters
  186. const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth;
  187. cv::Mat mDistCoef;
  188. // Number of KeyPoints
  189. const int N;
  190. // KeyPoints, stereo coordinate and descriptors (all associated by an index)
  191. const std::vector<cv::KeyPoint> mvKeys;
  192. const std::vector<cv::KeyPoint> mvKeysUn;
  193. const std::vector<float> mvuRight; // negative value for monocular points
  194. const std::vector<float> mvDepth; // negative value for monocular points
  195. const cv::Mat mDescriptors;
  196. //BoW
  197. DBoW2::BowVector mBowVec;
  198. DBoW2::FeatureVector mFeatVec;
  199. // Pose relative to parent (this is computed when bad flag is activated)
  200. cv::Mat mTcp;
  201. // Scale
  202. const int mnScaleLevels;
  203. const float mfScaleFactor;
  204. const float mfLogScaleFactor;
  205. const std::vector<float> mvScaleFactors;
  206. const std::vector<float> mvLevelSigma2;
  207. const std::vector<float> mvInvLevelSigma2;
  208. // Image bounds and calibration
  209. const int mnMinX;
  210. const int mnMinY;
  211. const int mnMaxX;
  212. const int mnMaxY;
  213. const cv::Mat mK;
  214. // Preintegrated IMU measurements from previous keyframe
  215. KeyFrame* mPrevKF;
  216. KeyFrame* mNextKF;
  217. IMU::Preintegrated* mpImuPreintegrated;
  218. IMU::Calib mImuCalib;
  219. unsigned int mnOriginMapId;
  220. string mNameFile;
  221. int mnDataset;
  222. std::vector <KeyFrame*> mvpLoopCandKFs;
  223. std::vector <KeyFrame*> mvpMergeCandKFs;
  224. bool mbHasHessian;
  225. cv::Mat mHessianPose;
  226. // The following variables need to be accessed trough a mutex to be thread safe.
  227. protected:
  228. // SE3 Pose and camera center
  229. cv::Mat Tcw;
  230. cv::Mat Twc;
  231. cv::Mat Ow;
  232. cv::Mat Cw; // Stereo middel point. Only for visualization
  233. cv::Matx44f Tcw_, Twc_, Tlr_;
  234. cv::Matx31f Ow_;
  235. // IMU position
  236. cv::Mat Owb;
  237. // Velocity (Only used for inertial SLAM)
  238. cv::Mat Vw;
  239. // Imu bias
  240. IMU::Bias mImuBias;
  241. // MapPoints associated to keypoints
  242. std::vector<MapPoint*> mvpMapPoints;
  243. // BoW
  244. KeyFrameDatabase* mpKeyFrameDB;
  245. ORBVocabulary* mpORBvocabulary;
  246. // Grid over the image to speed up feature matching
  247. std::vector< std::vector <std::vector<size_t> > > mGrid;
  248. std::map<KeyFrame*,int> mConnectedKeyFrameWeights;
  249. std::vector<KeyFrame*> mvpOrderedConnectedKeyFrames;
  250. std::vector<int> mvOrderedWeights;
  251. // Spanning Tree and Loop Edges
  252. bool mbFirstConnection;
  253. KeyFrame* mpParent;
  254. std::set<KeyFrame*> mspChildrens;
  255. std::set<KeyFrame*> mspLoopEdges;
  256. std::set<KeyFrame*> mspMergeEdges;
  257. // Bad flags
  258. bool mbNotErase;
  259. bool mbToBeErased;
  260. bool mbBad;
  261. float mHalfBaseline; // Only for visualization
  262. Map* mpMap;
  263. std::mutex mMutexPose; // for pose, velocity and biases
  264. std::mutex mMutexConnections;
  265. std::mutex mMutexFeatures;
  266. std::mutex mMutexMap;
  267. public:
  268. GeometricCamera* mpCamera, *mpCamera2;
  269. //Indexes of stereo observations correspondences
  270. std::vector<int> mvLeftToRightMatch, mvRightToLeftMatch;
  271. //Transformation matrix between cameras in stereo fisheye
  272. cv::Mat mTlr;
  273. cv::Mat mTrl;
  274. //KeyPoints in the right image (for stereo fisheye, coordinates are needed)
  275. const std::vector<cv::KeyPoint> mvKeysRight;
  276. const int NLeft, NRight;
  277. std::vector< std::vector <std::vector<size_t> > > mGridRight;
  278. cv::Mat GetRightPose();
  279. cv::Mat GetRightPoseInverse();
  280. cv::Mat GetRightPoseInverseH();
  281. cv::Mat GetRightCameraCenter();
  282. cv::Mat GetRightRotation();
  283. cv::Mat GetRightTranslation();
  284. cv::Mat imgLeft, imgRight;
  285. void PrintPointDistribution(){
  286. int left = 0, right = 0;
  287. int Nlim = (NLeft != -1) ? NLeft : N;
  288. for(int i = 0; i < N; i++){
  289. if(mvpMapPoints[i]){
  290. if(i < Nlim) left++;
  291. else right++;
  292. }
  293. }
  294. cout << "Point distribution in KeyFrame: left-> " << left << " --- right-> " << right << endl;
  295. }
  296. };
  297. } //namespace ORB_SLAM
  298. #endif // KEYFRAME_H