Initializer.cc
Go to the documentation of this file.
1 
21 #include "Initializer.h"
22 
24 
25 #include "Optimizer.h"
26 #include "ORBmatcher.h"
27 
28 #include<thread>
29 
30 namespace ORB_SLAM2
31 {
32 
33 Initializer::Initializer(const Frame &ReferenceFrame, float sigma, int iterations)
34 {
35  mK = ReferenceFrame.mK.clone();
36 
37  mvKeys1 = ReferenceFrame.mvKeysUn;
38 
39  mSigma = sigma;
40  mSigma2 = sigma*sigma;
41  mMaxIterations = iterations;
42 }
43 
44 bool Initializer::Initialize(const Frame &CurrentFrame, const vector<int> &vMatches12, cv::Mat &R21, cv::Mat &t21,
45  vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated)
46 {
47  // Fill structures with current keypoints and matches with reference frame
48  // Reference Frame: 1, Current Frame: 2
49  mvKeys2 = CurrentFrame.mvKeysUn;
50 
51  mvMatches12.clear();
52  mvMatches12.reserve(mvKeys2.size());
53  mvbMatched1.resize(mvKeys1.size());
54  for(size_t i=0, iend=vMatches12.size();i<iend; i++)
55  {
56  if(vMatches12[i]>=0)
57  {
58  mvMatches12.push_back(make_pair(i,vMatches12[i]));
59  mvbMatched1[i]=true;
60  }
61  else
62  mvbMatched1[i]=false;
63  }
64 
65  const int N = mvMatches12.size();
66 
67  // Indices for minimum set selection
68  vector<size_t> vAllIndices;
69  vAllIndices.reserve(N);
70  vector<size_t> vAvailableIndices;
71 
72  for(int i=0; i<N; i++)
73  {
74  vAllIndices.push_back(i);
75  }
76 
77  // Generate sets of 8 points for each RANSAC iteration
78  mvSets = vector< vector<size_t> >(mMaxIterations,vector<size_t>(8,0));
79 
81 
82  for(int it=0; it<mMaxIterations; it++)
83  {
84  vAvailableIndices = vAllIndices;
85 
86  // Select a minimum set
87  for(size_t j=0; j<8; j++)
88  {
89  int randi = DUtils::Random::RandomInt(0,vAvailableIndices.size()-1);
90  int idx = vAvailableIndices[randi];
91 
92  mvSets[it][j] = idx;
93 
94  vAvailableIndices[randi] = vAvailableIndices.back();
95  vAvailableIndices.pop_back();
96  }
97  }
98 
99  // Launch threads to compute in parallel a fundamental matrix and a homography
100  vector<bool> vbMatchesInliersH, vbMatchesInliersF;
101  float SH, SF;
102  cv::Mat H, F;
103 
104  thread threadH(&Initializer::FindHomography,this,ref(vbMatchesInliersH), ref(SH), ref(H));
105  thread threadF(&Initializer::FindFundamental,this,ref(vbMatchesInliersF), ref(SF), ref(F));
106 
107  // Wait until both threads have finished
108  threadH.join();
109  threadF.join();
110 
111  // Compute ratio of scores
112  float RH = SH/(SH+SF);
113 
114  // Try to reconstruct from homography or fundamental depending on the ratio (0.40-0.45)
115  if(RH>0.40)
116  return ReconstructH(vbMatchesInliersH,H,mK,R21,t21,vP3D,vbTriangulated,1.0,50);
117  else //if(pF_HF>0.6)
118  return ReconstructF(vbMatchesInliersF,F,mK,R21,t21,vP3D,vbTriangulated,1.0,50);
119 
120  return false;
121 }
122 
123 
124 void Initializer::FindHomography(vector<bool> &vbMatchesInliers, float &score, cv::Mat &H21)
125 {
126  // Number of putative matches
127  const int N = mvMatches12.size();
128 
129  // Normalize coordinates
130  vector<cv::Point2f> vPn1, vPn2;
131  cv::Mat T1, T2;
132  Normalize(mvKeys1,vPn1, T1);
133  Normalize(mvKeys2,vPn2, T2);
134  cv::Mat T2inv = T2.inv();
135 
136  // Best Results variables
137  score = 0.0;
138  vbMatchesInliers = vector<bool>(N,false);
139 
140  // Iteration variables
141  vector<cv::Point2f> vPn1i(8);
142  vector<cv::Point2f> vPn2i(8);
143  cv::Mat H21i, H12i;
144  vector<bool> vbCurrentInliers(N,false);
145  float currentScore;
146 
147  // Perform all RANSAC iterations and save the solution with highest score
148  for(int it=0; it<mMaxIterations; it++)
149  {
150  // Select a minimum set
151  for(size_t j=0; j<8; j++)
152  {
153  int idx = mvSets[it][j];
154 
155  vPn1i[j] = vPn1[mvMatches12[idx].first];
156  vPn2i[j] = vPn2[mvMatches12[idx].second];
157  }
158 
159  cv::Mat Hn = ComputeH21(vPn1i,vPn2i);
160  H21i = T2inv*Hn*T1;
161  H12i = H21i.inv();
162 
163  currentScore = CheckHomography(H21i, H12i, vbCurrentInliers, mSigma);
164 
165  if(currentScore>score)
166  {
167  H21 = H21i.clone();
168  vbMatchesInliers = vbCurrentInliers;
169  score = currentScore;
170  }
171  }
172 }
173 
174 
175 void Initializer::FindFundamental(vector<bool> &vbMatchesInliers, float &score, cv::Mat &F21)
176 {
177  // Number of putative matches
178  const int N = vbMatchesInliers.size();
179 
180  // Normalize coordinates
181  vector<cv::Point2f> vPn1, vPn2;
182  cv::Mat T1, T2;
183  Normalize(mvKeys1,vPn1, T1);
184  Normalize(mvKeys2,vPn2, T2);
185  cv::Mat T2t = T2.t();
186 
187  // Best Results variables
188  score = 0.0;
189  vbMatchesInliers = vector<bool>(N,false);
190 
191  // Iteration variables
192  vector<cv::Point2f> vPn1i(8);
193  vector<cv::Point2f> vPn2i(8);
194  cv::Mat F21i;
195  vector<bool> vbCurrentInliers(N,false);
196  float currentScore;
197 
198  // Perform all RANSAC iterations and save the solution with highest score
199  for(int it=0; it<mMaxIterations; it++)
200  {
201  // Select a minimum set
202  for(int j=0; j<8; j++)
203  {
204  int idx = mvSets[it][j];
205 
206  vPn1i[j] = vPn1[mvMatches12[idx].first];
207  vPn2i[j] = vPn2[mvMatches12[idx].second];
208  }
209 
210  cv::Mat Fn = ComputeF21(vPn1i,vPn2i);
211 
212  F21i = T2t*Fn*T1;
213 
214  currentScore = CheckFundamental(F21i, vbCurrentInliers, mSigma);
215 
216  if(currentScore>score)
217  {
218  F21 = F21i.clone();
219  vbMatchesInliers = vbCurrentInliers;
220  score = currentScore;
221  }
222  }
223 }
224 
225 
226 cv::Mat Initializer::ComputeH21(const vector<cv::Point2f> &vP1, const vector<cv::Point2f> &vP2)
227 {
228  const int N = vP1.size();
229 
230  cv::Mat A(2*N,9,CV_32F);
231 
232  for(int i=0; i<N; i++)
233  {
234  const float u1 = vP1[i].x;
235  const float v1 = vP1[i].y;
236  const float u2 = vP2[i].x;
237  const float v2 = vP2[i].y;
238 
239  A.at<float>(2*i,0) = 0.0;
240  A.at<float>(2*i,1) = 0.0;
241  A.at<float>(2*i,2) = 0.0;
242  A.at<float>(2*i,3) = -u1;
243  A.at<float>(2*i,4) = -v1;
244  A.at<float>(2*i,5) = -1;
245  A.at<float>(2*i,6) = v2*u1;
246  A.at<float>(2*i,7) = v2*v1;
247  A.at<float>(2*i,8) = v2;
248 
249  A.at<float>(2*i+1,0) = u1;
250  A.at<float>(2*i+1,1) = v1;
251  A.at<float>(2*i+1,2) = 1;
252  A.at<float>(2*i+1,3) = 0.0;
253  A.at<float>(2*i+1,4) = 0.0;
254  A.at<float>(2*i+1,5) = 0.0;
255  A.at<float>(2*i+1,6) = -u2*u1;
256  A.at<float>(2*i+1,7) = -u2*v1;
257  A.at<float>(2*i+1,8) = -u2;
258 
259  }
260 
261  cv::Mat u,w,vt;
262 
263  cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
264 
265  return vt.row(8).reshape(0, 3);
266 }
267 
268 cv::Mat Initializer::ComputeF21(const vector<cv::Point2f> &vP1,const vector<cv::Point2f> &vP2)
269 {
270  const int N = vP1.size();
271 
272  cv::Mat A(N,9,CV_32F);
273 
274  for(int i=0; i<N; i++)
275  {
276  const float u1 = vP1[i].x;
277  const float v1 = vP1[i].y;
278  const float u2 = vP2[i].x;
279  const float v2 = vP2[i].y;
280 
281  A.at<float>(i,0) = u2*u1;
282  A.at<float>(i,1) = u2*v1;
283  A.at<float>(i,2) = u2;
284  A.at<float>(i,3) = v2*u1;
285  A.at<float>(i,4) = v2*v1;
286  A.at<float>(i,5) = v2;
287  A.at<float>(i,6) = u1;
288  A.at<float>(i,7) = v1;
289  A.at<float>(i,8) = 1;
290  }
291 
292  cv::Mat u,w,vt;
293 
294  cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
295 
296  cv::Mat Fpre = vt.row(8).reshape(0, 3);
297 
298  cv::SVDecomp(Fpre,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
299 
300  w.at<float>(2)=0;
301 
302  return u*cv::Mat::diag(w)*vt;
303 }
304 
305 float Initializer::CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector<bool> &vbMatchesInliers, float sigma)
306 {
307  const int N = mvMatches12.size();
308 
309  const float h11 = H21.at<float>(0,0);
310  const float h12 = H21.at<float>(0,1);
311  const float h13 = H21.at<float>(0,2);
312  const float h21 = H21.at<float>(1,0);
313  const float h22 = H21.at<float>(1,1);
314  const float h23 = H21.at<float>(1,2);
315  const float h31 = H21.at<float>(2,0);
316  const float h32 = H21.at<float>(2,1);
317  const float h33 = H21.at<float>(2,2);
318 
319  const float h11inv = H12.at<float>(0,0);
320  const float h12inv = H12.at<float>(0,1);
321  const float h13inv = H12.at<float>(0,2);
322  const float h21inv = H12.at<float>(1,0);
323  const float h22inv = H12.at<float>(1,1);
324  const float h23inv = H12.at<float>(1,2);
325  const float h31inv = H12.at<float>(2,0);
326  const float h32inv = H12.at<float>(2,1);
327  const float h33inv = H12.at<float>(2,2);
328 
329  vbMatchesInliers.resize(N);
330 
331  float score = 0;
332 
333  const float th = 5.991;
334 
335  const float invSigmaSquare = 1.0/(sigma*sigma);
336 
337  for(int i=0; i<N; i++)
338  {
339  bool bIn = true;
340 
341  const cv::KeyPoint &kp1 = mvKeys1[mvMatches12[i].first];
342  const cv::KeyPoint &kp2 = mvKeys2[mvMatches12[i].second];
343 
344  const float u1 = kp1.pt.x;
345  const float v1 = kp1.pt.y;
346  const float u2 = kp2.pt.x;
347  const float v2 = kp2.pt.y;
348 
349  // Reprojection error in first image
350  // x2in1 = H12*x2
351 
352  const float w2in1inv = 1.0/(h31inv*u2+h32inv*v2+h33inv);
353  const float u2in1 = (h11inv*u2+h12inv*v2+h13inv)*w2in1inv;
354  const float v2in1 = (h21inv*u2+h22inv*v2+h23inv)*w2in1inv;
355 
356  const float squareDist1 = (u1-u2in1)*(u1-u2in1)+(v1-v2in1)*(v1-v2in1);
357 
358  const float chiSquare1 = squareDist1*invSigmaSquare;
359 
360  if(chiSquare1>th)
361  bIn = false;
362  else
363  score += th - chiSquare1;
364 
365  // Reprojection error in second image
366  // x1in2 = H21*x1
367 
368  const float w1in2inv = 1.0/(h31*u1+h32*v1+h33);
369  const float u1in2 = (h11*u1+h12*v1+h13)*w1in2inv;
370  const float v1in2 = (h21*u1+h22*v1+h23)*w1in2inv;
371 
372  const float squareDist2 = (u2-u1in2)*(u2-u1in2)+(v2-v1in2)*(v2-v1in2);
373 
374  const float chiSquare2 = squareDist2*invSigmaSquare;
375 
376  if(chiSquare2>th)
377  bIn = false;
378  else
379  score += th - chiSquare2;
380 
381  if(bIn)
382  vbMatchesInliers[i]=true;
383  else
384  vbMatchesInliers[i]=false;
385  }
386 
387  return score;
388 }
389 
390 float Initializer::CheckFundamental(const cv::Mat &F21, vector<bool> &vbMatchesInliers, float sigma)
391 {
392  const int N = mvMatches12.size();
393 
394  const float f11 = F21.at<float>(0,0);
395  const float f12 = F21.at<float>(0,1);
396  const float f13 = F21.at<float>(0,2);
397  const float f21 = F21.at<float>(1,0);
398  const float f22 = F21.at<float>(1,1);
399  const float f23 = F21.at<float>(1,2);
400  const float f31 = F21.at<float>(2,0);
401  const float f32 = F21.at<float>(2,1);
402  const float f33 = F21.at<float>(2,2);
403 
404  vbMatchesInliers.resize(N);
405 
406  float score = 0;
407 
408  const float th = 3.841;
409  const float thScore = 5.991;
410 
411  const float invSigmaSquare = 1.0/(sigma*sigma);
412 
413  for(int i=0; i<N; i++)
414  {
415  bool bIn = true;
416 
417  const cv::KeyPoint &kp1 = mvKeys1[mvMatches12[i].first];
418  const cv::KeyPoint &kp2 = mvKeys2[mvMatches12[i].second];
419 
420  const float u1 = kp1.pt.x;
421  const float v1 = kp1.pt.y;
422  const float u2 = kp2.pt.x;
423  const float v2 = kp2.pt.y;
424 
425  // Reprojection error in second image
426  // l2=F21x1=(a2,b2,c2)
427 
428  const float a2 = f11*u1+f12*v1+f13;
429  const float b2 = f21*u1+f22*v1+f23;
430  const float c2 = f31*u1+f32*v1+f33;
431 
432  const float num2 = a2*u2+b2*v2+c2;
433 
434  const float squareDist1 = num2*num2/(a2*a2+b2*b2);
435 
436  const float chiSquare1 = squareDist1*invSigmaSquare;
437 
438  if(chiSquare1>th)
439  bIn = false;
440  else
441  score += thScore - chiSquare1;
442 
443  // Reprojection error in second image
444  // l1 =x2tF21=(a1,b1,c1)
445 
446  const float a1 = f11*u2+f21*v2+f31;
447  const float b1 = f12*u2+f22*v2+f32;
448  const float c1 = f13*u2+f23*v2+f33;
449 
450  const float num1 = a1*u1+b1*v1+c1;
451 
452  const float squareDist2 = num1*num1/(a1*a1+b1*b1);
453 
454  const float chiSquare2 = squareDist2*invSigmaSquare;
455 
456  if(chiSquare2>th)
457  bIn = false;
458  else
459  score += thScore - chiSquare2;
460 
461  if(bIn)
462  vbMatchesInliers[i]=true;
463  else
464  vbMatchesInliers[i]=false;
465  }
466 
467  return score;
468 }
469 
470 bool Initializer::ReconstructF(vector<bool> &vbMatchesInliers, cv::Mat &F21, cv::Mat &K,
471  cv::Mat &R21, cv::Mat &t21, vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated, float minParallax, int minTriangulated)
472 {
473  int N=0;
474  for(size_t i=0, iend = vbMatchesInliers.size() ; i<iend; i++)
475  if(vbMatchesInliers[i])
476  N++;
477 
478  // Compute Essential Matrix from Fundamental Matrix
479  cv::Mat E21 = K.t()*F21*K;
480 
481  cv::Mat R1, R2, t;
482 
483  // Recover the 4 motion hypotheses
484  DecomposeE(E21,R1,R2,t);
485 
486  cv::Mat t1=t;
487  cv::Mat t2=-t;
488 
489  // Reconstruct with the 4 hyphoteses and check
490  vector<cv::Point3f> vP3D1, vP3D2, vP3D3, vP3D4;
491  vector<bool> vbTriangulated1,vbTriangulated2,vbTriangulated3, vbTriangulated4;
492  float parallax1,parallax2, parallax3, parallax4;
493 
494  int nGood1 = CheckRT(R1,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D1, 4.0*mSigma2, vbTriangulated1, parallax1);
495  int nGood2 = CheckRT(R2,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D2, 4.0*mSigma2, vbTriangulated2, parallax2);
496  int nGood3 = CheckRT(R1,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D3, 4.0*mSigma2, vbTriangulated3, parallax3);
497  int nGood4 = CheckRT(R2,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D4, 4.0*mSigma2, vbTriangulated4, parallax4);
498 
499  int maxGood = max(nGood1,max(nGood2,max(nGood3,nGood4)));
500 
501  R21 = cv::Mat();
502  t21 = cv::Mat();
503 
504  int nMinGood = max(static_cast<int>(0.9*N),minTriangulated);
505 
506  int nsimilar = 0;
507  if(nGood1>0.7*maxGood)
508  nsimilar++;
509  if(nGood2>0.7*maxGood)
510  nsimilar++;
511  if(nGood3>0.7*maxGood)
512  nsimilar++;
513  if(nGood4>0.7*maxGood)
514  nsimilar++;
515 
516  // If there is not a clear winner or not enough triangulated points reject initialization
517  if(maxGood<nMinGood || nsimilar>1)
518  {
519  return false;
520  }
521 
522  // If best reconstruction has enough parallax initialize
523  if(maxGood==nGood1)
524  {
525  if(parallax1>minParallax)
526  {
527  vP3D = vP3D1;
528  vbTriangulated = vbTriangulated1;
529 
530  R1.copyTo(R21);
531  t1.copyTo(t21);
532  return true;
533  }
534  }else if(maxGood==nGood2)
535  {
536  if(parallax2>minParallax)
537  {
538  vP3D = vP3D2;
539  vbTriangulated = vbTriangulated2;
540 
541  R2.copyTo(R21);
542  t1.copyTo(t21);
543  return true;
544  }
545  }else if(maxGood==nGood3)
546  {
547  if(parallax3>minParallax)
548  {
549  vP3D = vP3D3;
550  vbTriangulated = vbTriangulated3;
551 
552  R1.copyTo(R21);
553  t2.copyTo(t21);
554  return true;
555  }
556  }else if(maxGood==nGood4)
557  {
558  if(parallax4>minParallax)
559  {
560  vP3D = vP3D4;
561  vbTriangulated = vbTriangulated4;
562 
563  R2.copyTo(R21);
564  t2.copyTo(t21);
565  return true;
566  }
567  }
568 
569  return false;
570 }
571 
572 bool Initializer::ReconstructH(vector<bool> &vbMatchesInliers, cv::Mat &H21, cv::Mat &K,
573  cv::Mat &R21, cv::Mat &t21, vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated, float minParallax, int minTriangulated)
574 {
575  int N=0;
576  for(size_t i=0, iend = vbMatchesInliers.size() ; i<iend; i++)
577  if(vbMatchesInliers[i])
578  N++;
579 
580  // We recover 8 motion hypotheses using the method of Faugeras et al.
581  // Motion and structure from motion in a piecewise planar environment.
582  // International Journal of Pattern Recognition and Artificial Intelligence, 1988
583 
584  cv::Mat invK = K.inv();
585  cv::Mat A = invK*H21*K;
586 
587  cv::Mat U,w,Vt,V;
588  cv::SVD::compute(A,w,U,Vt,cv::SVD::FULL_UV);
589  V=Vt.t();
590 
591  float s = cv::determinant(U)*cv::determinant(Vt);
592 
593  float d1 = w.at<float>(0);
594  float d2 = w.at<float>(1);
595  float d3 = w.at<float>(2);
596 
597  if(d1/d2<1.00001 || d2/d3<1.00001)
598  {
599  return false;
600  }
601 
602  vector<cv::Mat> vR, vt, vn;
603  vR.reserve(8);
604  vt.reserve(8);
605  vn.reserve(8);
606 
607  //n'=[x1 0 x3] 4 posibilities e1=e3=1, e1=1 e3=-1, e1=-1 e3=1, e1=e3=-1
608  float aux1 = sqrt((d1*d1-d2*d2)/(d1*d1-d3*d3));
609  float aux3 = sqrt((d2*d2-d3*d3)/(d1*d1-d3*d3));
610  float x1[] = {aux1,aux1,-aux1,-aux1};
611  float x3[] = {aux3,-aux3,aux3,-aux3};
612 
613  //case d'=d2
614  float aux_stheta = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1+d3)*d2);
615 
616  float ctheta = (d2*d2+d1*d3)/((d1+d3)*d2);
617  float stheta[] = {aux_stheta, -aux_stheta, -aux_stheta, aux_stheta};
618 
619  for(int i=0; i<4; i++)
620  {
621  cv::Mat Rp=cv::Mat::eye(3,3,CV_32F);
622  Rp.at<float>(0,0)=ctheta;
623  Rp.at<float>(0,2)=-stheta[i];
624  Rp.at<float>(2,0)=stheta[i];
625  Rp.at<float>(2,2)=ctheta;
626 
627  cv::Mat R = s*U*Rp*Vt;
628  vR.push_back(R);
629 
630  cv::Mat tp(3,1,CV_32F);
631  tp.at<float>(0)=x1[i];
632  tp.at<float>(1)=0;
633  tp.at<float>(2)=-x3[i];
634  tp*=d1-d3;
635 
636  cv::Mat t = U*tp;
637  vt.push_back(t/cv::norm(t));
638 
639  cv::Mat np(3,1,CV_32F);
640  np.at<float>(0)=x1[i];
641  np.at<float>(1)=0;
642  np.at<float>(2)=x3[i];
643 
644  cv::Mat n = V*np;
645  if(n.at<float>(2)<0)
646  n=-n;
647  vn.push_back(n);
648  }
649 
650  //case d'=-d2
651  float aux_sphi = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1-d3)*d2);
652 
653  float cphi = (d1*d3-d2*d2)/((d1-d3)*d2);
654  float sphi[] = {aux_sphi, -aux_sphi, -aux_sphi, aux_sphi};
655 
656  for(int i=0; i<4; i++)
657  {
658  cv::Mat Rp=cv::Mat::eye(3,3,CV_32F);
659  Rp.at<float>(0,0)=cphi;
660  Rp.at<float>(0,2)=sphi[i];
661  Rp.at<float>(1,1)=-1;
662  Rp.at<float>(2,0)=sphi[i];
663  Rp.at<float>(2,2)=-cphi;
664 
665  cv::Mat R = s*U*Rp*Vt;
666  vR.push_back(R);
667 
668  cv::Mat tp(3,1,CV_32F);
669  tp.at<float>(0)=x1[i];
670  tp.at<float>(1)=0;
671  tp.at<float>(2)=x3[i];
672  tp*=d1+d3;
673 
674  cv::Mat t = U*tp;
675  vt.push_back(t/cv::norm(t));
676 
677  cv::Mat np(3,1,CV_32F);
678  np.at<float>(0)=x1[i];
679  np.at<float>(1)=0;
680  np.at<float>(2)=x3[i];
681 
682  cv::Mat n = V*np;
683  if(n.at<float>(2)<0)
684  n=-n;
685  vn.push_back(n);
686  }
687 
688 
689  int bestGood = 0;
690  int secondBestGood = 0;
691  int bestSolutionIdx = -1;
692  float bestParallax = -1;
693  vector<cv::Point3f> bestP3D;
694  vector<bool> bestTriangulated;
695 
696  // Instead of applying the visibility constraints proposed in the Faugeras' paper (which could fail for points seen with low parallax)
697  // We reconstruct all hypotheses and check in terms of triangulated points and parallax
698  for(size_t i=0; i<8; i++)
699  {
700  float parallaxi;
701  vector<cv::Point3f> vP3Di;
702  vector<bool> vbTriangulatedi;
703  int nGood = CheckRT(vR[i],vt[i],mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K,vP3Di, 4.0*mSigma2, vbTriangulatedi, parallaxi);
704 
705  if(nGood>bestGood)
706  {
707  secondBestGood = bestGood;
708  bestGood = nGood;
709  bestSolutionIdx = i;
710  bestParallax = parallaxi;
711  bestP3D = vP3Di;
712  bestTriangulated = vbTriangulatedi;
713  }
714  else if(nGood>secondBestGood)
715  {
716  secondBestGood = nGood;
717  }
718  }
719 
720 
721  if(secondBestGood<0.75*bestGood && bestParallax>=minParallax && bestGood>minTriangulated && bestGood>0.9*N)
722  {
723  vR[bestSolutionIdx].copyTo(R21);
724  vt[bestSolutionIdx].copyTo(t21);
725  vP3D = bestP3D;
726  vbTriangulated = bestTriangulated;
727 
728  return true;
729  }
730 
731  return false;
732 }
733 
734 void Initializer::Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D)
735 {
736  cv::Mat A(4,4,CV_32F);
737 
738  A.row(0) = kp1.pt.x*P1.row(2)-P1.row(0);
739  A.row(1) = kp1.pt.y*P1.row(2)-P1.row(1);
740  A.row(2) = kp2.pt.x*P2.row(2)-P2.row(0);
741  A.row(3) = kp2.pt.y*P2.row(2)-P2.row(1);
742 
743  cv::Mat u,w,vt;
744  cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV);
745  x3D = vt.row(3).t();
746  x3D = x3D.rowRange(0,3)/x3D.at<float>(3);
747 }
748 
749 void Initializer::Normalize(const vector<cv::KeyPoint> &vKeys, vector<cv::Point2f> &vNormalizedPoints, cv::Mat &T)
750 {
751  float meanX = 0;
752  float meanY = 0;
753  const int N = vKeys.size();
754 
755  vNormalizedPoints.resize(N);
756 
757  for(int i=0; i<N; i++)
758  {
759  meanX += vKeys[i].pt.x;
760  meanY += vKeys[i].pt.y;
761  }
762 
763  meanX = meanX/N;
764  meanY = meanY/N;
765 
766  float meanDevX = 0;
767  float meanDevY = 0;
768 
769  for(int i=0; i<N; i++)
770  {
771  vNormalizedPoints[i].x = vKeys[i].pt.x - meanX;
772  vNormalizedPoints[i].y = vKeys[i].pt.y - meanY;
773 
774  meanDevX += fabs(vNormalizedPoints[i].x);
775  meanDevY += fabs(vNormalizedPoints[i].y);
776  }
777 
778  meanDevX = meanDevX/N;
779  meanDevY = meanDevY/N;
780 
781  float sX = 1.0/meanDevX;
782  float sY = 1.0/meanDevY;
783 
784  for(int i=0; i<N; i++)
785  {
786  vNormalizedPoints[i].x = vNormalizedPoints[i].x * sX;
787  vNormalizedPoints[i].y = vNormalizedPoints[i].y * sY;
788  }
789 
790  T = cv::Mat::eye(3,3,CV_32F);
791  T.at<float>(0,0) = sX;
792  T.at<float>(1,1) = sY;
793  T.at<float>(0,2) = -meanX*sX;
794  T.at<float>(1,2) = -meanY*sY;
795 }
796 
797 
798 int Initializer::CheckRT(const cv::Mat &R, const cv::Mat &t, const vector<cv::KeyPoint> &vKeys1, const vector<cv::KeyPoint> &vKeys2,
799  const vector<Match> &vMatches12, vector<bool> &vbMatchesInliers,
800  const cv::Mat &K, vector<cv::Point3f> &vP3D, float th2, vector<bool> &vbGood, float &parallax)
801 {
802  // Calibration parameters
803  const float fx = K.at<float>(0,0);
804  const float fy = K.at<float>(1,1);
805  const float cx = K.at<float>(0,2);
806  const float cy = K.at<float>(1,2);
807 
808  vbGood = vector<bool>(vKeys1.size(),false);
809  vP3D.resize(vKeys1.size());
810 
811  vector<float> vCosParallax;
812  vCosParallax.reserve(vKeys1.size());
813 
814  // Camera 1 Projection Matrix K[I|0]
815  cv::Mat P1(3,4,CV_32F,cv::Scalar(0));
816  K.copyTo(P1.rowRange(0,3).colRange(0,3));
817 
818  cv::Mat O1 = cv::Mat::zeros(3,1,CV_32F);
819 
820  // Camera 2 Projection Matrix K[R|t]
821  cv::Mat P2(3,4,CV_32F);
822  R.copyTo(P2.rowRange(0,3).colRange(0,3));
823  t.copyTo(P2.rowRange(0,3).col(3));
824  P2 = K*P2;
825 
826  cv::Mat O2 = -R.t()*t;
827 
828  int nGood=0;
829 
830  for(size_t i=0, iend=vMatches12.size();i<iend;i++)
831  {
832  if(!vbMatchesInliers[i])
833  continue;
834 
835  const cv::KeyPoint &kp1 = vKeys1[vMatches12[i].first];
836  const cv::KeyPoint &kp2 = vKeys2[vMatches12[i].second];
837  cv::Mat p3dC1;
838 
839  Triangulate(kp1,kp2,P1,P2,p3dC1);
840 
841  if(!isfinite(p3dC1.at<float>(0)) || !isfinite(p3dC1.at<float>(1)) || !isfinite(p3dC1.at<float>(2)))
842  {
843  vbGood[vMatches12[i].first]=false;
844  continue;
845  }
846 
847  // Check parallax
848  cv::Mat normal1 = p3dC1 - O1;
849  float dist1 = cv::norm(normal1);
850 
851  cv::Mat normal2 = p3dC1 - O2;
852  float dist2 = cv::norm(normal2);
853 
854  float cosParallax = normal1.dot(normal2)/(dist1*dist2);
855 
856  // Check depth in front of first camera (only if enough parallax, as "infinite" points can easily go to negative depth)
857  if(p3dC1.at<float>(2)<=0 && cosParallax<0.99998)
858  continue;
859 
860  // Check depth in front of second camera (only if enough parallax, as "infinite" points can easily go to negative depth)
861  cv::Mat p3dC2 = R*p3dC1+t;
862 
863  if(p3dC2.at<float>(2)<=0 && cosParallax<0.99998)
864  continue;
865 
866  // Check reprojection error in first image
867  float im1x, im1y;
868  float invZ1 = 1.0/p3dC1.at<float>(2);
869  im1x = fx*p3dC1.at<float>(0)*invZ1+cx;
870  im1y = fy*p3dC1.at<float>(1)*invZ1+cy;
871 
872  float squareError1 = (im1x-kp1.pt.x)*(im1x-kp1.pt.x)+(im1y-kp1.pt.y)*(im1y-kp1.pt.y);
873 
874  if(squareError1>th2)
875  continue;
876 
877  // Check reprojection error in second image
878  float im2x, im2y;
879  float invZ2 = 1.0/p3dC2.at<float>(2);
880  im2x = fx*p3dC2.at<float>(0)*invZ2+cx;
881  im2y = fy*p3dC2.at<float>(1)*invZ2+cy;
882 
883  float squareError2 = (im2x-kp2.pt.x)*(im2x-kp2.pt.x)+(im2y-kp2.pt.y)*(im2y-kp2.pt.y);
884 
885  if(squareError2>th2)
886  continue;
887 
888  vCosParallax.push_back(cosParallax);
889  vP3D[vMatches12[i].first] = cv::Point3f(p3dC1.at<float>(0),p3dC1.at<float>(1),p3dC1.at<float>(2));
890  nGood++;
891 
892  if(cosParallax<0.99998)
893  vbGood[vMatches12[i].first]=true;
894  }
895 
896  if(nGood>0)
897  {
898  sort(vCosParallax.begin(),vCosParallax.end());
899 
900  size_t idx = min(50,int(vCosParallax.size()-1));
901  parallax = acos(vCosParallax[idx])*180/CV_PI;
902  }
903  else
904  parallax=0;
905 
906  return nGood;
907 }
908 
909 void Initializer::DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t)
910 {
911  cv::Mat u,w,vt;
912  cv::SVD::compute(E,w,u,vt);
913 
914  u.col(2).copyTo(t);
915  t=t/cv::norm(t);
916 
917  cv::Mat W(3,3,CV_32F,cv::Scalar(0));
918  W.at<float>(0,1)=-1;
919  W.at<float>(1,0)=1;
920  W.at<float>(2,2)=1;
921 
922  R1 = u*W*vt;
923  if(cv::determinant(R1)<0)
924  R1=-R1;
925 
926  R2 = u*W.t()*vt;
927  if(cv::determinant(R2)<0)
928  R2=-R2;
929 }
930 
931 } //namespace ORB_SLAM
static void SeedRandOnce()
Definition: Random.cpp:24
void FindFundamental(vector< bool > &vbInliers, float &score, cv::Mat &F21)
Definition: Initializer.cc:175
XmlRpcServer s
void DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t)
Definition: Initializer.cc:909
TFSIMD_FORCE_INLINE const tfScalar & y() const
vector< cv::KeyPoint > mvKeys1
Definition: Initializer.h:76
cv::Mat ComputeF21(const vector< cv::Point2f > &vP1, const vector< cv::Point2f > &vP2)
Definition: Initializer.cc:268
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:138
int CheckRT(const cv::Mat &R, const cv::Mat &t, const vector< cv::KeyPoint > &vKeys1, const vector< cv::KeyPoint > &vKeys2, const vector< Match > &vMatches12, vector< bool > &vbInliers, const cv::Mat &K, vector< cv::Point3f > &vP3D, float th2, vector< bool > &vbGood, float &parallax)
Definition: Initializer.cc:798
float CheckFundamental(const cv::Mat &F21, vector< bool > &vbMatchesInliers, float sigma)
Definition: Initializer.cc:390
vector< vector< size_t > > mvSets
Definition: Initializer.h:95
void Normalize(const vector< cv::KeyPoint > &vKeys, vector< cv::Point2f > &vNormalizedPoints, cv::Mat &T)
Definition: Initializer.cc:749
void Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D)
Definition: Initializer.cc:734
float CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector< bool > &vbMatchesInliers, float sigma)
Definition: Initializer.cc:305
TFSIMD_FORCE_INLINE const tfScalar & x() const
cv::Mat mK
Definition: Frame.h:112
static int RandomInt(int min, int max)
Definition: Random.cpp:47
TFSIMD_FORCE_INLINE const tfScalar & w() const
Initializer(const Frame &ReferenceFrame, float sigma=1.0, int iterations=200)
Definition: Initializer.cc:33
vector< bool > mvbMatched1
Definition: Initializer.h:83
int min(int a, int b)
bool ReconstructH(vector< bool > &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, cv::Mat &R21, cv::Mat &t21, vector< cv::Point3f > &vP3D, vector< bool > &vbTriangulated, float minParallax, int minTriangulated)
Definition: Initializer.cc:572
cv::Mat ComputeH21(const vector< cv::Point2f > &vP1, const vector< cv::Point2f > &vP2)
Definition: Initializer.cc:226
bool Initialize(const Frame &CurrentFrame, const vector< int > &vMatches12, cv::Mat &R21, cv::Mat &t21, vector< cv::Point3f > &vP3D, vector< bool > &vbTriangulated)
Definition: Initializer.cc:44
vector< cv::KeyPoint > mvKeys2
Definition: Initializer.h:79
vector< Match > mvMatches12
Definition: Initializer.h:82
bool ReconstructF(vector< bool > &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, cv::Mat &R21, cv::Mat &t21, vector< cv::Point3f > &vP3D, vector< bool > &vbTriangulated, float minParallax, int minTriangulated)
Definition: Initializer.cc:470
void FindHomography(vector< bool > &vbMatchesInliers, float &score, cv::Mat &H21)
Definition: Initializer.cc:124


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05