forked from raulmur/ORB_SLAM2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
MapDrawer.cc
264 lines (216 loc) · 7.12 KB
/
MapDrawer.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
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
/**
* 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 "MapDrawer.h"
#include "MapPoint.h"
#include "KeyFrame.h"
#include <pangolin/pangolin.h>
#include <mutex>
namespace ORB_SLAM2
{
MapDrawer::MapDrawer(Map* pMap, const string &strSettingPath):mpMap(pMap)
{
cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
mKeyFrameSize = fSettings["Viewer.KeyFrameSize"];
mKeyFrameLineWidth = fSettings["Viewer.KeyFrameLineWidth"];
mGraphLineWidth = fSettings["Viewer.GraphLineWidth"];
mPointSize = fSettings["Viewer.PointSize"];
mCameraSize = fSettings["Viewer.CameraSize"];
mCameraLineWidth = fSettings["Viewer.CameraLineWidth"];
}
void MapDrawer::DrawMapPoints()
{
const vector<MapPoint*> &vpMPs = mpMap->GetAllMapPoints();
const vector<MapPoint*> &vpRefMPs = mpMap->GetReferenceMapPoints();
set<MapPoint*> spRefMPs(vpRefMPs.begin(), vpRefMPs.end());
if(vpMPs.empty())
return;
glPointSize(mPointSize);
glBegin(GL_POINTS);
glColor3f(0.0,0.0,0.0);
for(size_t i=0, iend=vpMPs.size(); i<iend;i++)
{
if(vpMPs[i]->isBad() || spRefMPs.count(vpMPs[i]))
continue;
cv::Mat pos = vpMPs[i]->GetWorldPos();
glVertex3f(pos.at<float>(0),pos.at<float>(1),pos.at<float>(2));
}
glEnd();
glPointSize(mPointSize);
glBegin(GL_POINTS);
glColor3f(1.0,0.0,0.0);
for(set<MapPoint*>::iterator sit=spRefMPs.begin(), send=spRefMPs.end(); sit!=send; sit++)
{
if((*sit)->isBad())
continue;
cv::Mat pos = (*sit)->GetWorldPos();
glVertex3f(pos.at<float>(0),pos.at<float>(1),pos.at<float>(2));
}
glEnd();
}
void MapDrawer::DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph)
{
const float &w = mKeyFrameSize;
const float h = w*0.75;
const float z = w*0.6;
const vector<KeyFrame*> vpKFs = mpMap->GetAllKeyFrames();
if(bDrawKF)
{
for(size_t i=0; i<vpKFs.size(); i++)
{
KeyFrame* pKF = vpKFs[i];
cv::Mat Twc = pKF->GetPoseInverse().t();
glPushMatrix();
glMultMatrixf(Twc.ptr<GLfloat>(0));
glLineWidth(mKeyFrameLineWidth);
glColor3f(0.0f,0.0f,1.0f);
glBegin(GL_LINES);
glVertex3f(0,0,0);
glVertex3f(w,h,z);
glVertex3f(0,0,0);
glVertex3f(w,-h,z);
glVertex3f(0,0,0);
glVertex3f(-w,-h,z);
glVertex3f(0,0,0);
glVertex3f(-w,h,z);
glVertex3f(w,h,z);
glVertex3f(w,-h,z);
glVertex3f(-w,h,z);
glVertex3f(-w,-h,z);
glVertex3f(-w,h,z);
glVertex3f(w,h,z);
glVertex3f(-w,-h,z);
glVertex3f(w,-h,z);
glEnd();
glPopMatrix();
}
}
if(bDrawGraph)
{
glLineWidth(mGraphLineWidth);
glColor4f(0.0f,1.0f,0.0f,0.6f);
glBegin(GL_LINES);
for(size_t i=0; i<vpKFs.size(); i++)
{
// Covisibility Graph
const vector<KeyFrame*> vCovKFs = vpKFs[i]->GetCovisiblesByWeight(100);
cv::Mat Ow = vpKFs[i]->GetCameraCenter();
if(!vCovKFs.empty())
{
for(vector<KeyFrame*>::const_iterator vit=vCovKFs.begin(), vend=vCovKFs.end(); vit!=vend; vit++)
{
if((*vit)->mnId<vpKFs[i]->mnId)
continue;
cv::Mat Ow2 = (*vit)->GetCameraCenter();
glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
glVertex3f(Ow2.at<float>(0),Ow2.at<float>(1),Ow2.at<float>(2));
}
}
// Spanning tree
KeyFrame* pParent = vpKFs[i]->GetParent();
if(pParent)
{
cv::Mat Owp = pParent->GetCameraCenter();
glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
glVertex3f(Owp.at<float>(0),Owp.at<float>(1),Owp.at<float>(2));
}
// Loops
set<KeyFrame*> sLoopKFs = vpKFs[i]->GetLoopEdges();
for(set<KeyFrame*>::iterator sit=sLoopKFs.begin(), send=sLoopKFs.end(); sit!=send; sit++)
{
if((*sit)->mnId<vpKFs[i]->mnId)
continue;
cv::Mat Owl = (*sit)->GetCameraCenter();
glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
glVertex3f(Owl.at<float>(0),Owl.at<float>(1),Owl.at<float>(2));
}
}
glEnd();
}
}
void MapDrawer::DrawCurrentCamera(pangolin::OpenGlMatrix &Twc)
{
const float &w = mCameraSize;
const float h = w*0.75;
const float z = w*0.6;
glPushMatrix();
#ifdef HAVE_GLES
glMultMatrixf(Twc.m);
#else
glMultMatrixd(Twc.m);
#endif
glLineWidth(mCameraLineWidth);
glColor3f(0.0f,1.0f,0.0f);
glBegin(GL_LINES);
glVertex3f(0,0,0);
glVertex3f(w,h,z);
glVertex3f(0,0,0);
glVertex3f(w,-h,z);
glVertex3f(0,0,0);
glVertex3f(-w,-h,z);
glVertex3f(0,0,0);
glVertex3f(-w,h,z);
glVertex3f(w,h,z);
glVertex3f(w,-h,z);
glVertex3f(-w,h,z);
glVertex3f(-w,-h,z);
glVertex3f(-w,h,z);
glVertex3f(w,h,z);
glVertex3f(-w,-h,z);
glVertex3f(w,-h,z);
glEnd();
glPopMatrix();
}
void MapDrawer::SetCurrentCameraPose(const cv::Mat &Tcw)
{
unique_lock<mutex> lock(mMutexCamera);
mCameraPose = Tcw.clone();
}
void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M)
{
if(!mCameraPose.empty())
{
cv::Mat Rwc(3,3,CV_32F);
cv::Mat twc(3,1,CV_32F);
{
unique_lock<mutex> lock(mMutexCamera);
Rwc = mCameraPose.rowRange(0,3).colRange(0,3).t();
twc = -Rwc*mCameraPose.rowRange(0,3).col(3);
}
M.m[0] = Rwc.at<float>(0,0);
M.m[1] = Rwc.at<float>(1,0);
M.m[2] = Rwc.at<float>(2,0);
M.m[3] = 0.0;
M.m[4] = Rwc.at<float>(0,1);
M.m[5] = Rwc.at<float>(1,1);
M.m[6] = Rwc.at<float>(2,1);
M.m[7] = 0.0;
M.m[8] = Rwc.at<float>(0,2);
M.m[9] = Rwc.at<float>(1,2);
M.m[10] = Rwc.at<float>(2,2);
M.m[11] = 0.0;
M.m[12] = twc.at<float>(0);
M.m[13] = twc.at<float>(1);
M.m[14] = twc.at<float>(2);
M.m[15] = 1.0;
}
else
M.SetIdentity();
}
} //namespace ORB_SLAM