Viewer.h 2.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  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 VIEWER_H
  19. #define VIEWER_H
  20. #include "FrameDrawer.h"
  21. #include "MapDrawer.h"
  22. #include "Tracking.h"
  23. #include "System.h"
  24. #include "Settings.h"
  25. #include <mutex>
  26. namespace ORB_SLAM3
  27. {
  28. class Tracking;
  29. class FrameDrawer;
  30. class MapDrawer;
  31. class System;
  32. class Settings;
  33. class Viewer
  34. {
  35. public:
  36. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  37. Viewer(System* pSystem, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Tracking *pTracking, const string &strSettingPath, Settings* settings);
  38. void newParameterLoader(Settings* settings);
  39. // Main thread function. Draw points, keyframes, the current camera pose and the last processed
  40. // frame. Drawing is refreshed according to the camera fps. We use Pangolin.
  41. void Run();
  42. void RequestFinish();
  43. void RequestStop();
  44. bool isFinished();
  45. bool isStopped();
  46. bool isStepByStep();
  47. void Release();
  48. //void SetTrackingPause();
  49. bool both;
  50. private:
  51. bool ParseViewerParamFile(cv::FileStorage &fSettings);
  52. bool Stop();
  53. System* mpSystem;
  54. FrameDrawer* mpFrameDrawer;
  55. MapDrawer* mpMapDrawer;
  56. Tracking* mpTracker;
  57. // 1/fps in ms
  58. double mT;
  59. float mImageWidth, mImageHeight;
  60. float mImageViewerScale;
  61. float mViewpointX, mViewpointY, mViewpointZ, mViewpointF;
  62. bool CheckFinish();
  63. void SetFinish();
  64. bool mbFinishRequested;
  65. bool mbFinished;
  66. std::mutex mMutexFinish;
  67. bool mbStopped;
  68. bool mbStopRequested;
  69. std::mutex mMutexStop;
  70. bool mbStopTrack;
  71. };
  72. }
  73. #endif // VIEWER_H