FrameDrawer.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 FRAMEDRAWER_H
  19. #define FRAMEDRAWER_H
  20. #include "Tracking.h"
  21. #include "MapPoint.h"
  22. #include "Atlas.h"
  23. #include<opencv2/core/core.hpp>
  24. #include<opencv2/features2d/features2d.hpp>
  25. #include<mutex>
  26. #include <unordered_set>
  27. namespace ORB_SLAM3
  28. {
  29. class Tracking;
  30. class Viewer;
  31. class FrameDrawer
  32. {
  33. public:
  34. FrameDrawer(Atlas* pAtlas);
  35. // Update info from the last processed frame.
  36. void Update(Tracking *pTracker);
  37. // Draw last processed frame.
  38. cv::Mat DrawFrame(bool bOldFeatures=true);
  39. cv::Mat DrawRightFrame();
  40. bool both;
  41. protected:
  42. void DrawTextInfo(cv::Mat &im, int nState, cv::Mat &imText);
  43. // Info of the frame to be drawn
  44. cv::Mat mIm, mImRight;
  45. int N;
  46. vector<cv::KeyPoint> mvCurrentKeys,mvCurrentKeysRight;
  47. vector<bool> mvbMap, mvbVO;
  48. bool mbOnlyTracking;
  49. int mnTracked, mnTrackedVO;
  50. vector<cv::KeyPoint> mvIniKeys;
  51. vector<int> mvIniMatches;
  52. int mState;
  53. Atlas* mpAtlas;
  54. std::mutex mMutex;
  55. vector<pair<cv::Point2f, cv::Point2f> > mvTracks;
  56. Frame mCurrentFrame;
  57. vector<MapPoint*> mvpLocalMap;
  58. vector<cv::KeyPoint> mvMatchedKeys;
  59. vector<MapPoint*> mvpMatchedMPs;
  60. vector<cv::KeyPoint> mvOutlierKeys;
  61. vector<MapPoint*> mvpOutlierMPs;
  62. map<long unsigned int, cv::Point2f> mmProjectPoints;
  63. map<long unsigned int, cv::Point2f> mmMatchedInImage;
  64. };
  65. } //namespace ORB_SLAM
  66. #endif // FRAMEDRAWER_H