-
Notifications
You must be signed in to change notification settings - Fork 1
/
Viewer.cc
232 lines (192 loc) · 6.33 KB
/
Viewer.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <https://github.com/raulmur/ORB_SLAM2>
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see <http://www.gnu.org/licenses/>.
*/
#include "Viewer.h"
#include <pangolin/pangolin.h>
#include <mutex>
namespace ORB_SLAM2
{
Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Tracking *pTracking, const string &strSettingPath):
mpSystem(pSystem), mpFrameDrawer(pFrameDrawer),mpMapDrawer(pMapDrawer), mpTracker(pTracking),
mbFinishRequested(false), mbFinished(true), mbStopped(true), mbStopRequested(false)
{
cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
float fps = fSettings["Camera.fps"];
if(fps<1)
fps=30;
mT = 1e3/fps;
mImageWidth = fSettings["Camera.width"];
mImageHeight = fSettings["Camera.height"];
if(mImageWidth<1 || mImageHeight<1)
{
mImageWidth = 640;
mImageHeight = 480;
}
mViewpointX = fSettings["Viewer.ViewpointX"];
mViewpointY = fSettings["Viewer.ViewpointY"];
mViewpointZ = fSettings["Viewer.ViewpointZ"];
mViewpointF = fSettings["Viewer.ViewpointF"];
}
void Viewer::Run()
{
mbFinished = false;
mbStopped = false;
pangolin::CreateWindowAndBind("EnvDyna-SLAM: Map Viewer",1024,768);
// 3D Mouse handler requires depth testing to be enabled
glEnable(GL_DEPTH_TEST);
// Issue specific OpenGl we might need
glEnable (GL_BLEND);
glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(175));
pangolin::Var<bool> menuFollowCamera("menu.Follow Camera",true,true);
pangolin::Var<bool> menuShowPoints("menu.Show Points",true,true);
pangolin::Var<bool> menuShowKeyFrames("menu.Show KeyFrames",true,true);
pangolin::Var<bool> menuShowGraph("menu.Show Graph",true,true);
pangolin::Var<bool> menuLocalizationMode("menu.Localization Mode",false,true);
pangolin::Var<bool> menuReset("menu.Reset",false,false);
// Define Camera Render Object (for view / scene browsing)
pangolin::OpenGlRenderState s_cam(
pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000),
pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0)
);
// Add named OpenGL viewport to window and provide 3D Handler
pangolin::View& d_cam = pangolin::CreateDisplay()
.SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f/768.0f)
.SetHandler(new pangolin::Handler3D(s_cam));
pangolin::OpenGlMatrix Twc;
Twc.SetIdentity();
cv::namedWindow("EnvDyna-SLAM: Current Frame");
bool bFollow = true;
bool bLocalizationMode = false;
while(1)
{
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc);
if(menuFollowCamera && bFollow)
{
s_cam.Follow(Twc);
}
else if(menuFollowCamera && !bFollow)
{
s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0));
s_cam.Follow(Twc);
bFollow = true;
}
else if(!menuFollowCamera && bFollow)
{
bFollow = false;
}
if(menuLocalizationMode && !bLocalizationMode)
{
mpSystem->ActivateLocalizationMode();
bLocalizationMode = true;
}
else if(!menuLocalizationMode && bLocalizationMode)
{
mpSystem->DeactivateLocalizationMode();
bLocalizationMode = false;
}
d_cam.Activate(s_cam);
glClearColor(1.0f,1.0f,1.0f,1.0f);
mpMapDrawer->DrawCurrentCamera(Twc);
if(menuShowKeyFrames || menuShowGraph)
mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph);
if(menuShowPoints)
mpMapDrawer->DrawMapPoints();
pangolin::FinishFrame();
cv::Mat im = mpFrameDrawer->DrawFrame();
cv::imshow("EnvDyna-SLAM: Current Frame",im);
cv::waitKey(mT);
if(menuReset)
{
menuShowGraph = true;
menuShowKeyFrames = true;
menuShowPoints = true;
menuLocalizationMode = false;
if(bLocalizationMode)
mpSystem->DeactivateLocalizationMode();
bLocalizationMode = false;
bFollow = true;
menuFollowCamera = true;
mpSystem->Reset();
menuReset = false;
}
if(Stop())
{
while(isStopped())
{
usleep(3000);
}
}
if(CheckFinish())
break;
}
SetFinish();
}
void Viewer::RequestFinish()
{
unique_lock<mutex> lock(mMutexFinish);
mbFinishRequested = true;
}
bool Viewer::CheckFinish()
{
unique_lock<mutex> lock(mMutexFinish);
return mbFinishRequested;
}
void Viewer::SetFinish()
{
unique_lock<mutex> lock(mMutexFinish);
mbFinished = true;
}
bool Viewer::isFinished()
{
unique_lock<mutex> lock(mMutexFinish);
return mbFinished;
}
void Viewer::RequestStop()
{
unique_lock<mutex> lock(mMutexStop);
if(!mbStopped)
mbStopRequested = true;
}
bool Viewer::isStopped()
{
unique_lock<mutex> lock(mMutexStop);
return mbStopped;
}
bool Viewer::Stop()
{
unique_lock<mutex> lock(mMutexStop);
unique_lock<mutex> lock2(mMutexFinish);
if(mbFinishRequested)
return false;
else if(mbStopRequested)
{
mbStopped = true;
mbStopRequested = false;
return true;
}
return false;
}
void Viewer::Release()
{
unique_lock<mutex> lock(mMutexStop);
mbStopped = false;
}
}