KeyFrame.h 16 KB

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