Sim3Solver.cc 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508
  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 "Sim3Solver.h"
  19. #include <vector>
  20. #include <cmath>
  21. #include <opencv2/core/core.hpp>
  22. #include "KeyFrame.h"
  23. #include "ORBmatcher.h"
  24. #include "Thirdparty/DBoW2/DUtils/Random.h"
  25. namespace ORB_SLAM3
  26. {
  27. Sim3Solver::Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const vector<MapPoint *> &vpMatched12, const bool bFixScale,
  28. vector<KeyFrame*> vpKeyFrameMatchedMP):
  29. mnIterations(0), mnBestInliers(0), mbFixScale(bFixScale),
  30. pCamera1(pKF1->mpCamera), pCamera2(pKF2->mpCamera)
  31. {
  32. bool bDifferentKFs = false;
  33. if(vpKeyFrameMatchedMP.empty())
  34. {
  35. bDifferentKFs = true;
  36. vpKeyFrameMatchedMP = vector<KeyFrame*>(vpMatched12.size(), pKF2);
  37. }
  38. mpKF1 = pKF1;
  39. mpKF2 = pKF2;
  40. vector<MapPoint*> vpKeyFrameMP1 = pKF1->GetMapPointMatches();
  41. mN1 = vpMatched12.size();
  42. mvpMapPoints1.reserve(mN1);
  43. mvpMapPoints2.reserve(mN1);
  44. mvpMatches12 = vpMatched12;
  45. mvnIndices1.reserve(mN1);
  46. mvX3Dc1.reserve(mN1);
  47. mvX3Dc2.reserve(mN1);
  48. cv::Mat Rcw1 = pKF1->GetRotation();
  49. cv::Mat tcw1 = pKF1->GetTranslation();
  50. cv::Mat Rcw2 = pKF2->GetRotation();
  51. cv::Mat tcw2 = pKF2->GetTranslation();
  52. mvAllIndices.reserve(mN1);
  53. size_t idx=0;
  54. KeyFrame* pKFm = pKF2; //Default variable
  55. for(int i1=0; i1<mN1; i1++)
  56. {
  57. if(vpMatched12[i1])
  58. {
  59. MapPoint* pMP1 = vpKeyFrameMP1[i1];
  60. MapPoint* pMP2 = vpMatched12[i1];
  61. if(!pMP1)
  62. continue;
  63. if(pMP1->isBad() || pMP2->isBad())
  64. continue;
  65. if(bDifferentKFs)
  66. pKFm = vpKeyFrameMatchedMP[i1];
  67. int indexKF1 = get<0>(pMP1->GetIndexInKeyFrame(pKF1));
  68. int indexKF2 = get<0>(pMP2->GetIndexInKeyFrame(pKFm));
  69. if(indexKF1<0 || indexKF2<0)
  70. continue;
  71. const cv::KeyPoint &kp1 = pKF1->mvKeysUn[indexKF1];
  72. const cv::KeyPoint &kp2 = pKFm->mvKeysUn[indexKF2];
  73. const float sigmaSquare1 = pKF1->mvLevelSigma2[kp1.octave];
  74. const float sigmaSquare2 = pKFm->mvLevelSigma2[kp2.octave];
  75. mvnMaxError1.push_back(9.210*sigmaSquare1);
  76. mvnMaxError2.push_back(9.210*sigmaSquare2);
  77. mvpMapPoints1.push_back(pMP1);
  78. mvpMapPoints2.push_back(pMP2);
  79. mvnIndices1.push_back(i1);
  80. cv::Mat X3D1w = pMP1->GetWorldPos();
  81. mvX3Dc1.push_back(Rcw1*X3D1w+tcw1);
  82. cv::Mat X3D2w = pMP2->GetWorldPos();
  83. mvX3Dc2.push_back(Rcw2*X3D2w+tcw2);
  84. mvAllIndices.push_back(idx);
  85. idx++;
  86. }
  87. }
  88. mK1 = pKF1->mK;
  89. mK2 = pKF2->mK;
  90. FromCameraToImage(mvX3Dc1,mvP1im1,pCamera1);
  91. FromCameraToImage(mvX3Dc2,mvP2im2,pCamera2);
  92. SetRansacParameters();
  93. }
  94. void Sim3Solver::SetRansacParameters(double probability, int minInliers, int maxIterations)
  95. {
  96. mRansacProb = probability;
  97. mRansacMinInliers = minInliers;
  98. mRansacMaxIts = maxIterations;
  99. N = mvpMapPoints1.size(); // number of correspondences
  100. mvbInliersi.resize(N);
  101. // Adjust Parameters according to number of correspondences
  102. float epsilon = (float)mRansacMinInliers/N;
  103. // Set RANSAC iterations according to probability, epsilon, and max iterations
  104. int nIterations;
  105. if(mRansacMinInliers==N)
  106. nIterations=1;
  107. else
  108. nIterations = ceil(log(1-mRansacProb)/log(1-pow(epsilon,3)));
  109. mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts));
  110. mnIterations = 0;
  111. }
  112. cv::Mat Sim3Solver::iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers)
  113. {
  114. bNoMore = false;
  115. vbInliers = vector<bool>(mN1,false);
  116. nInliers=0;
  117. if(N<mRansacMinInliers)
  118. {
  119. bNoMore = true;
  120. return cv::Mat();
  121. }
  122. vector<size_t> vAvailableIndices;
  123. cv::Mat P3Dc1i(3,3,CV_32F);
  124. cv::Mat P3Dc2i(3,3,CV_32F);
  125. int nCurrentIterations = 0;
  126. while(mnIterations<mRansacMaxIts && nCurrentIterations<nIterations)
  127. {
  128. nCurrentIterations++;
  129. mnIterations++;
  130. vAvailableIndices = mvAllIndices;
  131. // Get min set of points
  132. for(short i = 0; i < 3; ++i)
  133. {
  134. int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1);
  135. int idx = vAvailableIndices[randi];
  136. mvX3Dc1[idx].copyTo(P3Dc1i.col(i));
  137. mvX3Dc2[idx].copyTo(P3Dc2i.col(i));
  138. vAvailableIndices[randi] = vAvailableIndices.back();
  139. vAvailableIndices.pop_back();
  140. }
  141. ComputeSim3(P3Dc1i,P3Dc2i);
  142. CheckInliers();
  143. if(mnInliersi>=mnBestInliers)
  144. {
  145. mvbBestInliers = mvbInliersi;
  146. mnBestInliers = mnInliersi;
  147. mBestT12 = mT12i.clone();
  148. mBestRotation = mR12i.clone();
  149. mBestTranslation = mt12i.clone();
  150. mBestScale = ms12i;
  151. if(mnInliersi>mRansacMinInliers)
  152. {
  153. nInliers = mnInliersi;
  154. for(int i=0; i<N; i++)
  155. if(mvbInliersi[i])
  156. vbInliers[mvnIndices1[i]] = true;
  157. return mBestT12;
  158. }
  159. }
  160. }
  161. if(mnIterations>=mRansacMaxIts)
  162. bNoMore=true;
  163. return cv::Mat();
  164. }
  165. cv::Mat Sim3Solver::iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers, bool &bConverge)
  166. {
  167. bNoMore = false;
  168. bConverge = false;
  169. vbInliers = vector<bool>(mN1,false);
  170. nInliers=0;
  171. if(N<mRansacMinInliers)
  172. {
  173. bNoMore = true;
  174. return cv::Mat();
  175. }
  176. vector<size_t> vAvailableIndices;
  177. cv::Mat P3Dc1i(3,3,CV_32F);
  178. cv::Mat P3Dc2i(3,3,CV_32F);
  179. int nCurrentIterations = 0;
  180. cv::Mat bestSim3;
  181. while(mnIterations<mRansacMaxIts && nCurrentIterations<nIterations)
  182. {
  183. nCurrentIterations++;
  184. mnIterations++;
  185. vAvailableIndices = mvAllIndices;
  186. // Get min set of points
  187. for(short i = 0; i < 3; ++i)
  188. {
  189. int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1);
  190. int idx = vAvailableIndices[randi];
  191. mvX3Dc1[idx].copyTo(P3Dc1i.col(i));
  192. mvX3Dc2[idx].copyTo(P3Dc2i.col(i));
  193. vAvailableIndices[randi] = vAvailableIndices.back();
  194. vAvailableIndices.pop_back();
  195. }
  196. ComputeSim3(P3Dc1i,P3Dc2i);
  197. CheckInliers();
  198. if(mnInliersi>=mnBestInliers)
  199. {
  200. mvbBestInliers = mvbInliersi;
  201. mnBestInliers = mnInliersi;
  202. mBestT12 = mT12i.clone();
  203. mBestRotation = mR12i.clone();
  204. mBestTranslation = mt12i.clone();
  205. mBestScale = ms12i;
  206. if(mnInliersi>mRansacMinInliers)
  207. {
  208. nInliers = mnInliersi;
  209. for(int i=0; i<N; i++)
  210. if(mvbInliersi[i])
  211. vbInliers[mvnIndices1[i]] = true;
  212. bConverge = true;
  213. return mBestT12;
  214. }
  215. else
  216. {
  217. bestSim3 = mBestT12;
  218. }
  219. }
  220. }
  221. if(mnIterations>=mRansacMaxIts)
  222. bNoMore=true;
  223. return bestSim3;
  224. }
  225. cv::Mat Sim3Solver::find(vector<bool> &vbInliers12, int &nInliers)
  226. {
  227. bool bFlag;
  228. return iterate(mRansacMaxIts,bFlag,vbInliers12,nInliers);
  229. }
  230. void Sim3Solver::ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C)
  231. {
  232. cv::reduce(P,C,1,CV_REDUCE_SUM);
  233. C = C/P.cols;
  234. for(int i=0; i<P.cols; i++)
  235. {
  236. Pr.col(i)=P.col(i)-C;
  237. }
  238. }
  239. void Sim3Solver::ComputeSim3(cv::Mat &P1, cv::Mat &P2)
  240. {
  241. // Custom implementation of:
  242. // Horn 1987, Closed-form solution of absolute orientataion using unit quaternions
  243. // Step 1: Centroid and relative coordinates
  244. cv::Mat Pr1(P1.size(),P1.type()); // Relative coordinates to centroid (set 1)
  245. cv::Mat Pr2(P2.size(),P2.type()); // Relative coordinates to centroid (set 2)
  246. cv::Mat O1(3,1,Pr1.type()); // Centroid of P1
  247. cv::Mat O2(3,1,Pr2.type()); // Centroid of P2
  248. ComputeCentroid(P1,Pr1,O1);
  249. ComputeCentroid(P2,Pr2,O2);
  250. // Step 2: Compute M matrix
  251. cv::Mat M = Pr2*Pr1.t();
  252. // Step 3: Compute N matrix
  253. double N11, N12, N13, N14, N22, N23, N24, N33, N34, N44;
  254. cv::Mat N(4,4,P1.type());
  255. N11 = M.at<float>(0,0)+M.at<float>(1,1)+M.at<float>(2,2);
  256. N12 = M.at<float>(1,2)-M.at<float>(2,1);
  257. N13 = M.at<float>(2,0)-M.at<float>(0,2);
  258. N14 = M.at<float>(0,1)-M.at<float>(1,0);
  259. N22 = M.at<float>(0,0)-M.at<float>(1,1)-M.at<float>(2,2);
  260. N23 = M.at<float>(0,1)+M.at<float>(1,0);
  261. N24 = M.at<float>(2,0)+M.at<float>(0,2);
  262. N33 = -M.at<float>(0,0)+M.at<float>(1,1)-M.at<float>(2,2);
  263. N34 = M.at<float>(1,2)+M.at<float>(2,1);
  264. N44 = -M.at<float>(0,0)-M.at<float>(1,1)+M.at<float>(2,2);
  265. N = (cv::Mat_<float>(4,4) << N11, N12, N13, N14,
  266. N12, N22, N23, N24,
  267. N13, N23, N33, N34,
  268. N14, N24, N34, N44);
  269. // Step 4: Eigenvector of the highest eigenvalue
  270. cv::Mat eval, evec;
  271. cv::eigen(N,eval,evec); //evec[0] is the quaternion of the desired rotation
  272. cv::Mat vec(1,3,evec.type());
  273. (evec.row(0).colRange(1,4)).copyTo(vec); //extract imaginary part of the quaternion (sin*axis)
  274. // Rotation angle. sin is the norm of the imaginary part, cos is the real part
  275. double ang=atan2(norm(vec),evec.at<float>(0,0));
  276. vec = 2*ang*vec/norm(vec); //Angle-axis representation. quaternion angle is the half
  277. mR12i.create(3,3,P1.type());
  278. cv::Rodrigues(vec,mR12i); // computes the rotation matrix from angle-axis
  279. // Step 5: Rotate set 2
  280. cv::Mat P3 = mR12i*Pr2;
  281. // Step 6: Scale
  282. if(!mbFixScale)
  283. {
  284. double nom = Pr1.dot(P3);
  285. cv::Mat aux_P3(P3.size(),P3.type());
  286. aux_P3=P3;
  287. cv::pow(P3,2,aux_P3);
  288. double den = 0;
  289. for(int i=0; i<aux_P3.rows; i++)
  290. {
  291. for(int j=0; j<aux_P3.cols; j++)
  292. {
  293. den+=aux_P3.at<float>(i,j);
  294. }
  295. }
  296. ms12i = nom/den;
  297. }
  298. else
  299. ms12i = 1.0f;
  300. // Step 7: Translation
  301. mt12i.create(1,3,P1.type());
  302. mt12i = O1 - ms12i*mR12i*O2;
  303. // Step 8: Transformation
  304. // Step 8.1 T12
  305. mT12i = cv::Mat::eye(4,4,P1.type());
  306. cv::Mat sR = ms12i*mR12i;
  307. sR.copyTo(mT12i.rowRange(0,3).colRange(0,3));
  308. mt12i.copyTo(mT12i.rowRange(0,3).col(3));
  309. // Step 8.2 T21
  310. mT21i = cv::Mat::eye(4,4,P1.type());
  311. cv::Mat sRinv = (1.0/ms12i)*mR12i.t();
  312. sRinv.copyTo(mT21i.rowRange(0,3).colRange(0,3));
  313. cv::Mat tinv = -sRinv*mt12i;
  314. tinv.copyTo(mT21i.rowRange(0,3).col(3));
  315. }
  316. void Sim3Solver::CheckInliers()
  317. {
  318. vector<cv::Mat> vP1im2, vP2im1;
  319. Project(mvX3Dc2,vP2im1,mT12i,pCamera1);
  320. Project(mvX3Dc1,vP1im2,mT21i,pCamera2);
  321. mnInliersi=0;
  322. for(size_t i=0; i<mvP1im1.size(); i++)
  323. {
  324. cv::Mat dist1 = mvP1im1[i]-vP2im1[i];
  325. cv::Mat dist2 = vP1im2[i]-mvP2im2[i];
  326. const float err1 = dist1.dot(dist1);
  327. const float err2 = dist2.dot(dist2);
  328. if(err1<mvnMaxError1[i] && err2<mvnMaxError2[i])
  329. {
  330. mvbInliersi[i]=true;
  331. mnInliersi++;
  332. }
  333. else
  334. mvbInliersi[i]=false;
  335. }
  336. }
  337. cv::Mat Sim3Solver::GetEstimatedRotation()
  338. {
  339. return mBestRotation.clone();
  340. }
  341. cv::Mat Sim3Solver::GetEstimatedTranslation()
  342. {
  343. return mBestTranslation.clone();
  344. }
  345. float Sim3Solver::GetEstimatedScale()
  346. {
  347. return mBestScale;
  348. }
  349. void Sim3Solver::Project(const vector<cv::Mat> &vP3Dw, vector<cv::Mat> &vP2D, cv::Mat Tcw, GeometricCamera* pCamera)
  350. {
  351. cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3);
  352. cv::Mat tcw = Tcw.rowRange(0,3).col(3);
  353. vP2D.clear();
  354. vP2D.reserve(vP3Dw.size());
  355. for(size_t i=0, iend=vP3Dw.size(); i<iend; i++)
  356. {
  357. cv::Mat P3Dc = Rcw*vP3Dw[i]+tcw;
  358. const float invz = 1/(P3Dc.at<float>(2));
  359. const float x = P3Dc.at<float>(0);
  360. const float y = P3Dc.at<float>(1);
  361. const float z = P3Dc.at<float>(2);
  362. vP2D.push_back(pCamera->projectMat(cv::Point3f(x,y,z)));
  363. }
  364. }
  365. void Sim3Solver::FromCameraToImage(const vector<cv::Mat> &vP3Dc, vector<cv::Mat> &vP2D, GeometricCamera* pCamera)
  366. {
  367. vP2D.clear();
  368. vP2D.reserve(vP3Dc.size());
  369. for(size_t i=0, iend=vP3Dc.size(); i<iend; i++)
  370. {
  371. const float invz = 1/(vP3Dc[i].at<float>(2));
  372. const float x = vP3Dc[i].at<float>(0);
  373. const float y = vP3Dc[i].at<float>(1);
  374. const float z = vP3Dc[i].at<float>(2);
  375. vP2D.push_back(pCamera->projectMat(cv::Point3f(x,y,z)));
  376. }
  377. }
  378. } //namespace ORB_SLAM