Viewer.h 2.2 KB

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