ORB SLA2
Viewer.h
1 
22 #ifndef VIEWER_H
23 #define VIEWER_H
24 
25 #include "FrameDrawer.h"
26 #include "MapDrawer.h"
27 #include "Tracking.h"
28 #include "System.h"
29 
30 #include <mutex>
31 
32 namespace ORB_SLAM2
33 {
34 
35 class Tracking;
36 class FrameDrawer;
37 class MapDrawer;
38 class System;
39 
40 class Viewer
41 {
42 public:
43  Viewer(System* pSystem, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Tracking *pTracking, const string &strSettingPath);
44 
45  // Main thread function. Draw points, keyframes, the current camera pose and the last processed
46  // frame. Drawing is refreshed according to the camera fps. We use Pangolin.
47  void Run();
48 
49  void RequestFinish();
50 
51  void RequestStop();
52 
53  bool isFinished();
54 
55  bool isStopped();
56 
57  void Release();
58 
59 private:
60 
61  bool Stop();
62 
63  System* mpSystem;
64  FrameDrawer* mpFrameDrawer;
65  MapDrawer* mpMapDrawer;
66  Tracking* mpTracker;
67 
68  // 1/fps in ms
69  double mT;
70  float mImageWidth, mImageHeight;
71 
72  float mViewpointX, mViewpointY, mViewpointZ, mViewpointF;
73 
74  bool CheckFinish();
75  void SetFinish();
76  bool mbFinishRequested;
77  bool mbFinished;
78  std::mutex mMutexFinish;
79 
80  bool mbStopped;
81  bool mbStopRequested;
82  std::mutex mMutexStop;
83 
84 };
85 
86 }
87 
88 
89 #endif // VIEWER_H
90 
91 
Definition: Tracking.h:53
Definition: Viewer.h:40
Definition: Converter.cpp:24
Definition: MapDrawer.h:34
Definition: FrameDrawer.h:40
Definition: System.h:49