KeyFrameDatabase.h 2.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788
  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 KEYFRAMEDATABASE_H
  19. #define KEYFRAMEDATABASE_H
  20. #include <vector>
  21. #include <list>
  22. #include <set>
  23. #include "KeyFrame.h"
  24. #include "Frame.h"
  25. #include "ORBVocabulary.h"
  26. #include "Map.h"
  27. #include <boost/serialization/base_object.hpp>
  28. #include <boost/serialization/vector.hpp>
  29. #include <boost/serialization/list.hpp>
  30. #include<mutex>
  31. namespace ORB_SLAM3
  32. {
  33. class KeyFrame;
  34. class Frame;
  35. class Map;
  36. class KeyFrameDatabase
  37. {
  38. public:
  39. KeyFrameDatabase(const ORBVocabulary &voc);
  40. void add(KeyFrame* pKF);
  41. void erase(KeyFrame* pKF);
  42. void clear();
  43. void clearMap(Map* pMap);
  44. // Loop Detection(DEPRECATED)
  45. std::vector<KeyFrame *> DetectLoopCandidates(KeyFrame* pKF, float minScore);
  46. // Loop and Merge Detection
  47. void DetectCandidates(KeyFrame* pKF, float minScore,vector<KeyFrame*>& vpLoopCand, vector<KeyFrame*>& vpMergeCand);
  48. void DetectBestCandidates(KeyFrame *pKF, vector<KeyFrame*> &vpLoopCand, vector<KeyFrame*> &vpMergeCand, int nMinWords);
  49. void DetectNBestCandidates(KeyFrame *pKF, vector<KeyFrame*> &vpLoopCand, vector<KeyFrame*> &vpMergeCand, int nNumCandidates);
  50. // Relocalization
  51. std::vector<KeyFrame*> DetectRelocalizationCandidates(Frame* F, Map* pMap);
  52. void SetORBVocabulary(ORBVocabulary* pORBVoc);
  53. protected:
  54. // Associated vocabulary
  55. const ORBVocabulary* mpVoc;
  56. // Inverted file
  57. std::vector<list<KeyFrame*> > mvInvertedFile;
  58. // Mutex
  59. std::mutex mMutex;
  60. };
  61. } //namespace ORB_SLAM
  62. #endif