forked from raulmur/ORB_SLAM
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Sim3Solver.cc
420 lines (311 loc) · 10.9 KB
/
Sim3Solver.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
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
/**
* This file is part of ORB-SLAM.
*
* Copyright (C) 2014 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <http://webdiis.unizar.es/~raulmur/orbslam/>
*
* ORB-SLAM 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-SLAM 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-SLAM. If not, see <http://www.gnu.org/licenses/>.
*/
#include "Sim3Solver.h"
#include <vector>
#include <cmath>
#include <opencv/cv.h>
#include <ros/ros.h>
#include "KeyFrame.h"
#include "ORBmatcher.h"
#include "Thirdparty/DBoW2/DUtils/Random.h"
namespace ORB_SLAM
{
Sim3Solver::Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const vector<MapPoint *> &vpMatched12):
mnIterations(0), mnBestInliers(0)
{
mpKF1 = pKF1;
mpKF2 = pKF2;
vector<MapPoint*> vpKeyFrameMP1 = pKF1->GetMapPointMatches();
mN1 = vpMatched12.size();
mvpMapPoints1.reserve(mN1);
mvpMapPoints2.reserve(mN1);
mvpMatches12 = vpMatched12;
mvnIndices1.reserve(mN1);
mvX3Dc1.reserve(mN1);
mvX3Dc2.reserve(mN1);
cv::Mat Rcw1 = pKF1->GetRotation();
cv::Mat tcw1 = pKF1->GetTranslation();
cv::Mat Rcw2 = pKF2->GetRotation();
cv::Mat tcw2 = pKF2->GetTranslation();
mvAllIndices.reserve(mN1);
size_t idx=0;
for(int i1=0; i1<mN1; i1++)
{
if(vpMatched12[i1])
{
MapPoint* pMP1 = vpKeyFrameMP1[i1];
MapPoint* pMP2 = vpMatched12[i1];
if(!pMP1)
continue;
if(pMP1->isBad() || pMP2->isBad())
continue;
int indexKF1 = pMP1->GetIndexInKeyFrame(pKF1);
int indexKF2 = pMP2->GetIndexInKeyFrame(pKF2);
if(indexKF1<0 || indexKF2<0)
continue;
const cv::KeyPoint &kp1 = pKF1->GetKeyPointUn(indexKF1);
const cv::KeyPoint &kp2 = pKF2->GetKeyPointUn(indexKF2);
const float sigmaSquare1 = pKF1->GetSigma2(kp1.octave);
const float sigmaSquare2 = pKF2->GetSigma2(kp2.octave);
mvnMaxError1.push_back(9.210*sigmaSquare1);
mvnMaxError2.push_back(9.210*sigmaSquare2);
mvpMapPoints1.push_back(pMP1);
mvpMapPoints2.push_back(pMP2);
mvnIndices1.push_back(i1);
cv::Mat X3D1w = pMP1->GetWorldPos();
mvX3Dc1.push_back(Rcw1*X3D1w+tcw1);
cv::Mat X3D2w = pMP2->GetWorldPos();
mvX3Dc2.push_back(Rcw2*X3D2w+tcw2);
mvAllIndices.push_back(idx);
idx++;
}
}
mK1 = pKF1->GetCalibrationMatrix();
mK2 = pKF2->GetCalibrationMatrix();
FromCameraToImage(mvX3Dc1,mvP1im1,mK1);
FromCameraToImage(mvX3Dc2,mvP2im2,mK2);
SetRansacParameters();
}
void Sim3Solver::SetRansacParameters(double probability, int minInliers, int maxIterations)
{
mRansacProb = probability;
mRansacMinInliers = minInliers;
mRansacMaxIts = maxIterations;
N = mvpMapPoints1.size(); // number of correspondences
mvbInliersi.resize(N);
// Adjust Parameters according to number of correspondences
float epsilon = (float)mRansacMinInliers/N;
// Set RANSAC iterations according to probability, epsilon, and max iterations
int nIterations;
if(mRansacMinInliers==N)
nIterations=1;
else
nIterations = ceil(log(1-mRansacProb)/log(1-pow(epsilon,3)));
mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts));
mnIterations = 0;
}
cv::Mat Sim3Solver::iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers)
{
bNoMore = false;
vbInliers = vector<bool>(mN1,false);
nInliers=0;
if(N<mRansacMinInliers)
{
bNoMore = true;
return cv::Mat();
}
vector<size_t> vAvailableIndices;
cv::Mat P3Dc1i(3,3,CV_32F);
cv::Mat P3Dc2i(3,3,CV_32F);
int nCurrentIterations = 0;
while(mnIterations<mRansacMaxIts && nCurrentIterations<nIterations)
{
nCurrentIterations++;
mnIterations++;
vAvailableIndices = mvAllIndices;
// Get min set of points
for(short i = 0; i < 3; ++i)
{
int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1);
int idx = vAvailableIndices[randi];
mvX3Dc1[idx].copyTo(P3Dc1i.col(i));
mvX3Dc2[idx].copyTo(P3Dc2i.col(i));
vAvailableIndices[idx] = vAvailableIndices.back();
vAvailableIndices.pop_back();
}
computeT(P3Dc1i,P3Dc2i);
CheckInliers();
if(mnInliersi>=mnBestInliers)
{
mvbBestInliers = mvbInliersi;
mnBestInliers = mnInliersi;
mBestT12 = mT12i.clone();
mBestRotation = mR12i.clone();
mBestTranslation = mt12i.clone();
mBestScale = ms12i;
if(mnInliersi>mRansacMinInliers)
{
nInliers = mnInliersi;
for(int i=0; i<N; i++)
if(mvbInliersi[i])
vbInliers[mvnIndices1[i]] = true;
return mBestT12;
}
}
}
if(mnIterations>=mRansacMaxIts)
bNoMore=true;
return cv::Mat();
}
cv::Mat Sim3Solver::find(vector<bool> &vbInliers12, int &nInliers)
{
bool bFlag;
return iterate(mRansacMaxIts,bFlag,vbInliers12,nInliers);
}
void Sim3Solver::centroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C)
{
cv::reduce(P,C,1,CV_REDUCE_SUM);
C = C/P.cols;
for(int i=0; i<P.cols; i++)
{
Pr.col(i)=P.col(i)-C;
}
}
void Sim3Solver::computeT(cv::Mat &P1, cv::Mat &P2)
{
// Custom implementation of:
// Horn 1987, Closed-form solution of absolute orientataion using unit quaternions
// Step 1: Centroid and relative coordinates
cv::Mat Pr1(P1.size(),P1.type()); // Relative coordinates to centroid (set 1)
cv::Mat Pr2(P2.size(),P2.type()); // Relative coordinates to centroid (set 2)
cv::Mat O1(3,1,Pr1.type()); // Centroid of P1
cv::Mat O2(3,1,Pr2.type()); // Centroid of P2
centroid(P1,Pr1,O1);
centroid(P2,Pr2,O2);
// Step 2: Compute M matrix
cv::Mat M = Pr2*Pr1.t();
// Step 3: Compute N matrix
double N11, N12, N13, N14, N22, N23, N24, N33, N34, N44;
cv::Mat N(4,4,P1.type());
N11 = M.at<float>(0,0)+M.at<float>(1,1)+M.at<float>(2,2);
N12 = M.at<float>(1,2)-M.at<float>(2,1);
N13 = M.at<float>(2,0)-M.at<float>(0,2);
N14 = M.at<float>(0,1)-M.at<float>(1,0);
N22 = M.at<float>(0,0)-M.at<float>(1,1)-M.at<float>(2,2);
N23 = M.at<float>(0,1)+M.at<float>(1,0);
N24 = M.at<float>(2,0)+M.at<float>(0,2);
N33 = -M.at<float>(0,0)+M.at<float>(1,1)-M.at<float>(2,2);
N34 = M.at<float>(1,2)+M.at<float>(2,1);
N44 = -M.at<float>(0,0)-M.at<float>(1,1)+M.at<float>(2,2);
N = (cv::Mat_<float>(4,4) << N11, N12, N13, N14,
N12, N22, N23, N24,
N13, N23, N33, N34,
N14, N24, N34, N44);
// Step 4: Eigenvector of the highest eigenvalue
cv::Mat eval, evec;
cv::eigen(N,eval,evec); //evec[0] is the quaternion of the desired rotation
cv::Mat vec(1,3,evec.type());
(evec.row(0).colRange(1,4)).copyTo(vec); //extract imaginary part of the quaternion (sin*axis)
// Rotation angle. sin is the norm of the imaginary part, cos is the real part
double ang=atan2(norm(vec),evec.at<float>(0,0));
vec = 2*ang*vec/norm(vec); //Angle-axis representation. quaternion angle is the half
mR12i.create(3,3,P1.type());
cv::Rodrigues(vec,mR12i); // computes the rotation matrix from angle-axis
// Step 5: Rotate set 2
cv::Mat P3 = mR12i*Pr2;
// Step 6: Scale
double nom = Pr1.dot(P3);
cv::Mat aux_P3(P3.size(),P3.type());
aux_P3=P3;
cv::pow(P3,2,aux_P3);
double den = 0;
for(int i=0; i<aux_P3.rows; i++)
{
for(int j=0; j<aux_P3.cols; j++)
{
den+=aux_P3.at<float>(i,j);
}
}
ms12i = nom/den;
// Step 7: Translation
mt12i.create(1,3,P1.type());
mt12i = O1 - ms12i*mR12i*O2;
// Step 8: Transformation
// Step 8.1 T12
mT12i = cv::Mat::eye(4,4,P1.type());
cv::Mat sR = ms12i*mR12i;
sR.copyTo(mT12i.rowRange(0,3).colRange(0,3));
mt12i.copyTo(mT12i.rowRange(0,3).col(3));
// Step 8.2 T21
mT21i = cv::Mat::eye(4,4,P1.type());
cv::Mat sRinv = (1.0/ms12i)*mR12i.t();
sRinv.copyTo(mT21i.rowRange(0,3).colRange(0,3));
cv::Mat tinv = -sRinv*mt12i;
tinv.copyTo(mT21i.rowRange(0,3).col(3));
}
void Sim3Solver::CheckInliers()
{
vector<cv::Mat> vP1im2, vP2im1;
Project(mvX3Dc2,vP2im1,mT12i,mK1);
Project(mvX3Dc1,vP1im2,mT21i,mK2);
mnInliersi=0;
for(size_t i=0; i<mvP1im1.size(); i++)
{
cv::Mat dist1 = mvP1im1[i]-vP2im1[i];
cv::Mat dist2 = vP1im2[i]-mvP2im2[i];
float err1 = dist1.dot(dist1);
float err2 = dist2.dot(dist2);
if(err1<mvnMaxError1[i] && err2<mvnMaxError2[i])
{
mvbInliersi[i]=true;
mnInliersi++;
}
else
mvbInliersi[i]=false;
}
}
cv::Mat Sim3Solver::GetEstimatedRotation()
{
return mBestRotation.clone();
}
cv::Mat Sim3Solver::GetEstimatedTranslation()
{
return mBestTranslation.clone();
}
float Sim3Solver::GetEstimatedScale()
{
return mBestScale;
}
void Sim3Solver::Project(const vector<cv::Mat> &vP3Dw, vector<cv::Mat> &vP2D, cv::Mat Tcw, cv::Mat K)
{
cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3);
cv::Mat tcw = Tcw.rowRange(0,3).col(3);
float fx = K.at<float>(0,0);
float fy = K.at<float>(1,1);
float cx = K.at<float>(0,2);
float cy = K.at<float>(1,2);
vP2D.clear();
vP2D.reserve(vP3Dw.size());
for(size_t i=0, iend=vP3Dw.size(); i<iend; i++)
{
cv::Mat P3Dc = Rcw*vP3Dw[i]+tcw;
float invz = 1/(P3Dc.at<float>(2));
float x = P3Dc.at<float>(0)*invz;
float y = P3Dc.at<float>(1)*invz;
vP2D.push_back((cv::Mat_<float>(2,1) << fx*x+cx, fy*y+cy));
}
}
void Sim3Solver::FromCameraToImage(const vector<cv::Mat> &vP3Dc, vector<cv::Mat> &vP2D, cv::Mat K)
{
float fx = K.at<float>(0,0);
float fy = K.at<float>(1,1);
float cx = K.at<float>(0,2);
float cy = K.at<float>(1,2);
vP2D.clear();
vP2D.reserve(vP3Dc.size());
for(size_t i=0, iend=vP3Dc.size(); i<iend; i++)
{
float invz = 1/(vP3Dc[i].at<float>(2));
float x = vP3Dc[i].at<float>(0)*invz;
float y = vP3Dc[i].at<float>(1)*invz;
vP2D.push_back((cv::Mat_<float>(2,1) << fx*x+cx, fy*y+cy));
}
}
} //namespace ORB_SLAM