KeyFrame.h 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623
  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. template<class Archive>
  43. void serializeMatrix(Archive& ar, cv::Mat& mat, const unsigned int version)
  44. {
  45. int cols, rows, type;
  46. bool continuous;
  47. if (Archive::is_saving::value) {
  48. cols = mat.cols; rows = mat.rows; type = mat.type();
  49. continuous = mat.isContinuous();
  50. }
  51. ar & cols & rows & type & continuous;
  52. if (Archive::is_loading::value)
  53. mat.create(rows, cols, type);
  54. if (continuous) {
  55. const unsigned int data_size = rows * cols * mat.elemSize();
  56. ar & boost::serialization::make_array(mat.ptr(), data_size);
  57. } else {
  58. const unsigned int row_size = cols*mat.elemSize();
  59. for (int i = 0; i < rows; i++) {
  60. ar & boost::serialization::make_array(mat.ptr(i), row_size);
  61. }
  62. }
  63. }
  64. template<class Archive>
  65. void serializeMatrix(Archive& ar, const cv::Mat& mat, const unsigned int version)
  66. {
  67. cv::Mat matAux = mat;
  68. serializeMatrix(ar, matAux,version);
  69. if (Archive::is_loading::value)
  70. {
  71. cv::Mat* ptr;
  72. ptr = (cv::Mat*)( &mat );
  73. *ptr = matAux;
  74. }
  75. }
  76. friend class boost::serialization::access;
  77. template<class Archive>
  78. void serializeVectorKeyPoints(Archive& ar, const vector<cv::KeyPoint>& vKP, const unsigned int version)
  79. {
  80. int NumEl;
  81. if (Archive::is_saving::value) {
  82. NumEl = vKP.size();
  83. }
  84. ar & NumEl;
  85. vector<cv::KeyPoint> vKPaux = vKP;
  86. if (Archive::is_loading::value)
  87. vKPaux.reserve(NumEl);
  88. for(int i=0; i < NumEl; ++i)
  89. {
  90. cv::KeyPoint KPi;
  91. if (Archive::is_loading::value)
  92. KPi = cv::KeyPoint();
  93. if (Archive::is_saving::value)
  94. KPi = vKPaux[i];
  95. ar & KPi.angle;
  96. ar & KPi.response;
  97. ar & KPi.size;
  98. ar & KPi.pt.x;
  99. ar & KPi.pt.y;
  100. ar & KPi.class_id;
  101. ar & KPi.octave;
  102. if (Archive::is_loading::value)
  103. vKPaux.push_back(KPi);
  104. }
  105. if (Archive::is_loading::value)
  106. {
  107. vector<cv::KeyPoint> *ptr;
  108. ptr = (vector<cv::KeyPoint>*)( &vKP );
  109. *ptr = vKPaux;
  110. }
  111. }
  112. template<class Archive>
  113. void serialize(Archive& ar, const unsigned int version)
  114. {
  115. ar & mnId;
  116. ar & const_cast<long unsigned int&>(mnFrameId);
  117. ar & const_cast<double&>(mTimeStamp);
  118. // Grid
  119. ar & const_cast<int&>(mnGridCols);
  120. ar & const_cast<int&>(mnGridRows);
  121. ar & const_cast<float&>(mfGridElementWidthInv);
  122. ar & const_cast<float&>(mfGridElementHeightInv);
  123. // Variables of tracking
  124. ar & mnTrackReferenceForFrame;
  125. ar & mnFuseTargetForKF;
  126. // Variables of local mapping
  127. ar & mnBALocalForKF;
  128. ar & mnBAFixedForKF;
  129. ar & mnNumberOfOpt;
  130. // Variables used by KeyFrameDatabase
  131. ar & mnLoopQuery;
  132. ar & mnLoopWords;
  133. ar & mLoopScore;
  134. ar & mnRelocQuery;
  135. ar & mnRelocWords;
  136. ar & mRelocScore;
  137. ar & mnMergeQuery;
  138. ar & mnMergeWords;
  139. ar & mMergeScore;
  140. ar & mnPlaceRecognitionQuery;
  141. ar & mnPlaceRecognitionWords;
  142. ar & mPlaceRecognitionScore;
  143. ar & mbCurrentPlaceRecognition;
  144. // Variables of loop closing
  145. serializeMatrix(ar,mTcwGBA,version);
  146. serializeMatrix(ar,mTcwBefGBA,version);
  147. serializeMatrix(ar,mVwbGBA,version);
  148. serializeMatrix(ar,mVwbBefGBA,version);
  149. ar & mBiasGBA;
  150. ar & mnBAGlobalForKF;
  151. // Variables of Merging
  152. serializeMatrix(ar,mTcwMerge,version);
  153. serializeMatrix(ar,mTcwBefMerge,version);
  154. serializeMatrix(ar,mTwcBefMerge,version);
  155. serializeMatrix(ar,mVwbMerge,version);
  156. serializeMatrix(ar,mVwbBefMerge,version);
  157. ar & mBiasMerge;
  158. ar & mnMergeCorrectedForKF;
  159. ar & mnMergeForKF;
  160. ar & mfScaleMerge;
  161. ar & mnBALocalForMerge;
  162. // Scale
  163. ar & mfScale;
  164. // Calibration parameters
  165. ar & const_cast<float&>(fx);
  166. ar & const_cast<float&>(fy);
  167. ar & const_cast<float&>(invfx);
  168. ar & const_cast<float&>(invfy);
  169. ar & const_cast<float&>(cx);
  170. ar & const_cast<float&>(cy);
  171. ar & const_cast<float&>(mbf);
  172. ar & const_cast<float&>(mb);
  173. ar & const_cast<float&>(mThDepth);
  174. serializeMatrix(ar,mDistCoef,version);
  175. // Number of Keypoints
  176. ar & const_cast<int&>(N);
  177. // KeyPoints
  178. serializeVectorKeyPoints(ar,mvKeys,version);
  179. serializeVectorKeyPoints(ar,mvKeysUn,version);
  180. ar & const_cast<vector<float>& >(mvuRight);
  181. ar & const_cast<vector<float>& >(mvDepth);
  182. serializeMatrix(ar,mDescriptors,version);
  183. // BOW
  184. ar & mBowVec;
  185. ar & mFeatVec;
  186. // Pose relative to parent
  187. serializeMatrix(ar,mTcp,version);
  188. // Scale
  189. ar & const_cast<int&>(mnScaleLevels);
  190. ar & const_cast<float&>(mfScaleFactor);
  191. ar & const_cast<float&>(mfLogScaleFactor);
  192. ar & const_cast<vector<float>& >(mvScaleFactors);
  193. ar & const_cast<vector<float>& >(mvLevelSigma2);
  194. ar & const_cast<vector<float>& >(mvInvLevelSigma2);
  195. // Image bounds and calibration
  196. ar & const_cast<int&>(mnMinX);
  197. ar & const_cast<int&>(mnMinY);
  198. ar & const_cast<int&>(mnMaxX);
  199. ar & const_cast<int&>(mnMaxY);
  200. serializeMatrix(ar,mK,version);
  201. // Pose
  202. serializeMatrix(ar,Tcw,version);
  203. // MapPointsId associated to keypoints
  204. ar & mvBackupMapPointsId;
  205. // Grid
  206. ar & mGrid;
  207. // Connected KeyFrameWeight
  208. ar & mBackupConnectedKeyFrameIdWeights;
  209. // Spanning Tree and Loop Edges
  210. ar & mbFirstConnection;
  211. ar & mBackupParentId;
  212. ar & mvBackupChildrensId;
  213. ar & mvBackupLoopEdgesId;
  214. ar & mvBackupMergeEdgesId;
  215. // Bad flags
  216. ar & mbNotErase;
  217. ar & mbToBeErased;
  218. ar & mbBad;
  219. ar & mHalfBaseline;
  220. // Camera variables
  221. ar & mnBackupIdCamera;
  222. ar & mnBackupIdCamera2;
  223. // Fisheye variables
  224. /*ar & mvLeftToRightMatch;
  225. ar & mvRightToLeftMatch;
  226. ar & NLeft;
  227. ar & NRight;
  228. serializeMatrix(ar, mTlr, version);
  229. //serializeMatrix(ar, mTrl, version);
  230. serializeVectorKeyPoints(ar, mvKeysRight, version);
  231. ar & mGridRight;
  232. // Inertial variables
  233. ar & mImuBias;
  234. ar & mBackupImuPreintegrated;
  235. ar & mImuCalib;
  236. ar & mBackupPrevKFId;
  237. ar & mBackupNextKFId;
  238. ar & bImu;
  239. serializeMatrix(ar, Vw, version);
  240. serializeMatrix(ar, Owb, version);*/
  241. }
  242. public:
  243. KeyFrame();
  244. KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB);
  245. // Pose functions
  246. void SetPose(const cv::Mat &Tcw);
  247. void SetVelocity(const cv::Mat &Vw_);
  248. cv::Mat GetPose();
  249. cv::Mat GetPoseInverse();
  250. cv::Mat GetCameraCenter();
  251. cv::Mat GetImuPosition();
  252. cv::Mat GetImuRotation();
  253. cv::Mat GetImuPose();
  254. cv::Mat GetStereoCenter();
  255. cv::Mat GetRotation();
  256. cv::Mat GetTranslation();
  257. cv::Mat GetVelocity();
  258. // Bag of Words Representation
  259. void ComputeBoW();
  260. // Covisibility graph functions
  261. void AddConnection(KeyFrame* pKF, const int &weight);
  262. void EraseConnection(KeyFrame* pKF);
  263. void UpdateConnections(bool upParent=true);
  264. void UpdateBestCovisibles();
  265. std::set<KeyFrame *> GetConnectedKeyFrames();
  266. std::vector<KeyFrame* > GetVectorCovisibleKeyFrames();
  267. std::vector<KeyFrame*> GetBestCovisibilityKeyFrames(const int &N);
  268. std::vector<KeyFrame*> GetCovisiblesByWeight(const int &w);
  269. int GetWeight(KeyFrame* pKF);
  270. // Spanning tree functions
  271. void AddChild(KeyFrame* pKF);
  272. void EraseChild(KeyFrame* pKF);
  273. void ChangeParent(KeyFrame* pKF);
  274. std::set<KeyFrame*> GetChilds();
  275. KeyFrame* GetParent();
  276. bool hasChild(KeyFrame* pKF);
  277. void SetFirstConnection(bool bFirst);
  278. // Loop Edges
  279. void AddLoopEdge(KeyFrame* pKF);
  280. std::set<KeyFrame*> GetLoopEdges();
  281. // Merge Edges
  282. void AddMergeEdge(KeyFrame* pKF);
  283. set<KeyFrame*> GetMergeEdges();
  284. // MapPoint observation functions
  285. int GetNumberMPs();
  286. void AddMapPoint(MapPoint* pMP, const size_t &idx);
  287. void EraseMapPointMatch(const int &idx);
  288. void EraseMapPointMatch(MapPoint* pMP);
  289. void ReplaceMapPointMatch(const int &idx, MapPoint* pMP);
  290. std::set<MapPoint*> GetMapPoints();
  291. std::vector<MapPoint*> GetMapPointMatches();
  292. int TrackedMapPoints(const int &minObs);
  293. MapPoint* GetMapPoint(const size_t &idx);
  294. // KeyPoint functions
  295. std::vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r, const bool bRight = false) const;
  296. cv::Mat UnprojectStereo(int i);
  297. // Image
  298. bool IsInImage(const float &x, const float &y) const;
  299. // Enable/Disable bad flag changes
  300. void SetNotErase();
  301. void SetErase();
  302. // Set/check bad flag
  303. void SetBadFlag();
  304. bool isBad();
  305. // Compute Scene Depth (q=2 median). Used in monocular.
  306. float ComputeSceneMedianDepth(const int q);
  307. static bool weightComp( int a, int b){
  308. return a>b;
  309. }
  310. static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){
  311. return pKF1->mnId<pKF2->mnId;
  312. }
  313. Map* GetMap();
  314. void UpdateMap(Map* pMap);
  315. void SetNewBias(const IMU::Bias &b);
  316. cv::Mat GetGyroBias();
  317. cv::Mat GetAccBias();
  318. IMU::Bias GetImuBias();
  319. bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
  320. bool ProjectPointUnDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
  321. void PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP, set<GeometricCamera*>& spCam);
  322. void PostLoad(map<long unsigned int, KeyFrame*>& mpKFid, map<long unsigned int, MapPoint*>& mpMPid, map<unsigned int, GeometricCamera*>& mpCamId);
  323. void SetORBVocabulary(ORBVocabulary* pORBVoc);
  324. void SetKeyFrameDatabase(KeyFrameDatabase* pKFDB);
  325. bool bImu;
  326. // The following variables are accesed from only 1 thread or never change (no mutex needed).
  327. public:
  328. static long unsigned int nNextId;
  329. long unsigned int mnId;
  330. const long unsigned int mnFrameId;
  331. const double mTimeStamp;
  332. // Grid (to speed up feature matching)
  333. const int mnGridCols;
  334. const int mnGridRows;
  335. const float mfGridElementWidthInv;
  336. const float mfGridElementHeightInv;
  337. // Variables used by the tracking
  338. long unsigned int mnTrackReferenceForFrame;
  339. long unsigned int mnFuseTargetForKF;
  340. // Variables used by the local mapping
  341. long unsigned int mnBALocalForKF;
  342. long unsigned int mnBAFixedForKF;
  343. //Number of optimizations by BA(amount of iterations in BA)
  344. long unsigned int mnNumberOfOpt;
  345. // Variables used by the keyframe database
  346. long unsigned int mnLoopQuery;
  347. int mnLoopWords;
  348. float mLoopScore;
  349. long unsigned int mnRelocQuery;
  350. int mnRelocWords;
  351. float mRelocScore;
  352. long unsigned int mnMergeQuery;
  353. int mnMergeWords;
  354. float mMergeScore;
  355. long unsigned int mnPlaceRecognitionQuery;
  356. int mnPlaceRecognitionWords;
  357. float mPlaceRecognitionScore;
  358. bool mbCurrentPlaceRecognition;
  359. // Variables used by loop closing
  360. cv::Mat mTcwGBA;
  361. cv::Mat mTcwBefGBA;
  362. cv::Mat mVwbGBA;
  363. cv::Mat mVwbBefGBA;
  364. IMU::Bias mBiasGBA;
  365. long unsigned int mnBAGlobalForKF;
  366. // Variables used by merging
  367. cv::Mat mTcwMerge;
  368. cv::Mat mTcwBefMerge;
  369. cv::Mat mTwcBefMerge;
  370. cv::Mat mVwbMerge;
  371. cv::Mat mVwbBefMerge;
  372. IMU::Bias mBiasMerge;
  373. long unsigned int mnMergeCorrectedForKF;
  374. long unsigned int mnMergeForKF;
  375. float mfScaleMerge;
  376. long unsigned int mnBALocalForMerge;
  377. float mfScale;
  378. // Calibration parameters
  379. const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth;
  380. cv::Mat mDistCoef;
  381. // Number of KeyPoints
  382. const int N;
  383. // KeyPoints, stereo coordinate and descriptors (all associated by an index)
  384. const std::vector<cv::KeyPoint> mvKeys;
  385. const std::vector<cv::KeyPoint> mvKeysUn;
  386. const std::vector<float> mvuRight; // negative value for monocular points
  387. const std::vector<float> mvDepth; // negative value for monocular points
  388. const cv::Mat mDescriptors;
  389. //BoW
  390. DBoW2::BowVector mBowVec;
  391. DBoW2::FeatureVector mFeatVec;
  392. // Pose relative to parent (this is computed when bad flag is activated)
  393. cv::Mat mTcp;
  394. // Scale
  395. const int mnScaleLevels;
  396. const float mfScaleFactor;
  397. const float mfLogScaleFactor;
  398. const std::vector<float> mvScaleFactors;
  399. const std::vector<float> mvLevelSigma2;
  400. const std::vector<float> mvInvLevelSigma2;
  401. // Image bounds and calibration
  402. const int mnMinX;
  403. const int mnMinY;
  404. const int mnMaxX;
  405. const int mnMaxY;
  406. const cv::Mat mK;
  407. // Preintegrated IMU measurements from previous keyframe
  408. KeyFrame* mPrevKF;
  409. KeyFrame* mNextKF;
  410. IMU::Preintegrated* mpImuPreintegrated;
  411. IMU::Calib mImuCalib;
  412. unsigned int mnOriginMapId;
  413. string mNameFile;
  414. int mnDataset;
  415. std::vector <KeyFrame*> mvpLoopCandKFs;
  416. std::vector <KeyFrame*> mvpMergeCandKFs;
  417. bool mbHasHessian;
  418. cv::Mat mHessianPose;
  419. // The following variables need to be accessed trough a mutex to be thread safe.
  420. protected:
  421. // SE3 Pose and camera center
  422. cv::Mat Tcw;
  423. cv::Mat Twc;
  424. cv::Mat Ow;
  425. cv::Mat Cw; // Stereo middel point. Only for visualization
  426. // IMU position
  427. cv::Mat Owb;
  428. // Velocity (Only used for inertial SLAM)
  429. cv::Mat Vw;
  430. // Imu bias
  431. IMU::Bias mImuBias;
  432. // MapPoints associated to keypoints
  433. std::vector<MapPoint*> mvpMapPoints;
  434. // For save relation without pointer, this is necessary for save/load function
  435. std::vector<long long int> mvBackupMapPointsId;
  436. // BoW
  437. KeyFrameDatabase* mpKeyFrameDB;
  438. ORBVocabulary* mpORBvocabulary;
  439. // Grid over the image to speed up feature matching
  440. std::vector< std::vector <std::vector<size_t> > > mGrid;
  441. std::map<KeyFrame*,int> mConnectedKeyFrameWeights;
  442. std::vector<KeyFrame*> mvpOrderedConnectedKeyFrames;
  443. std::vector<int> mvOrderedWeights;
  444. // For save relation without pointer, this is necessary for save/load function
  445. std::map<long unsigned int, int> mBackupConnectedKeyFrameIdWeights;
  446. // Spanning Tree and Loop Edges
  447. bool mbFirstConnection;
  448. KeyFrame* mpParent;
  449. std::set<KeyFrame*> mspChildrens;
  450. std::set<KeyFrame*> mspLoopEdges;
  451. std::set<KeyFrame*> mspMergeEdges;
  452. // For save relation without pointer, this is necessary for save/load function
  453. long long int mBackupParentId;
  454. std::vector<long unsigned int> mvBackupChildrensId;
  455. std::vector<long unsigned int> mvBackupLoopEdgesId;
  456. std::vector<long unsigned int> mvBackupMergeEdgesId;
  457. // Bad flags
  458. bool mbNotErase;
  459. bool mbToBeErased;
  460. bool mbBad;
  461. float mHalfBaseline; // Only for visualization
  462. Map* mpMap;
  463. std::mutex mMutexPose; // for pose, velocity and biases
  464. std::mutex mMutexConnections;
  465. std::mutex mMutexFeatures;
  466. std::mutex mMutexMap;
  467. // Backup variables for inertial
  468. long long int mBackupPrevKFId;
  469. long long int mBackupNextKFId;
  470. IMU::Preintegrated mBackupImuPreintegrated;
  471. // Backup for Cameras
  472. unsigned int mnBackupIdCamera, mnBackupIdCamera2;
  473. public:
  474. GeometricCamera* mpCamera, *mpCamera2;
  475. //Indexes of stereo observations correspondences
  476. std::vector<int> mvLeftToRightMatch, mvRightToLeftMatch;
  477. //Transformation matrix between cameras in stereo fisheye
  478. cv::Mat mTlr;
  479. cv::Mat mTrl;
  480. //KeyPoints in the right image (for stereo fisheye, coordinates are needed)
  481. const std::vector<cv::KeyPoint> mvKeysRight;
  482. const int NLeft, NRight;
  483. std::vector< std::vector <std::vector<size_t> > > mGridRight;
  484. cv::Mat GetRightPose();
  485. cv::Mat GetRightPoseInverse();
  486. cv::Mat GetRightPoseInverseH();
  487. cv::Mat GetRightCameraCenter();
  488. cv::Mat GetRightRotation();
  489. cv::Mat GetRightTranslation();
  490. cv::Mat imgLeft, imgRight; //TODO Backup??
  491. void PrintPointDistribution(){
  492. int left = 0, right = 0;
  493. int Nlim = (NLeft != -1) ? NLeft : N;
  494. for(int i = 0; i < N; i++){
  495. if(mvpMapPoints[i]){
  496. if(i < Nlim) left++;
  497. else right++;
  498. }
  499. }
  500. cout << "Point distribution in KeyFrame: left-> " << left << " --- right-> " << right << endl;
  501. }
  502. };
  503. } //namespace ORB_SLAM
  504. #endif // KEYFRAME_H