PnPsolver.cc 28 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019
  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. /**
  19. * Copyright (c) 2009, V. Lepetit, EPFL
  20. * All rights reserved.
  21. *
  22. * Redistribution and use in source and binary forms, with or without
  23. * modification, are permitted provided that the following conditions are met:
  24. *
  25. * 1. Redistributions of source code must retain the above copyright notice, this
  26. * list of conditions and the following disclaimer.
  27. * 2. Redistributions in binary form must reproduce the above copyright notice,
  28. * this list of conditions and the following disclaimer in the documentation
  29. * and/or other materials provided with the distribution.
  30. *
  31. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
  32. * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
  33. * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
  34. * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
  35. * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
  36. * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  37. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
  38. * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
  39. * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
  40. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  41. *
  42. * The views and conclusions contained in the software and documentation are those
  43. * of the authors and should not be interpreted as representing official policies,
  44. * either expressed or implied, of the FreeBSD Project
  45. */
  46. #include <iostream>
  47. #include "PnPsolver.h"
  48. #include <vector>
  49. #include <cmath>
  50. #include <opencv2/core/core.hpp>
  51. #include "Thirdparty/DBoW2/DUtils/Random.h"
  52. #include <algorithm>
  53. using namespace std;
  54. namespace ORB_SLAM3
  55. {
  56. PnPsolver::PnPsolver(const Frame &F, const vector<MapPoint*> &vpMapPointMatches):
  57. pws(0), us(0), alphas(0), pcs(0), maximum_number_of_correspondences(0), number_of_correspondences(0), mnInliersi(0),
  58. mnIterations(0), mnBestInliers(0), N(0)
  59. {
  60. mvpMapPointMatches = vpMapPointMatches;
  61. mvP2D.reserve(F.mvpMapPoints.size());
  62. mvSigma2.reserve(F.mvpMapPoints.size());
  63. mvP3Dw.reserve(F.mvpMapPoints.size());
  64. mvKeyPointIndices.reserve(F.mvpMapPoints.size());
  65. mvAllIndices.reserve(F.mvpMapPoints.size());
  66. int idx=0;
  67. for(size_t i=0, iend=vpMapPointMatches.size(); i<iend; i++)
  68. {
  69. MapPoint* pMP = vpMapPointMatches[i];
  70. if(pMP)
  71. {
  72. if(!pMP->isBad())
  73. {
  74. const cv::KeyPoint &kp = F.mvKeysUn[i];
  75. mvP2D.push_back(kp.pt);
  76. mvSigma2.push_back(F.mvLevelSigma2[kp.octave]);
  77. cv::Mat Pos = pMP->GetWorldPos();
  78. mvP3Dw.push_back(cv::Point3f(Pos.at<float>(0),Pos.at<float>(1), Pos.at<float>(2)));
  79. mvKeyPointIndices.push_back(i);
  80. mvAllIndices.push_back(idx);
  81. idx++;
  82. }
  83. }
  84. }
  85. // Set camera calibration parameters
  86. fu = F.fx;
  87. fv = F.fy;
  88. uc = F.cx;
  89. vc = F.cy;
  90. SetRansacParameters();
  91. }
  92. PnPsolver::~PnPsolver()
  93. {
  94. delete [] pws;
  95. delete [] us;
  96. delete [] alphas;
  97. delete [] pcs;
  98. }
  99. void PnPsolver::SetRansacParameters(double probability, int minInliers, int maxIterations, int minSet, float epsilon, float th2)
  100. {
  101. mRansacProb = probability;
  102. mRansacMinInliers = minInliers;
  103. mRansacMaxIts = maxIterations;
  104. mRansacEpsilon = epsilon;
  105. mRansacMinSet = minSet;
  106. N = mvP2D.size(); // number of correspondences
  107. mvbInliersi.resize(N);
  108. // Adjust Parameters according to number of correspondences
  109. int nMinInliers = N*mRansacEpsilon;
  110. if(nMinInliers<mRansacMinInliers)
  111. nMinInliers=mRansacMinInliers;
  112. if(nMinInliers<minSet)
  113. nMinInliers=minSet;
  114. mRansacMinInliers = nMinInliers;
  115. if(mRansacEpsilon<(float)mRansacMinInliers/N)
  116. mRansacEpsilon=(float)mRansacMinInliers/N;
  117. // Set RANSAC iterations according to probability, epsilon, and max iterations
  118. int nIterations;
  119. if(mRansacMinInliers==N)
  120. nIterations=1;
  121. else
  122. nIterations = ceil(log(1-mRansacProb)/log(1-pow(mRansacEpsilon,3)));
  123. mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts));
  124. mvMaxError.resize(mvSigma2.size());
  125. for(size_t i=0; i<mvSigma2.size(); i++)
  126. mvMaxError[i] = mvSigma2[i]*th2;
  127. }
  128. cv::Mat PnPsolver::find(vector<bool> &vbInliers, int &nInliers)
  129. {
  130. bool bFlag;
  131. return iterate(mRansacMaxIts,bFlag,vbInliers,nInliers);
  132. }
  133. cv::Mat PnPsolver::iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers)
  134. {
  135. bNoMore = false;
  136. vbInliers.clear();
  137. nInliers=0;
  138. set_maximum_number_of_correspondences(mRansacMinSet);
  139. if(N<mRansacMinInliers)
  140. {
  141. bNoMore = true;
  142. return cv::Mat();
  143. }
  144. vector<size_t> vAvailableIndices;
  145. int nCurrentIterations = 0;
  146. while(mnIterations<mRansacMaxIts || nCurrentIterations<nIterations)
  147. {
  148. nCurrentIterations++;
  149. mnIterations++;
  150. reset_correspondences();
  151. vAvailableIndices = mvAllIndices;
  152. // Get min set of points
  153. for(short i = 0; i < mRansacMinSet; ++i)
  154. {
  155. int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1);
  156. int idx = vAvailableIndices[randi];
  157. add_correspondence(mvP3Dw[idx].x,mvP3Dw[idx].y,mvP3Dw[idx].z,mvP2D[idx].x,mvP2D[idx].y);
  158. vAvailableIndices[randi] = vAvailableIndices.back();
  159. vAvailableIndices.pop_back();
  160. }
  161. // Compute camera pose
  162. compute_pose(mRi, mti);
  163. // Check inliers
  164. CheckInliers();
  165. if(mnInliersi>=mRansacMinInliers)
  166. {
  167. // If it is the best solution so far, save it
  168. if(mnInliersi>mnBestInliers)
  169. {
  170. mvbBestInliers = mvbInliersi;
  171. mnBestInliers = mnInliersi;
  172. cv::Mat Rcw(3,3,CV_64F,mRi);
  173. cv::Mat tcw(3,1,CV_64F,mti);
  174. Rcw.convertTo(Rcw,CV_32F);
  175. tcw.convertTo(tcw,CV_32F);
  176. mBestTcw = cv::Mat::eye(4,4,CV_32F);
  177. Rcw.copyTo(mBestTcw.rowRange(0,3).colRange(0,3));
  178. tcw.copyTo(mBestTcw.rowRange(0,3).col(3));
  179. }
  180. if(Refine())
  181. {
  182. nInliers = mnRefinedInliers;
  183. vbInliers = vector<bool>(mvpMapPointMatches.size(),false);
  184. for(int i=0; i<N; i++)
  185. {
  186. if(mvbRefinedInliers[i])
  187. vbInliers[mvKeyPointIndices[i]] = true;
  188. }
  189. return mRefinedTcw.clone();
  190. }
  191. }
  192. }
  193. if(mnIterations>=mRansacMaxIts)
  194. {
  195. bNoMore=true;
  196. if(mnBestInliers>=mRansacMinInliers)
  197. {
  198. nInliers=mnBestInliers;
  199. vbInliers = vector<bool>(mvpMapPointMatches.size(),false);
  200. for(int i=0; i<N; i++)
  201. {
  202. if(mvbBestInliers[i])
  203. vbInliers[mvKeyPointIndices[i]] = true;
  204. }
  205. return mBestTcw.clone();
  206. }
  207. }
  208. return cv::Mat();
  209. }
  210. bool PnPsolver::Refine()
  211. {
  212. vector<int> vIndices;
  213. vIndices.reserve(mvbBestInliers.size());
  214. for(size_t i=0; i<mvbBestInliers.size(); i++)
  215. {
  216. if(mvbBestInliers[i])
  217. {
  218. vIndices.push_back(i);
  219. }
  220. }
  221. set_maximum_number_of_correspondences(vIndices.size());
  222. reset_correspondences();
  223. for(size_t i=0; i<vIndices.size(); i++)
  224. {
  225. int idx = vIndices[i];
  226. add_correspondence(mvP3Dw[idx].x,mvP3Dw[idx].y,mvP3Dw[idx].z,mvP2D[idx].x,mvP2D[idx].y);
  227. }
  228. // Compute camera pose
  229. compute_pose(mRi, mti);
  230. // Check inliers
  231. CheckInliers();
  232. mnRefinedInliers =mnInliersi;
  233. mvbRefinedInliers = mvbInliersi;
  234. if(mnInliersi>mRansacMinInliers)
  235. {
  236. cv::Mat Rcw(3,3,CV_64F,mRi);
  237. cv::Mat tcw(3,1,CV_64F,mti);
  238. Rcw.convertTo(Rcw,CV_32F);
  239. tcw.convertTo(tcw,CV_32F);
  240. mRefinedTcw = cv::Mat::eye(4,4,CV_32F);
  241. Rcw.copyTo(mRefinedTcw.rowRange(0,3).colRange(0,3));
  242. tcw.copyTo(mRefinedTcw.rowRange(0,3).col(3));
  243. return true;
  244. }
  245. return false;
  246. }
  247. void PnPsolver::CheckInliers()
  248. {
  249. mnInliersi=0;
  250. for(int i=0; i<N; i++)
  251. {
  252. cv::Point3f P3Dw = mvP3Dw[i];
  253. cv::Point2f P2D = mvP2D[i];
  254. float Xc = mRi[0][0]*P3Dw.x+mRi[0][1]*P3Dw.y+mRi[0][2]*P3Dw.z+mti[0];
  255. float Yc = mRi[1][0]*P3Dw.x+mRi[1][1]*P3Dw.y+mRi[1][2]*P3Dw.z+mti[1];
  256. float invZc = 1/(mRi[2][0]*P3Dw.x+mRi[2][1]*P3Dw.y+mRi[2][2]*P3Dw.z+mti[2]);
  257. double ue = uc + fu * Xc * invZc;
  258. double ve = vc + fv * Yc * invZc;
  259. float distX = P2D.x-ue;
  260. float distY = P2D.y-ve;
  261. float error2 = distX*distX+distY*distY;
  262. if(error2<mvMaxError[i])
  263. {
  264. mvbInliersi[i]=true;
  265. mnInliersi++;
  266. }
  267. else
  268. {
  269. mvbInliersi[i]=false;
  270. }
  271. }
  272. }
  273. void PnPsolver::set_maximum_number_of_correspondences(int n)
  274. {
  275. if (maximum_number_of_correspondences < n) {
  276. if (pws != 0) delete [] pws;
  277. if (us != 0) delete [] us;
  278. if (alphas != 0) delete [] alphas;
  279. if (pcs != 0) delete [] pcs;
  280. maximum_number_of_correspondences = n;
  281. pws = new double[3 * maximum_number_of_correspondences];
  282. us = new double[2 * maximum_number_of_correspondences];
  283. alphas = new double[4 * maximum_number_of_correspondences];
  284. pcs = new double[3 * maximum_number_of_correspondences];
  285. }
  286. }
  287. void PnPsolver::reset_correspondences(void)
  288. {
  289. number_of_correspondences = 0;
  290. }
  291. void PnPsolver::add_correspondence(double X, double Y, double Z, double u, double v)
  292. {
  293. pws[3 * number_of_correspondences ] = X;
  294. pws[3 * number_of_correspondences + 1] = Y;
  295. pws[3 * number_of_correspondences + 2] = Z;
  296. us[2 * number_of_correspondences ] = u;
  297. us[2 * number_of_correspondences + 1] = v;
  298. number_of_correspondences++;
  299. }
  300. void PnPsolver::choose_control_points(void)
  301. {
  302. // Take C0 as the reference points centroid:
  303. cws[0][0] = cws[0][1] = cws[0][2] = 0;
  304. for(int i = 0; i < number_of_correspondences; i++)
  305. for(int j = 0; j < 3; j++)
  306. cws[0][j] += pws[3 * i + j];
  307. for(int j = 0; j < 3; j++)
  308. cws[0][j] /= number_of_correspondences;
  309. // Take C1, C2, and C3 from PCA on the reference points:
  310. CvMat * PW0 = cvCreateMat(number_of_correspondences, 3, CV_64F);
  311. double pw0tpw0[3 * 3], dc[3], uct[3 * 3];
  312. CvMat PW0tPW0 = cvMat(3, 3, CV_64F, pw0tpw0);
  313. CvMat DC = cvMat(3, 1, CV_64F, dc);
  314. CvMat UCt = cvMat(3, 3, CV_64F, uct);
  315. for(int i = 0; i < number_of_correspondences; i++)
  316. for(int j = 0; j < 3; j++)
  317. PW0->data.db[3 * i + j] = pws[3 * i + j] - cws[0][j];
  318. cvMulTransposed(PW0, &PW0tPW0, 1);
  319. cvSVD(&PW0tPW0, &DC, &UCt, 0, CV_SVD_MODIFY_A | CV_SVD_U_T);
  320. cvReleaseMat(&PW0);
  321. for(int i = 1; i < 4; i++) {
  322. double k = sqrt(dc[i - 1] / number_of_correspondences);
  323. for(int j = 0; j < 3; j++)
  324. cws[i][j] = cws[0][j] + k * uct[3 * (i - 1) + j];
  325. }
  326. }
  327. void PnPsolver::compute_barycentric_coordinates(void)
  328. {
  329. double cc[3 * 3], cc_inv[3 * 3];
  330. CvMat CC = cvMat(3, 3, CV_64F, cc);
  331. CvMat CC_inv = cvMat(3, 3, CV_64F, cc_inv);
  332. for(int i = 0; i < 3; i++)
  333. for(int j = 1; j < 4; j++)
  334. cc[3 * i + j - 1] = cws[j][i] - cws[0][i];
  335. cvInvert(&CC, &CC_inv, CV_SVD);
  336. double * ci = cc_inv;
  337. for(int i = 0; i < number_of_correspondences; i++) {
  338. double * pi = pws + 3 * i;
  339. double * a = alphas + 4 * i;
  340. for(int j = 0; j < 3; j++)
  341. a[1 + j] =
  342. ci[3 * j ] * (pi[0] - cws[0][0]) +
  343. ci[3 * j + 1] * (pi[1] - cws[0][1]) +
  344. ci[3 * j + 2] * (pi[2] - cws[0][2]);
  345. a[0] = 1.0f - a[1] - a[2] - a[3];
  346. }
  347. }
  348. void PnPsolver::fill_M(CvMat * M,
  349. const int row, const double * as, const double u, const double v)
  350. {
  351. double * M1 = M->data.db + row * 12;
  352. double * M2 = M1 + 12;
  353. for(int i = 0; i < 4; i++) {
  354. M1[3 * i ] = as[i] * fu;
  355. M1[3 * i + 1] = 0.0;
  356. M1[3 * i + 2] = as[i] * (uc - u);
  357. M2[3 * i ] = 0.0;
  358. M2[3 * i + 1] = as[i] * fv;
  359. M2[3 * i + 2] = as[i] * (vc - v);
  360. }
  361. }
  362. void PnPsolver::compute_ccs(const double * betas, const double * ut)
  363. {
  364. for(int i = 0; i < 4; i++)
  365. ccs[i][0] = ccs[i][1] = ccs[i][2] = 0.0f;
  366. for(int i = 0; i < 4; i++) {
  367. const double * v = ut + 12 * (11 - i);
  368. for(int j = 0; j < 4; j++)
  369. for(int k = 0; k < 3; k++)
  370. ccs[j][k] += betas[i] * v[3 * j + k];
  371. }
  372. }
  373. void PnPsolver::compute_pcs(void)
  374. {
  375. for(int i = 0; i < number_of_correspondences; i++) {
  376. double * a = alphas + 4 * i;
  377. double * pc = pcs + 3 * i;
  378. for(int j = 0; j < 3; j++)
  379. pc[j] = a[0] * ccs[0][j] + a[1] * ccs[1][j] + a[2] * ccs[2][j] + a[3] * ccs[3][j];
  380. }
  381. }
  382. double PnPsolver::compute_pose(double R[3][3], double t[3])
  383. {
  384. choose_control_points();
  385. compute_barycentric_coordinates();
  386. CvMat * M = cvCreateMat(2 * number_of_correspondences, 12, CV_64F);
  387. for(int i = 0; i < number_of_correspondences; i++)
  388. fill_M(M, 2 * i, alphas + 4 * i, us[2 * i], us[2 * i + 1]);
  389. double mtm[12 * 12], d[12], ut[12 * 12];
  390. CvMat MtM = cvMat(12, 12, CV_64F, mtm);
  391. CvMat D = cvMat(12, 1, CV_64F, d);
  392. CvMat Ut = cvMat(12, 12, CV_64F, ut);
  393. cvMulTransposed(M, &MtM, 1);
  394. cvSVD(&MtM, &D, &Ut, 0, CV_SVD_MODIFY_A | CV_SVD_U_T);
  395. cvReleaseMat(&M);
  396. double l_6x10[6 * 10], rho[6];
  397. CvMat L_6x10 = cvMat(6, 10, CV_64F, l_6x10);
  398. CvMat Rho = cvMat(6, 1, CV_64F, rho);
  399. compute_L_6x10(ut, l_6x10);
  400. compute_rho(rho);
  401. double Betas[4][4], rep_errors[4];
  402. double Rs[4][3][3], ts[4][3];
  403. find_betas_approx_1(&L_6x10, &Rho, Betas[1]);
  404. gauss_newton(&L_6x10, &Rho, Betas[1]);
  405. rep_errors[1] = compute_R_and_t(ut, Betas[1], Rs[1], ts[1]);
  406. find_betas_approx_2(&L_6x10, &Rho, Betas[2]);
  407. gauss_newton(&L_6x10, &Rho, Betas[2]);
  408. rep_errors[2] = compute_R_and_t(ut, Betas[2], Rs[2], ts[2]);
  409. find_betas_approx_3(&L_6x10, &Rho, Betas[3]);
  410. gauss_newton(&L_6x10, &Rho, Betas[3]);
  411. rep_errors[3] = compute_R_and_t(ut, Betas[3], Rs[3], ts[3]);
  412. int N = 1;
  413. if (rep_errors[2] < rep_errors[1]) N = 2;
  414. if (rep_errors[3] < rep_errors[N]) N = 3;
  415. copy_R_and_t(Rs[N], ts[N], R, t);
  416. return rep_errors[N];
  417. }
  418. void PnPsolver::copy_R_and_t(const double R_src[3][3], const double t_src[3],
  419. double R_dst[3][3], double t_dst[3])
  420. {
  421. for(int i = 0; i < 3; i++) {
  422. for(int j = 0; j < 3; j++)
  423. R_dst[i][j] = R_src[i][j];
  424. t_dst[i] = t_src[i];
  425. }
  426. }
  427. double PnPsolver::dist2(const double * p1, const double * p2)
  428. {
  429. return
  430. (p1[0] - p2[0]) * (p1[0] - p2[0]) +
  431. (p1[1] - p2[1]) * (p1[1] - p2[1]) +
  432. (p1[2] - p2[2]) * (p1[2] - p2[2]);
  433. }
  434. double PnPsolver::dot(const double * v1, const double * v2)
  435. {
  436. return v1[0] * v2[0] + v1[1] * v2[1] + v1[2] * v2[2];
  437. }
  438. double PnPsolver::reprojection_error(const double R[3][3], const double t[3])
  439. {
  440. double sum2 = 0.0;
  441. for(int i = 0; i < number_of_correspondences; i++) {
  442. double * pw = pws + 3 * i;
  443. double Xc = dot(R[0], pw) + t[0];
  444. double Yc = dot(R[1], pw) + t[1];
  445. double inv_Zc = 1.0 / (dot(R[2], pw) + t[2]);
  446. double ue = uc + fu * Xc * inv_Zc;
  447. double ve = vc + fv * Yc * inv_Zc;
  448. double u = us[2 * i], v = us[2 * i + 1];
  449. sum2 += sqrt( (u - ue) * (u - ue) + (v - ve) * (v - ve) );
  450. }
  451. return sum2 / number_of_correspondences;
  452. }
  453. void PnPsolver::estimate_R_and_t(double R[3][3], double t[3])
  454. {
  455. double pc0[3], pw0[3];
  456. pc0[0] = pc0[1] = pc0[2] = 0.0;
  457. pw0[0] = pw0[1] = pw0[2] = 0.0;
  458. for(int i = 0; i < number_of_correspondences; i++) {
  459. const double * pc = pcs + 3 * i;
  460. const double * pw = pws + 3 * i;
  461. for(int j = 0; j < 3; j++) {
  462. pc0[j] += pc[j];
  463. pw0[j] += pw[j];
  464. }
  465. }
  466. for(int j = 0; j < 3; j++) {
  467. pc0[j] /= number_of_correspondences;
  468. pw0[j] /= number_of_correspondences;
  469. }
  470. double abt[3 * 3], abt_d[3], abt_u[3 * 3], abt_v[3 * 3];
  471. CvMat ABt = cvMat(3, 3, CV_64F, abt);
  472. CvMat ABt_D = cvMat(3, 1, CV_64F, abt_d);
  473. CvMat ABt_U = cvMat(3, 3, CV_64F, abt_u);
  474. CvMat ABt_V = cvMat(3, 3, CV_64F, abt_v);
  475. cvSetZero(&ABt);
  476. for(int i = 0; i < number_of_correspondences; i++) {
  477. double * pc = pcs + 3 * i;
  478. double * pw = pws + 3 * i;
  479. for(int j = 0; j < 3; j++) {
  480. abt[3 * j ] += (pc[j] - pc0[j]) * (pw[0] - pw0[0]);
  481. abt[3 * j + 1] += (pc[j] - pc0[j]) * (pw[1] - pw0[1]);
  482. abt[3 * j + 2] += (pc[j] - pc0[j]) * (pw[2] - pw0[2]);
  483. }
  484. }
  485. cvSVD(&ABt, &ABt_D, &ABt_U, &ABt_V, CV_SVD_MODIFY_A);
  486. for(int i = 0; i < 3; i++)
  487. for(int j = 0; j < 3; j++)
  488. R[i][j] = dot(abt_u + 3 * i, abt_v + 3 * j);
  489. const double det =
  490. R[0][0] * R[1][1] * R[2][2] + R[0][1] * R[1][2] * R[2][0] + R[0][2] * R[1][0] * R[2][1] -
  491. R[0][2] * R[1][1] * R[2][0] - R[0][1] * R[1][0] * R[2][2] - R[0][0] * R[1][2] * R[2][1];
  492. if (det < 0) {
  493. R[2][0] = -R[2][0];
  494. R[2][1] = -R[2][1];
  495. R[2][2] = -R[2][2];
  496. }
  497. t[0] = pc0[0] - dot(R[0], pw0);
  498. t[1] = pc0[1] - dot(R[1], pw0);
  499. t[2] = pc0[2] - dot(R[2], pw0);
  500. }
  501. void PnPsolver::print_pose(const double R[3][3], const double t[3])
  502. {
  503. cout << R[0][0] << " " << R[0][1] << " " << R[0][2] << " " << t[0] << endl;
  504. cout << R[1][0] << " " << R[1][1] << " " << R[1][2] << " " << t[1] << endl;
  505. cout << R[2][0] << " " << R[2][1] << " " << R[2][2] << " " << t[2] << endl;
  506. }
  507. void PnPsolver::solve_for_sign(void)
  508. {
  509. if (pcs[2] < 0.0) {
  510. for(int i = 0; i < 4; i++)
  511. for(int j = 0; j < 3; j++)
  512. ccs[i][j] = -ccs[i][j];
  513. for(int i = 0; i < number_of_correspondences; i++) {
  514. pcs[3 * i ] = -pcs[3 * i];
  515. pcs[3 * i + 1] = -pcs[3 * i + 1];
  516. pcs[3 * i + 2] = -pcs[3 * i + 2];
  517. }
  518. }
  519. }
  520. double PnPsolver::compute_R_and_t(const double * ut, const double * betas,
  521. double R[3][3], double t[3])
  522. {
  523. compute_ccs(betas, ut);
  524. compute_pcs();
  525. solve_for_sign();
  526. estimate_R_and_t(R, t);
  527. return reprojection_error(R, t);
  528. }
  529. // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
  530. // betas_approx_1 = [B11 B12 B13 B14]
  531. void PnPsolver::find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho,
  532. double * betas)
  533. {
  534. double l_6x4[6 * 4], b4[4];
  535. CvMat L_6x4 = cvMat(6, 4, CV_64F, l_6x4);
  536. CvMat B4 = cvMat(4, 1, CV_64F, b4);
  537. for(int i = 0; i < 6; i++) {
  538. cvmSet(&L_6x4, i, 0, cvmGet(L_6x10, i, 0));
  539. cvmSet(&L_6x4, i, 1, cvmGet(L_6x10, i, 1));
  540. cvmSet(&L_6x4, i, 2, cvmGet(L_6x10, i, 3));
  541. cvmSet(&L_6x4, i, 3, cvmGet(L_6x10, i, 6));
  542. }
  543. cvSolve(&L_6x4, Rho, &B4, CV_SVD);
  544. if (b4[0] < 0) {
  545. betas[0] = sqrt(-b4[0]);
  546. betas[1] = -b4[1] / betas[0];
  547. betas[2] = -b4[2] / betas[0];
  548. betas[3] = -b4[3] / betas[0];
  549. } else {
  550. betas[0] = sqrt(b4[0]);
  551. betas[1] = b4[1] / betas[0];
  552. betas[2] = b4[2] / betas[0];
  553. betas[3] = b4[3] / betas[0];
  554. }
  555. }
  556. // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
  557. // betas_approx_2 = [B11 B12 B22 ]
  558. void PnPsolver::find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho,
  559. double * betas)
  560. {
  561. double l_6x3[6 * 3], b3[3];
  562. CvMat L_6x3 = cvMat(6, 3, CV_64F, l_6x3);
  563. CvMat B3 = cvMat(3, 1, CV_64F, b3);
  564. for(int i = 0; i < 6; i++) {
  565. cvmSet(&L_6x3, i, 0, cvmGet(L_6x10, i, 0));
  566. cvmSet(&L_6x3, i, 1, cvmGet(L_6x10, i, 1));
  567. cvmSet(&L_6x3, i, 2, cvmGet(L_6x10, i, 2));
  568. }
  569. cvSolve(&L_6x3, Rho, &B3, CV_SVD);
  570. if (b3[0] < 0) {
  571. betas[0] = sqrt(-b3[0]);
  572. betas[1] = (b3[2] < 0) ? sqrt(-b3[2]) : 0.0;
  573. } else {
  574. betas[0] = sqrt(b3[0]);
  575. betas[1] = (b3[2] > 0) ? sqrt(b3[2]) : 0.0;
  576. }
  577. if (b3[1] < 0) betas[0] = -betas[0];
  578. betas[2] = 0.0;
  579. betas[3] = 0.0;
  580. }
  581. // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
  582. // betas_approx_3 = [B11 B12 B22 B13 B23 ]
  583. void PnPsolver::find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho,
  584. double * betas)
  585. {
  586. double l_6x5[6 * 5], b5[5];
  587. CvMat L_6x5 = cvMat(6, 5, CV_64F, l_6x5);
  588. CvMat B5 = cvMat(5, 1, CV_64F, b5);
  589. for(int i = 0; i < 6; i++) {
  590. cvmSet(&L_6x5, i, 0, cvmGet(L_6x10, i, 0));
  591. cvmSet(&L_6x5, i, 1, cvmGet(L_6x10, i, 1));
  592. cvmSet(&L_6x5, i, 2, cvmGet(L_6x10, i, 2));
  593. cvmSet(&L_6x5, i, 3, cvmGet(L_6x10, i, 3));
  594. cvmSet(&L_6x5, i, 4, cvmGet(L_6x10, i, 4));
  595. }
  596. cvSolve(&L_6x5, Rho, &B5, CV_SVD);
  597. if (b5[0] < 0) {
  598. betas[0] = sqrt(-b5[0]);
  599. betas[1] = (b5[2] < 0) ? sqrt(-b5[2]) : 0.0;
  600. } else {
  601. betas[0] = sqrt(b5[0]);
  602. betas[1] = (b5[2] > 0) ? sqrt(b5[2]) : 0.0;
  603. }
  604. if (b5[1] < 0) betas[0] = -betas[0];
  605. betas[2] = b5[3] / betas[0];
  606. betas[3] = 0.0;
  607. }
  608. void PnPsolver::compute_L_6x10(const double * ut, double * l_6x10)
  609. {
  610. const double * v[4];
  611. v[0] = ut + 12 * 11;
  612. v[1] = ut + 12 * 10;
  613. v[2] = ut + 12 * 9;
  614. v[3] = ut + 12 * 8;
  615. double dv[4][6][3];
  616. for(int i = 0; i < 4; i++) {
  617. int a = 0, b = 1;
  618. for(int j = 0; j < 6; j++) {
  619. dv[i][j][0] = v[i][3 * a ] - v[i][3 * b];
  620. dv[i][j][1] = v[i][3 * a + 1] - v[i][3 * b + 1];
  621. dv[i][j][2] = v[i][3 * a + 2] - v[i][3 * b + 2];
  622. b++;
  623. if (b > 3) {
  624. a++;
  625. b = a + 1;
  626. }
  627. }
  628. }
  629. for(int i = 0; i < 6; i++) {
  630. double * row = l_6x10 + 10 * i;
  631. row[0] = dot(dv[0][i], dv[0][i]);
  632. row[1] = 2.0f * dot(dv[0][i], dv[1][i]);
  633. row[2] = dot(dv[1][i], dv[1][i]);
  634. row[3] = 2.0f * dot(dv[0][i], dv[2][i]);
  635. row[4] = 2.0f * dot(dv[1][i], dv[2][i]);
  636. row[5] = dot(dv[2][i], dv[2][i]);
  637. row[6] = 2.0f * dot(dv[0][i], dv[3][i]);
  638. row[7] = 2.0f * dot(dv[1][i], dv[3][i]);
  639. row[8] = 2.0f * dot(dv[2][i], dv[3][i]);
  640. row[9] = dot(dv[3][i], dv[3][i]);
  641. }
  642. }
  643. void PnPsolver::compute_rho(double * rho)
  644. {
  645. rho[0] = dist2(cws[0], cws[1]);
  646. rho[1] = dist2(cws[0], cws[2]);
  647. rho[2] = dist2(cws[0], cws[3]);
  648. rho[3] = dist2(cws[1], cws[2]);
  649. rho[4] = dist2(cws[1], cws[3]);
  650. rho[5] = dist2(cws[2], cws[3]);
  651. }
  652. void PnPsolver::compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho,
  653. double betas[4], CvMat * A, CvMat * b)
  654. {
  655. for(int i = 0; i < 6; i++) {
  656. const double * rowL = l_6x10 + i * 10;
  657. double * rowA = A->data.db + i * 4;
  658. rowA[0] = 2 * rowL[0] * betas[0] + rowL[1] * betas[1] + rowL[3] * betas[2] + rowL[6] * betas[3];
  659. rowA[1] = rowL[1] * betas[0] + 2 * rowL[2] * betas[1] + rowL[4] * betas[2] + rowL[7] * betas[3];
  660. rowA[2] = rowL[3] * betas[0] + rowL[4] * betas[1] + 2 * rowL[5] * betas[2] + rowL[8] * betas[3];
  661. rowA[3] = rowL[6] * betas[0] + rowL[7] * betas[1] + rowL[8] * betas[2] + 2 * rowL[9] * betas[3];
  662. cvmSet(b, i, 0, rho[i] -
  663. (
  664. rowL[0] * betas[0] * betas[0] +
  665. rowL[1] * betas[0] * betas[1] +
  666. rowL[2] * betas[1] * betas[1] +
  667. rowL[3] * betas[0] * betas[2] +
  668. rowL[4] * betas[1] * betas[2] +
  669. rowL[5] * betas[2] * betas[2] +
  670. rowL[6] * betas[0] * betas[3] +
  671. rowL[7] * betas[1] * betas[3] +
  672. rowL[8] * betas[2] * betas[3] +
  673. rowL[9] * betas[3] * betas[3]
  674. ));
  675. }
  676. }
  677. void PnPsolver::gauss_newton(const CvMat * L_6x10, const CvMat * Rho,
  678. double betas[4])
  679. {
  680. const int iterations_number = 5;
  681. double a[6*4], b[6], x[4];
  682. CvMat A = cvMat(6, 4, CV_64F, a);
  683. CvMat B = cvMat(6, 1, CV_64F, b);
  684. CvMat X = cvMat(4, 1, CV_64F, x);
  685. for(int k = 0; k < iterations_number; k++) {
  686. compute_A_and_b_gauss_newton(L_6x10->data.db, Rho->data.db,
  687. betas, &A, &B);
  688. qr_solve(&A, &B, &X);
  689. for(int i = 0; i < 4; i++)
  690. betas[i] += x[i];
  691. }
  692. }
  693. void PnPsolver::qr_solve(CvMat * A, CvMat * b, CvMat * X)
  694. {
  695. static int max_nr = 0;
  696. static double * A1, * A2;
  697. const int nr = A->rows;
  698. const int nc = A->cols;
  699. if (max_nr != 0 && max_nr < nr) {
  700. delete [] A1;
  701. delete [] A2;
  702. }
  703. if (max_nr < nr) {
  704. max_nr = nr;
  705. A1 = new double[nr];
  706. A2 = new double[nr];
  707. }
  708. double * pA = A->data.db, * ppAkk = pA;
  709. for(int k = 0; k < nc; k++) {
  710. double * ppAik = ppAkk, eta = fabs(*ppAik);
  711. for(int i = k + 1; i < nr; i++) {
  712. double elt = fabs(*ppAik);
  713. if (eta < elt) eta = elt;
  714. ppAik += nc;
  715. }
  716. if (eta == 0) {
  717. A1[k] = A2[k] = 0.0;
  718. cerr << "God damnit, A is singular, this shouldn't happen." << endl;
  719. return;
  720. } else {
  721. double * ppAik = ppAkk, sum = 0.0, inv_eta = 1. / eta;
  722. for(int i = k; i < nr; i++) {
  723. *ppAik *= inv_eta;
  724. sum += *ppAik * *ppAik;
  725. ppAik += nc;
  726. }
  727. double sigma = sqrt(sum);
  728. if (*ppAkk < 0)
  729. sigma = -sigma;
  730. *ppAkk += sigma;
  731. A1[k] = sigma * *ppAkk;
  732. A2[k] = -eta * sigma;
  733. for(int j = k + 1; j < nc; j++) {
  734. double * ppAik = ppAkk, sum = 0;
  735. for(int i = k; i < nr; i++) {
  736. sum += *ppAik * ppAik[j - k];
  737. ppAik += nc;
  738. }
  739. double tau = sum / A1[k];
  740. ppAik = ppAkk;
  741. for(int i = k; i < nr; i++) {
  742. ppAik[j - k] -= tau * *ppAik;
  743. ppAik += nc;
  744. }
  745. }
  746. }
  747. ppAkk += nc + 1;
  748. }
  749. // b <- Qt b
  750. double * ppAjj = pA, * pb = b->data.db;
  751. for(int j = 0; j < nc; j++) {
  752. double * ppAij = ppAjj, tau = 0;
  753. for(int i = j; i < nr; i++) {
  754. tau += *ppAij * pb[i];
  755. ppAij += nc;
  756. }
  757. tau /= A1[j];
  758. ppAij = ppAjj;
  759. for(int i = j; i < nr; i++) {
  760. pb[i] -= tau * *ppAij;
  761. ppAij += nc;
  762. }
  763. ppAjj += nc + 1;
  764. }
  765. // X = R-1 b
  766. double * pX = X->data.db;
  767. pX[nc - 1] = pb[nc - 1] / A2[nc - 1];
  768. for(int i = nc - 2; i >= 0; i--) {
  769. double * ppAij = pA + i * nc + (i + 1), sum = 0;
  770. for(int j = i + 1; j < nc; j++) {
  771. sum += *ppAij * pX[j];
  772. ppAij++;
  773. }
  774. pX[i] = (pb[i] - sum) / A2[i];
  775. }
  776. }
  777. void PnPsolver::relative_error(double & rot_err, double & transl_err,
  778. const double Rtrue[3][3], const double ttrue[3],
  779. const double Rest[3][3], const double test[3])
  780. {
  781. double qtrue[4], qest[4];
  782. mat_to_quat(Rtrue, qtrue);
  783. mat_to_quat(Rest, qest);
  784. double rot_err1 = sqrt((qtrue[0] - qest[0]) * (qtrue[0] - qest[0]) +
  785. (qtrue[1] - qest[1]) * (qtrue[1] - qest[1]) +
  786. (qtrue[2] - qest[2]) * (qtrue[2] - qest[2]) +
  787. (qtrue[3] - qest[3]) * (qtrue[3] - qest[3]) ) /
  788. sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]);
  789. double rot_err2 = sqrt((qtrue[0] + qest[0]) * (qtrue[0] + qest[0]) +
  790. (qtrue[1] + qest[1]) * (qtrue[1] + qest[1]) +
  791. (qtrue[2] + qest[2]) * (qtrue[2] + qest[2]) +
  792. (qtrue[3] + qest[3]) * (qtrue[3] + qest[3]) ) /
  793. sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]);
  794. rot_err = min(rot_err1, rot_err2);
  795. transl_err =
  796. sqrt((ttrue[0] - test[0]) * (ttrue[0] - test[0]) +
  797. (ttrue[1] - test[1]) * (ttrue[1] - test[1]) +
  798. (ttrue[2] - test[2]) * (ttrue[2] - test[2])) /
  799. sqrt(ttrue[0] * ttrue[0] + ttrue[1] * ttrue[1] + ttrue[2] * ttrue[2]);
  800. }
  801. void PnPsolver::mat_to_quat(const double R[3][3], double q[4])
  802. {
  803. double tr = R[0][0] + R[1][1] + R[2][2];
  804. double n4;
  805. if (tr > 0.0f) {
  806. q[0] = R[1][2] - R[2][1];
  807. q[1] = R[2][0] - R[0][2];
  808. q[2] = R[0][1] - R[1][0];
  809. q[3] = tr + 1.0f;
  810. n4 = q[3];
  811. } else if ( (R[0][0] > R[1][1]) && (R[0][0] > R[2][2]) ) {
  812. q[0] = 1.0f + R[0][0] - R[1][1] - R[2][2];
  813. q[1] = R[1][0] + R[0][1];
  814. q[2] = R[2][0] + R[0][2];
  815. q[3] = R[1][2] - R[2][1];
  816. n4 = q[0];
  817. } else if (R[1][1] > R[2][2]) {
  818. q[0] = R[1][0] + R[0][1];
  819. q[1] = 1.0f + R[1][1] - R[0][0] - R[2][2];
  820. q[2] = R[2][1] + R[1][2];
  821. q[3] = R[2][0] - R[0][2];
  822. n4 = q[1];
  823. } else {
  824. q[0] = R[2][0] + R[0][2];
  825. q[1] = R[2][1] + R[1][2];
  826. q[2] = 1.0f + R[2][2] - R[0][0] - R[1][1];
  827. q[3] = R[0][1] - R[1][0];
  828. n4 = q[2];
  829. }
  830. double scale = 0.5f / double(sqrt(n4));
  831. q[0] *= scale;
  832. q[1] *= scale;
  833. q[2] *= scale;
  834. q[3] *= scale;
  835. }
  836. } //namespace ORB_SLAM