FrameDrawer.h 2.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091
  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 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. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  35. FrameDrawer(Atlas* pAtlas);
  36. // Update info from the last processed frame.
  37. void Update(Tracking *pTracker);
  38. // Draw last processed frame.
  39. cv::Mat DrawFrame(float imageScale=1.f);
  40. cv::Mat DrawRightFrame(float imageScale=1.f);
  41. bool both;
  42. protected:
  43. void DrawTextInfo(cv::Mat &im, int nState, cv::Mat &imText);
  44. // Info of the frame to be drawn
  45. cv::Mat mIm, mImRight;
  46. int N;
  47. vector<cv::KeyPoint> mvCurrentKeys,mvCurrentKeysRight;
  48. vector<bool> mvbMap, mvbVO;
  49. bool mbOnlyTracking;
  50. int mnTracked, mnTrackedVO;
  51. vector<cv::KeyPoint> mvIniKeys;
  52. vector<int> mvIniMatches;
  53. int mState;
  54. std::vector<float> mvCurrentDepth;
  55. float mThDepth;
  56. Atlas* mpAtlas;
  57. std::mutex mMutex;
  58. vector<pair<cv::Point2f, cv::Point2f> > mvTracks;
  59. Frame mCurrentFrame;
  60. vector<MapPoint*> mvpLocalMap;
  61. vector<cv::KeyPoint> mvMatchedKeys;
  62. vector<MapPoint*> mvpMatchedMPs;
  63. vector<cv::KeyPoint> mvOutlierKeys;
  64. vector<MapPoint*> mvpOutlierMPs;
  65. map<long unsigned int, cv::Point2f> mmProjectPoints;
  66. map<long unsigned int, cv::Point2f> mmMatchedInImage;
  67. };
  68. } //namespace ORB_SLAM
  69. #endif // FRAMEDRAWER_H