Initializer.cc 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #include "Initializer.h"
  19. #include "Thirdparty/DBoW2/DUtils/Random.h"
  20. #include "Optimizer.h"
  21. #include "ORBmatcher.h"
  22. #include<thread>
  23. #include <include/CameraModels/Pinhole.h>
  24. namespace ORB_SLAM3
  25. {
  26. Initializer::Initializer(const Frame &ReferenceFrame, float sigma, int iterations)
  27. {
  28. mpCamera = ReferenceFrame.mpCamera;
  29. mK = ReferenceFrame.mK.clone();
  30. mvKeys1 = ReferenceFrame.mvKeysUn;
  31. mSigma = sigma;
  32. mSigma2 = sigma*sigma;
  33. mMaxIterations = iterations;
  34. }
  35. bool Initializer::Initialize(const Frame &CurrentFrame, const vector<int> &vMatches12, cv::Mat &R21, cv::Mat &t21,
  36. vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated)
  37. {
  38. mvKeys2 = CurrentFrame.mvKeysUn;
  39. mvMatches12.clear();
  40. mvMatches12.reserve(mvKeys2.size());
  41. mvbMatched1.resize(mvKeys1.size());
  42. for(size_t i=0, iend=vMatches12.size();i<iend; i++)
  43. {
  44. if(vMatches12[i]>=0)
  45. {
  46. mvMatches12.push_back(make_pair(i,vMatches12[i]));
  47. mvbMatched1[i]=true;
  48. }
  49. else
  50. mvbMatched1[i]=false;
  51. }
  52. const int N = mvMatches12.size();
  53. vector<size_t> vAllIndices;
  54. vAllIndices.reserve(N);
  55. vector<size_t> vAvailableIndices;
  56. for(int i=0; i<N; i++)
  57. {
  58. vAllIndices.push_back(i);
  59. }
  60. // Generate sets of 8 points for each RANSAC iteration
  61. mvSets = vector< vector<size_t> >(mMaxIterations,vector<size_t>(8,0));
  62. DUtils::Random::SeedRandOnce(0);
  63. for(int it=0; it<mMaxIterations; it++)
  64. {
  65. vAvailableIndices = vAllIndices;
  66. // Select a minimum set
  67. for(size_t j=0; j<8; j++)
  68. {
  69. int randi = DUtils::Random::RandomInt(0,vAvailableIndices.size()-1);
  70. int idx = vAvailableIndices[randi];
  71. mvSets[it][j] = idx;
  72. vAvailableIndices[randi] = vAvailableIndices.back();
  73. vAvailableIndices.pop_back();
  74. }
  75. }
  76. // Launch threads to compute in parallel a fundamental matrix and a homography
  77. vector<bool> vbMatchesInliersH, vbMatchesInliersF;
  78. float SH, SF;
  79. cv::Mat H, F;
  80. thread threadH(&Initializer::FindHomography,this,ref(vbMatchesInliersH), ref(SH), ref(H));
  81. thread threadF(&Initializer::FindFundamental,this,ref(vbMatchesInliersF), ref(SF), ref(F));
  82. //cout << "5" << endl;
  83. // Wait until both threads have finished
  84. threadH.join();
  85. threadF.join();
  86. // Compute ratio of scores
  87. float RH = SH/(SH+SF);
  88. //cout << "6" << endl;
  89. float minParallax = 1.0; // 1.0 originally
  90. cv::Mat K = static_cast<Pinhole*>(mpCamera)->toK();
  91. // Try to reconstruct from homography or fundamental depending on the ratio (0.40-0.45)
  92. if(RH>0.40) // if(RH>0.40)
  93. {
  94. //cout << "Initialization from Homography" << endl;
  95. return ReconstructH(vbMatchesInliersH,H, K,R21,t21,vP3D,vbTriangulated,minParallax,50);
  96. }
  97. else //if(pF_HF>0.6)
  98. {
  99. //cout << "Initialization from Fundamental" << endl;
  100. return ReconstructF(vbMatchesInliersF,F,K,R21,t21,vP3D,vbTriangulated,minParallax,50);
  101. }
  102. return false;
  103. }
  104. void Initializer::FindHomography(vector<bool> &vbMatchesInliers, float &score, cv::Mat &H21)
  105. {
  106. // Number of putative matches
  107. const int N = mvMatches12.size();
  108. // Normalize coordinates
  109. vector<cv::Point2f> vPn1, vPn2;
  110. cv::Mat T1, T2;
  111. Normalize(mvKeys1,vPn1, T1);
  112. Normalize(mvKeys2,vPn2, T2);
  113. cv::Mat T2inv = T2.inv();
  114. // Best Results variables
  115. score = 0.0;
  116. vbMatchesInliers = vector<bool>(N,false);
  117. // Iteration variables
  118. vector<cv::Point2f> vPn1i(8);
  119. vector<cv::Point2f> vPn2i(8);
  120. cv::Mat H21i, H12i;
  121. vector<bool> vbCurrentInliers(N,false);
  122. float currentScore;
  123. // Perform all RANSAC iterations and save the solution with highest score
  124. for(int it=0; it<mMaxIterations; it++)
  125. {
  126. // Select a minimum set
  127. for(size_t j=0; j<8; j++)
  128. {
  129. int idx = mvSets[it][j];
  130. vPn1i[j] = vPn1[mvMatches12[idx].first];
  131. vPn2i[j] = vPn2[mvMatches12[idx].second];
  132. }
  133. cv::Mat Hn = ComputeH21(vPn1i,vPn2i);
  134. H21i = T2inv*Hn*T1;
  135. H12i = H21i.inv();
  136. currentScore = CheckHomography(H21i, H12i, vbCurrentInliers, mSigma);
  137. if(currentScore>score)
  138. {
  139. H21 = H21i.clone();
  140. vbMatchesInliers = vbCurrentInliers;
  141. score = currentScore;
  142. }
  143. }
  144. }
  145. void Initializer::FindFundamental(vector<bool> &vbMatchesInliers, float &score, cv::Mat &F21)
  146. {
  147. // Number of putative matches
  148. const int N = vbMatchesInliers.size();
  149. // Normalize coordinates
  150. vector<cv::Point2f> vPn1, vPn2;
  151. cv::Mat T1, T2;
  152. Normalize(mvKeys1,vPn1, T1);
  153. Normalize(mvKeys2,vPn2, T2);
  154. cv::Mat T2t = T2.t();
  155. // Best Results variables
  156. score = 0.0;
  157. vbMatchesInliers = vector<bool>(N,false);
  158. // Iteration variables
  159. vector<cv::Point2f> vPn1i(8);
  160. vector<cv::Point2f> vPn2i(8);
  161. cv::Mat F21i;
  162. vector<bool> vbCurrentInliers(N,false);
  163. float currentScore;
  164. // Perform all RANSAC iterations and save the solution with highest score
  165. for(int it=0; it<mMaxIterations; it++)
  166. {
  167. // Select a minimum set
  168. for(int j=0; j<8; j++)
  169. {
  170. int idx = mvSets[it][j];
  171. vPn1i[j] = vPn1[mvMatches12[idx].first];
  172. vPn2i[j] = vPn2[mvMatches12[idx].second];
  173. }
  174. cv::Mat Fn = ComputeF21(vPn1i,vPn2i);
  175. F21i = T2t*Fn*T1;
  176. currentScore = CheckFundamental(F21i, vbCurrentInliers, mSigma);
  177. if(currentScore>score)
  178. {
  179. F21 = F21i.clone();
  180. vbMatchesInliers = vbCurrentInliers;
  181. score = currentScore;
  182. }
  183. }
  184. }
  185. cv::Mat Initializer::ComputeH21(const vector<cv::Point2f> &vP1, const vector<cv::Point2f> &vP2)
  186. {
  187. const int N = vP1.size();
  188. cv::Mat A(2*N,9,CV_32F);
  189. for(int i=0; i<N; i++)
  190. {
  191. const float u1 = vP1[i].x;
  192. const float v1 = vP1[i].y;
  193. const float u2 = vP2[i].x;
  194. const float v2 = vP2[i].y;
  195. A.at<float>(2*i,0) = 0.0;
  196. A.at<float>(2*i,1) = 0.0;
  197. A.at<float>(2*i,2) = 0.0;
  198. A.at<float>(2*i,3) = -u1;
  199. A.at<float>(2*i,4) = -v1;
  200. A.at<float>(2*i,5) = -1;
  201. A.at<float>(2*i,6) = v2*u1;
  202. A.at<float>(2*i,7) = v2*v1;
  203. A.at<float>(2*i,8) = v2;
  204. A.at<float>(2*i+1,0) = u1;
  205. A.at<float>(2*i+1,1) = v1;
  206. A.at<float>(2*i+1,2) = 1;
  207. A.at<float>(2*i+1,3) = 0.0;
  208. A.at<float>(2*i+1,4) = 0.0;
  209. A.at<float>(2*i+1,5) = 0.0;
  210. A.at<float>(2*i+1,6) = -u2*u1;
  211. A.at<float>(2*i+1,7) = -u2*v1;
  212. A.at<float>(2*i+1,8) = -u2;
  213. }
  214. cv::Mat u,w,vt;
  215. cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
  216. return vt.row(8).reshape(0, 3);
  217. }
  218. cv::Mat Initializer::ComputeF21(const vector<cv::Point2f> &vP1,const vector<cv::Point2f> &vP2)
  219. {
  220. const int N = vP1.size();
  221. cv::Mat A(N,9,CV_32F);
  222. for(int i=0; i<N; i++)
  223. {
  224. const float u1 = vP1[i].x;
  225. const float v1 = vP1[i].y;
  226. const float u2 = vP2[i].x;
  227. const float v2 = vP2[i].y;
  228. A.at<float>(i,0) = u2*u1;
  229. A.at<float>(i,1) = u2*v1;
  230. A.at<float>(i,2) = u2;
  231. A.at<float>(i,3) = v2*u1;
  232. A.at<float>(i,4) = v2*v1;
  233. A.at<float>(i,5) = v2;
  234. A.at<float>(i,6) = u1;
  235. A.at<float>(i,7) = v1;
  236. A.at<float>(i,8) = 1;
  237. }
  238. cv::Mat u,w,vt;
  239. cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
  240. cv::Mat Fpre = vt.row(8).reshape(0, 3);
  241. cv::SVDecomp(Fpre,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
  242. w.at<float>(2)=0;
  243. return u*cv::Mat::diag(w)*vt;
  244. }
  245. float Initializer::CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector<bool> &vbMatchesInliers, float sigma)
  246. {
  247. const int N = mvMatches12.size();
  248. const float h11 = H21.at<float>(0,0);
  249. const float h12 = H21.at<float>(0,1);
  250. const float h13 = H21.at<float>(0,2);
  251. const float h21 = H21.at<float>(1,0);
  252. const float h22 = H21.at<float>(1,1);
  253. const float h23 = H21.at<float>(1,2);
  254. const float h31 = H21.at<float>(2,0);
  255. const float h32 = H21.at<float>(2,1);
  256. const float h33 = H21.at<float>(2,2);
  257. const float h11inv = H12.at<float>(0,0);
  258. const float h12inv = H12.at<float>(0,1);
  259. const float h13inv = H12.at<float>(0,2);
  260. const float h21inv = H12.at<float>(1,0);
  261. const float h22inv = H12.at<float>(1,1);
  262. const float h23inv = H12.at<float>(1,2);
  263. const float h31inv = H12.at<float>(2,0);
  264. const float h32inv = H12.at<float>(2,1);
  265. const float h33inv = H12.at<float>(2,2);
  266. vbMatchesInliers.resize(N);
  267. float score = 0;
  268. const float th = 5.991;
  269. const float invSigmaSquare = 1.0/(sigma*sigma);
  270. for(int i=0; i<N; i++)
  271. {
  272. bool bIn = true;
  273. const cv::KeyPoint &kp1 = mvKeys1[mvMatches12[i].first];
  274. const cv::KeyPoint &kp2 = mvKeys2[mvMatches12[i].second];
  275. const float u1 = kp1.pt.x;
  276. const float v1 = kp1.pt.y;
  277. const float u2 = kp2.pt.x;
  278. const float v2 = kp2.pt.y;
  279. // Reprojection error in first image
  280. // x2in1 = H12*x2
  281. const float w2in1inv = 1.0/(h31inv*u2+h32inv*v2+h33inv);
  282. const float u2in1 = (h11inv*u2+h12inv*v2+h13inv)*w2in1inv;
  283. const float v2in1 = (h21inv*u2+h22inv*v2+h23inv)*w2in1inv;
  284. const float squareDist1 = (u1-u2in1)*(u1-u2in1)+(v1-v2in1)*(v1-v2in1);
  285. const float chiSquare1 = squareDist1*invSigmaSquare;
  286. if(chiSquare1>th)
  287. bIn = false;
  288. else
  289. score += th - chiSquare1;
  290. // Reprojection error in second image
  291. // x1in2 = H21*x1
  292. const float w1in2inv = 1.0/(h31*u1+h32*v1+h33);
  293. const float u1in2 = (h11*u1+h12*v1+h13)*w1in2inv;
  294. const float v1in2 = (h21*u1+h22*v1+h23)*w1in2inv;
  295. const float squareDist2 = (u2-u1in2)*(u2-u1in2)+(v2-v1in2)*(v2-v1in2);
  296. const float chiSquare2 = squareDist2*invSigmaSquare;
  297. if(chiSquare2>th)
  298. bIn = false;
  299. else
  300. score += th - chiSquare2;
  301. if(bIn)
  302. vbMatchesInliers[i]=true;
  303. else
  304. vbMatchesInliers[i]=false;
  305. }
  306. return score;
  307. }
  308. float Initializer::CheckFundamental(const cv::Mat &F21, vector<bool> &vbMatchesInliers, float sigma)
  309. {
  310. const int N = mvMatches12.size();
  311. const float f11 = F21.at<float>(0,0);
  312. const float f12 = F21.at<float>(0,1);
  313. const float f13 = F21.at<float>(0,2);
  314. const float f21 = F21.at<float>(1,0);
  315. const float f22 = F21.at<float>(1,1);
  316. const float f23 = F21.at<float>(1,2);
  317. const float f31 = F21.at<float>(2,0);
  318. const float f32 = F21.at<float>(2,1);
  319. const float f33 = F21.at<float>(2,2);
  320. vbMatchesInliers.resize(N);
  321. float score = 0;
  322. const float th = 3.841;
  323. const float thScore = 5.991;
  324. const float invSigmaSquare = 1.0/(sigma*sigma);
  325. for(int i=0; i<N; i++)
  326. {
  327. bool bIn = true;
  328. const cv::KeyPoint &kp1 = mvKeys1[mvMatches12[i].first];
  329. const cv::KeyPoint &kp2 = mvKeys2[mvMatches12[i].second];
  330. const float u1 = kp1.pt.x;
  331. const float v1 = kp1.pt.y;
  332. const float u2 = kp2.pt.x;
  333. const float v2 = kp2.pt.y;
  334. // Reprojection error in second image
  335. // l2=F21x1=(a2,b2,c2)
  336. const float a2 = f11*u1+f12*v1+f13;
  337. const float b2 = f21*u1+f22*v1+f23;
  338. const float c2 = f31*u1+f32*v1+f33;
  339. const float num2 = a2*u2+b2*v2+c2;
  340. const float squareDist1 = num2*num2/(a2*a2+b2*b2);
  341. const float chiSquare1 = squareDist1*invSigmaSquare;
  342. if(chiSquare1>th)
  343. bIn = false;
  344. else
  345. score += thScore - chiSquare1;
  346. // Reprojection error in second image
  347. // l1 =x2tF21=(a1,b1,c1)
  348. const float a1 = f11*u2+f21*v2+f31;
  349. const float b1 = f12*u2+f22*v2+f32;
  350. const float c1 = f13*u2+f23*v2+f33;
  351. const float num1 = a1*u1+b1*v1+c1;
  352. const float squareDist2 = num1*num1/(a1*a1+b1*b1);
  353. const float chiSquare2 = squareDist2*invSigmaSquare;
  354. if(chiSquare2>th)
  355. bIn = false;
  356. else
  357. score += thScore - chiSquare2;
  358. if(bIn)
  359. vbMatchesInliers[i]=true;
  360. else
  361. vbMatchesInliers[i]=false;
  362. }
  363. return score;
  364. }
  365. bool Initializer::ReconstructF(vector<bool> &vbMatchesInliers, cv::Mat &F21, cv::Mat &K,
  366. cv::Mat &R21, cv::Mat &t21, vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated, float minParallax, int minTriangulated)
  367. {
  368. int N=0;
  369. for(size_t i=0, iend = vbMatchesInliers.size() ; i<iend; i++)
  370. if(vbMatchesInliers[i])
  371. N++;
  372. // Compute Essential Matrix from Fundamental Matrix
  373. cv::Mat E21 = K.t()*F21*K;
  374. cv::Mat R1, R2, t;
  375. // Recover the 4 motion hypotheses
  376. DecomposeE(E21,R1,R2,t);
  377. cv::Mat t1=t;
  378. cv::Mat t2=-t;
  379. // Reconstruct with the 4 hyphoteses and check
  380. vector<cv::Point3f> vP3D1, vP3D2, vP3D3, vP3D4;
  381. vector<bool> vbTriangulated1,vbTriangulated2,vbTriangulated3, vbTriangulated4;
  382. float parallax1,parallax2, parallax3, parallax4;
  383. int nGood1 = CheckRT(R1,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D1, 4.0*mSigma2, vbTriangulated1, parallax1);
  384. int nGood2 = CheckRT(R2,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D2, 4.0*mSigma2, vbTriangulated2, parallax2);
  385. int nGood3 = CheckRT(R1,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D3, 4.0*mSigma2, vbTriangulated3, parallax3);
  386. int nGood4 = CheckRT(R2,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D4, 4.0*mSigma2, vbTriangulated4, parallax4);
  387. int maxGood = max(nGood1,max(nGood2,max(nGood3,nGood4)));
  388. R21 = cv::Mat();
  389. t21 = cv::Mat();
  390. int nMinGood = max(static_cast<int>(0.9*N),minTriangulated);
  391. int nsimilar = 0;
  392. if(nGood1>0.7*maxGood)
  393. nsimilar++;
  394. if(nGood2>0.7*maxGood)
  395. nsimilar++;
  396. if(nGood3>0.7*maxGood)
  397. nsimilar++;
  398. if(nGood4>0.7*maxGood)
  399. nsimilar++;
  400. // If there is not a clear winner or not enough triangulated points reject initialization
  401. if(maxGood<nMinGood || nsimilar>1)
  402. {
  403. return false;
  404. }
  405. // If best reconstruction has enough parallax initialize
  406. if(maxGood==nGood1)
  407. {
  408. if(parallax1>minParallax)
  409. {
  410. vP3D = vP3D1;
  411. vbTriangulated = vbTriangulated1;
  412. R1.copyTo(R21);
  413. t1.copyTo(t21);
  414. return true;
  415. }
  416. }else if(maxGood==nGood2)
  417. {
  418. if(parallax2>minParallax)
  419. {
  420. vP3D = vP3D2;
  421. vbTriangulated = vbTriangulated2;
  422. R2.copyTo(R21);
  423. t1.copyTo(t21);
  424. return true;
  425. }
  426. }else if(maxGood==nGood3)
  427. {
  428. if(parallax3>minParallax)
  429. {
  430. vP3D = vP3D3;
  431. vbTriangulated = vbTriangulated3;
  432. R1.copyTo(R21);
  433. t2.copyTo(t21);
  434. return true;
  435. }
  436. }else if(maxGood==nGood4)
  437. {
  438. if(parallax4>minParallax)
  439. {
  440. vP3D = vP3D4;
  441. vbTriangulated = vbTriangulated4;
  442. R2.copyTo(R21);
  443. t2.copyTo(t21);
  444. return true;
  445. }
  446. }
  447. return false;
  448. }
  449. bool Initializer::ReconstructH(vector<bool> &vbMatchesInliers, cv::Mat &H21, cv::Mat &K,
  450. cv::Mat &R21, cv::Mat &t21, vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated, float minParallax, int minTriangulated)
  451. {
  452. int N=0;
  453. for(size_t i=0, iend = vbMatchesInliers.size() ; i<iend; i++)
  454. if(vbMatchesInliers[i])
  455. N++;
  456. // We recover 8 motion hypotheses using the method of Faugeras et al.
  457. // Motion and structure from motion in a piecewise planar environment.
  458. // International Journal of Pattern Recognition and Artificial Intelligence, 1988
  459. cv::Mat invK = K.inv();
  460. cv::Mat A = invK*H21*K;
  461. cv::Mat U,w,Vt,V;
  462. cv::SVD::compute(A,w,U,Vt,cv::SVD::FULL_UV);
  463. V=Vt.t();
  464. float s = cv::determinant(U)*cv::determinant(Vt);
  465. float d1 = w.at<float>(0);
  466. float d2 = w.at<float>(1);
  467. float d3 = w.at<float>(2);
  468. if(d1/d2<1.00001 || d2/d3<1.00001)
  469. {
  470. return false;
  471. }
  472. vector<cv::Mat> vR, vt, vn;
  473. vR.reserve(8);
  474. vt.reserve(8);
  475. vn.reserve(8);
  476. //n'=[x1 0 x3] 4 posibilities e1=e3=1, e1=1 e3=-1, e1=-1 e3=1, e1=e3=-1
  477. float aux1 = sqrt((d1*d1-d2*d2)/(d1*d1-d3*d3));
  478. float aux3 = sqrt((d2*d2-d3*d3)/(d1*d1-d3*d3));
  479. float x1[] = {aux1,aux1,-aux1,-aux1};
  480. float x3[] = {aux3,-aux3,aux3,-aux3};
  481. //case d'=d2
  482. float aux_stheta = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1+d3)*d2);
  483. float ctheta = (d2*d2+d1*d3)/((d1+d3)*d2);
  484. float stheta[] = {aux_stheta, -aux_stheta, -aux_stheta, aux_stheta};
  485. for(int i=0; i<4; i++)
  486. {
  487. cv::Mat Rp=cv::Mat::eye(3,3,CV_32F);
  488. Rp.at<float>(0,0)=ctheta;
  489. Rp.at<float>(0,2)=-stheta[i];
  490. Rp.at<float>(2,0)=stheta[i];
  491. Rp.at<float>(2,2)=ctheta;
  492. cv::Mat R = s*U*Rp*Vt;
  493. vR.push_back(R);
  494. cv::Mat tp(3,1,CV_32F);
  495. tp.at<float>(0)=x1[i];
  496. tp.at<float>(1)=0;
  497. tp.at<float>(2)=-x3[i];
  498. tp*=d1-d3;
  499. cv::Mat t = U*tp;
  500. vt.push_back(t/cv::norm(t));
  501. cv::Mat np(3,1,CV_32F);
  502. np.at<float>(0)=x1[i];
  503. np.at<float>(1)=0;
  504. np.at<float>(2)=x3[i];
  505. cv::Mat n = V*np;
  506. if(n.at<float>(2)<0)
  507. n=-n;
  508. vn.push_back(n);
  509. }
  510. //case d'=-d2
  511. float aux_sphi = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1-d3)*d2);
  512. float cphi = (d1*d3-d2*d2)/((d1-d3)*d2);
  513. float sphi[] = {aux_sphi, -aux_sphi, -aux_sphi, aux_sphi};
  514. for(int i=0; i<4; i++)
  515. {
  516. cv::Mat Rp=cv::Mat::eye(3,3,CV_32F);
  517. Rp.at<float>(0,0)=cphi;
  518. Rp.at<float>(0,2)=sphi[i];
  519. Rp.at<float>(1,1)=-1;
  520. Rp.at<float>(2,0)=sphi[i];
  521. Rp.at<float>(2,2)=-cphi;
  522. cv::Mat R = s*U*Rp*Vt;
  523. vR.push_back(R);
  524. cv::Mat tp(3,1,CV_32F);
  525. tp.at<float>(0)=x1[i];
  526. tp.at<float>(1)=0;
  527. tp.at<float>(2)=x3[i];
  528. tp*=d1+d3;
  529. cv::Mat t = U*tp;
  530. vt.push_back(t/cv::norm(t));
  531. cv::Mat np(3,1,CV_32F);
  532. np.at<float>(0)=x1[i];
  533. np.at<float>(1)=0;
  534. np.at<float>(2)=x3[i];
  535. cv::Mat n = V*np;
  536. if(n.at<float>(2)<0)
  537. n=-n;
  538. vn.push_back(n);
  539. }
  540. int bestGood = 0;
  541. int secondBestGood = 0;
  542. int bestSolutionIdx = -1;
  543. float bestParallax = -1;
  544. vector<cv::Point3f> bestP3D;
  545. vector<bool> bestTriangulated;
  546. // Instead of applying the visibility constraints proposed in the Faugeras' paper (which could fail for points seen with low parallax)
  547. // We reconstruct all hypotheses and check in terms of triangulated points and parallax
  548. for(size_t i=0; i<8; i++)
  549. {
  550. float parallaxi;
  551. vector<cv::Point3f> vP3Di;
  552. vector<bool> vbTriangulatedi;
  553. int nGood = CheckRT(vR[i],vt[i],mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K,vP3Di, 4.0*mSigma2, vbTriangulatedi, parallaxi);
  554. if(nGood>bestGood)
  555. {
  556. secondBestGood = bestGood;
  557. bestGood = nGood;
  558. bestSolutionIdx = i;
  559. bestParallax = parallaxi;
  560. bestP3D = vP3Di;
  561. bestTriangulated = vbTriangulatedi;
  562. }
  563. else if(nGood>secondBestGood)
  564. {
  565. secondBestGood = nGood;
  566. }
  567. }
  568. if(secondBestGood<0.75*bestGood && bestParallax>=minParallax && bestGood>minTriangulated && bestGood>0.9*N)
  569. {
  570. vR[bestSolutionIdx].copyTo(R21);
  571. vt[bestSolutionIdx].copyTo(t21);
  572. vP3D = bestP3D;
  573. vbTriangulated = bestTriangulated;
  574. return true;
  575. }
  576. return false;
  577. }
  578. void Initializer::Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D)
  579. {
  580. cv::Mat A(4,4,CV_32F);
  581. A.row(0) = kp1.pt.x*P1.row(2)-P1.row(0);
  582. A.row(1) = kp1.pt.y*P1.row(2)-P1.row(1);
  583. A.row(2) = kp2.pt.x*P2.row(2)-P2.row(0);
  584. A.row(3) = kp2.pt.y*P2.row(2)-P2.row(1);
  585. cv::Mat u,w,vt;
  586. cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV);
  587. x3D = vt.row(3).t();
  588. x3D = x3D.rowRange(0,3)/x3D.at<float>(3);
  589. }
  590. void Initializer::Normalize(const vector<cv::KeyPoint> &vKeys, vector<cv::Point2f> &vNormalizedPoints, cv::Mat &T)
  591. {
  592. float meanX = 0;
  593. float meanY = 0;
  594. const int N = vKeys.size();
  595. vNormalizedPoints.resize(N);
  596. for(int i=0; i<N; i++)
  597. {
  598. meanX += vKeys[i].pt.x;
  599. meanY += vKeys[i].pt.y;
  600. }
  601. meanX = meanX/N;
  602. meanY = meanY/N;
  603. float meanDevX = 0;
  604. float meanDevY = 0;
  605. for(int i=0; i<N; i++)
  606. {
  607. vNormalizedPoints[i].x = vKeys[i].pt.x - meanX;
  608. vNormalizedPoints[i].y = vKeys[i].pt.y - meanY;
  609. meanDevX += fabs(vNormalizedPoints[i].x);
  610. meanDevY += fabs(vNormalizedPoints[i].y);
  611. }
  612. meanDevX = meanDevX/N;
  613. meanDevY = meanDevY/N;
  614. float sX = 1.0/meanDevX;
  615. float sY = 1.0/meanDevY;
  616. for(int i=0; i<N; i++)
  617. {
  618. vNormalizedPoints[i].x = vNormalizedPoints[i].x * sX;
  619. vNormalizedPoints[i].y = vNormalizedPoints[i].y * sY;
  620. }
  621. T = cv::Mat::eye(3,3,CV_32F);
  622. T.at<float>(0,0) = sX;
  623. T.at<float>(1,1) = sY;
  624. T.at<float>(0,2) = -meanX*sX;
  625. T.at<float>(1,2) = -meanY*sY;
  626. }
  627. int Initializer::CheckRT(const cv::Mat &R, const cv::Mat &t, const vector<cv::KeyPoint> &vKeys1, const vector<cv::KeyPoint> &vKeys2,
  628. const vector<Match> &vMatches12, vector<bool> &vbMatchesInliers,
  629. const cv::Mat &K, vector<cv::Point3f> &vP3D, float th2, vector<bool> &vbGood, float &parallax)
  630. {
  631. vbGood = vector<bool>(vKeys1.size(),false);
  632. vP3D.resize(vKeys1.size());
  633. vector<float> vCosParallax;
  634. vCosParallax.reserve(vKeys1.size());
  635. // Camera 1 Projection Matrix K[I|0]
  636. cv::Mat P1(3,4,CV_32F,cv::Scalar(0));
  637. K.copyTo(P1.rowRange(0,3).colRange(0,3));
  638. cv::Mat O1 = cv::Mat::zeros(3,1,CV_32F);
  639. // Camera 2 Projection Matrix K[R|t]
  640. cv::Mat P2(3,4,CV_32F);
  641. R.copyTo(P2.rowRange(0,3).colRange(0,3));
  642. t.copyTo(P2.rowRange(0,3).col(3));
  643. P2 = K*P2;
  644. cv::Mat O2 = -R.t()*t;
  645. int nGood=0;
  646. for(size_t i=0, iend=vMatches12.size();i<iend;i++)
  647. {
  648. if(!vbMatchesInliers[i])
  649. continue;
  650. const cv::KeyPoint &kp1 = vKeys1[vMatches12[i].first];
  651. const cv::KeyPoint &kp2 = vKeys2[vMatches12[i].second];
  652. cv::Mat p3dC1;
  653. Triangulate(kp1,kp2,P1,P2,p3dC1);
  654. if(!isfinite(p3dC1.at<float>(0)) || !isfinite(p3dC1.at<float>(1)) || !isfinite(p3dC1.at<float>(2)))
  655. {
  656. vbGood[vMatches12[i].first]=false;
  657. continue;
  658. }
  659. // Check parallax
  660. cv::Mat normal1 = p3dC1 - O1;
  661. float dist1 = cv::norm(normal1);
  662. cv::Mat normal2 = p3dC1 - O2;
  663. float dist2 = cv::norm(normal2);
  664. float cosParallax = normal1.dot(normal2)/(dist1*dist2);
  665. // Check depth in front of first camera (only if enough parallax, as "infinite" points can easily go to negative depth)
  666. if(p3dC1.at<float>(2)<=0 && cosParallax<0.99998)
  667. continue;
  668. // Check depth in front of second camera (only if enough parallax, as "infinite" points can easily go to negative depth)
  669. cv::Mat p3dC2 = R*p3dC1+t;
  670. if(p3dC2.at<float>(2)<=0 && cosParallax<0.99998)
  671. continue;
  672. // Check reprojection error in first image
  673. cv::Point2f uv1 = mpCamera->project(p3dC1);
  674. float squareError1 = (uv1.x-kp1.pt.x)*(uv1.x-kp1.pt.x)+(uv1.y-kp1.pt.y)*(uv1.y-kp1.pt.y);
  675. if(squareError1>th2)
  676. continue;
  677. // Check reprojection error in second image
  678. cv::Point2f uv2 = mpCamera->project(p3dC2);
  679. float squareError2 = (uv2.x-kp2.pt.x)*(uv2.x-kp2.pt.x)+(uv2.y-kp2.pt.y)*(uv2.y-kp2.pt.y);
  680. if(squareError2>th2)
  681. continue;
  682. vCosParallax.push_back(cosParallax);
  683. vP3D[vMatches12[i].first] = cv::Point3f(p3dC1.at<float>(0),p3dC1.at<float>(1),p3dC1.at<float>(2));
  684. nGood++;
  685. if(cosParallax<0.99998)
  686. vbGood[vMatches12[i].first]=true;
  687. }
  688. if(nGood>0)
  689. {
  690. sort(vCosParallax.begin(),vCosParallax.end());
  691. size_t idx = min(50,int(vCosParallax.size()-1));
  692. parallax = acos(vCosParallax[idx])*180/CV_PI;
  693. }
  694. else
  695. parallax=0;
  696. return nGood;
  697. }
  698. void Initializer::DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t)
  699. {
  700. cv::Mat u,w,vt;
  701. cv::SVD::compute(E,w,u,vt);
  702. u.col(2).copyTo(t);
  703. t=t/cv::norm(t);
  704. cv::Mat W(3,3,CV_32F,cv::Scalar(0));
  705. W.at<float>(0,1)=-1;
  706. W.at<float>(1,0)=1;
  707. W.at<float>(2,2)=1;
  708. R1 = u*W*vt;
  709. if(cv::determinant(R1)<0)
  710. R1=-R1;
  711. R2 = u*W.t()*vt;
  712. if(cv::determinant(R2)<0)
  713. R2=-R2;
  714. }
  715. } //namespace ORB_SLAM