PnPsolver.cc
Go to the documentation of this file.
1 
51 #include <iostream>
52 
53 #include "PnPsolver.h"
54 
55 #include <vector>
56 #include <cmath>
57 #include <opencv2/core/core.hpp>
59 #include <algorithm>
60 
61 using namespace std;
62 
63 namespace ORB_SLAM2
64 {
65 
66 
67 PnPsolver::PnPsolver(const Frame &F, const vector<MapPoint*> &vpMapPointMatches):
68  pws(0), us(0), alphas(0), pcs(0), maximum_number_of_correspondences(0), number_of_correspondences(0), mnInliersi(0),
69  mnIterations(0), mnBestInliers(0), N(0)
70 {
71  mvpMapPointMatches = vpMapPointMatches;
72  mvP2D.reserve(F.mvpMapPoints.size());
73  mvSigma2.reserve(F.mvpMapPoints.size());
74  mvP3Dw.reserve(F.mvpMapPoints.size());
75  mvKeyPointIndices.reserve(F.mvpMapPoints.size());
76  mvAllIndices.reserve(F.mvpMapPoints.size());
77 
78  int idx=0;
79  for(size_t i=0, iend=vpMapPointMatches.size(); i<iend; i++)
80  {
81  MapPoint* pMP = vpMapPointMatches[i];
82 
83  if(pMP)
84  {
85  if(!pMP->isBad())
86  {
87  const cv::KeyPoint &kp = F.mvKeysUn[i];
88 
89  mvP2D.push_back(kp.pt);
90  mvSigma2.push_back(F.mvLevelSigma2[kp.octave]);
91 
92  cv::Mat Pos = pMP->GetWorldPos();
93  mvP3Dw.push_back(cv::Point3f(Pos.at<float>(0),Pos.at<float>(1), Pos.at<float>(2)));
94 
95  mvKeyPointIndices.push_back(i);
96  mvAllIndices.push_back(idx);
97 
98  idx++;
99  }
100  }
101  }
102 
103  // Set camera calibration parameters
104  fu = F.fx;
105  fv = F.fy;
106  uc = F.cx;
107  vc = F.cy;
108 
110 }
111 
113 {
114  delete [] pws;
115  delete [] us;
116  delete [] alphas;
117  delete [] pcs;
118 }
119 
120 
121 void PnPsolver::SetRansacParameters(double probability, int minInliers, int maxIterations, int minSet, float epsilon, float th2)
122 {
123  mRansacProb = probability;
124  mRansacMinInliers = minInliers;
125  mRansacMaxIts = maxIterations;
126  mRansacEpsilon = epsilon;
127  mRansacMinSet = minSet;
128 
129  N = mvP2D.size(); // number of correspondences
130 
131  mvbInliersi.resize(N);
132 
133  // Adjust Parameters according to number of correspondences
134  int nMinInliers = N*mRansacEpsilon;
135  if(nMinInliers<mRansacMinInliers)
136  nMinInliers=mRansacMinInliers;
137  if(nMinInliers<minSet)
138  nMinInliers=minSet;
139  mRansacMinInliers = nMinInliers;
140 
141  if(mRansacEpsilon<(float)mRansacMinInliers/N)
142  mRansacEpsilon=(float)mRansacMinInliers/N;
143 
144  // Set RANSAC iterations according to probability, epsilon, and max iterations
145  int nIterations;
146 
147  if(mRansacMinInliers==N)
148  nIterations=1;
149  else
150  nIterations = ceil(log(1-mRansacProb)/log(1-pow(mRansacEpsilon,3)));
151 
152  mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts));
153 
154  mvMaxError.resize(mvSigma2.size());
155  for(size_t i=0; i<mvSigma2.size(); i++)
156  mvMaxError[i] = mvSigma2[i]*th2;
157 }
158 
159 cv::Mat PnPsolver::find(vector<bool> &vbInliers, int &nInliers)
160 {
161  bool bFlag;
162  return iterate(mRansacMaxIts,bFlag,vbInliers,nInliers);
163 }
164 
165 cv::Mat PnPsolver::iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers)
166 {
167  bNoMore = false;
168  vbInliers.clear();
169  nInliers=0;
170 
172 
173  if(N<mRansacMinInliers)
174  {
175  bNoMore = true;
176  return cv::Mat();
177  }
178 
179  vector<size_t> vAvailableIndices;
180 
181  int nCurrentIterations = 0;
182  while(mnIterations<mRansacMaxIts || nCurrentIterations<nIterations)
183  {
184  nCurrentIterations++;
185  mnIterations++;
187 
188  vAvailableIndices = mvAllIndices;
189 
190  // Get min set of points
191  for(short i = 0; i < mRansacMinSet; ++i)
192  {
193  int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1);
194 
195  int idx = vAvailableIndices[randi];
196 
197  add_correspondence(mvP3Dw[idx].x,mvP3Dw[idx].y,mvP3Dw[idx].z,mvP2D[idx].x,mvP2D[idx].y);
198 
199  vAvailableIndices[randi] = vAvailableIndices.back();
200  vAvailableIndices.pop_back();
201  }
202 
203  // Compute camera pose
204  compute_pose(mRi, mti);
205 
206  // Check inliers
207  CheckInliers();
208 
210  {
211  // If it is the best solution so far, save it
213  {
216 
217  cv::Mat Rcw(3,3,CV_64F,mRi);
218  cv::Mat tcw(3,1,CV_64F,mti);
219  Rcw.convertTo(Rcw,CV_32F);
220  tcw.convertTo(tcw,CV_32F);
221  mBestTcw = cv::Mat::eye(4,4,CV_32F);
222  Rcw.copyTo(mBestTcw.rowRange(0,3).colRange(0,3));
223  tcw.copyTo(mBestTcw.rowRange(0,3).col(3));
224  }
225 
226  if(Refine())
227  {
228  nInliers = mnRefinedInliers;
229  vbInliers = vector<bool>(mvpMapPointMatches.size(),false);
230  for(int i=0; i<N; i++)
231  {
232  if(mvbRefinedInliers[i])
233  vbInliers[mvKeyPointIndices[i]] = true;
234  }
235  return mRefinedTcw.clone();
236  }
237 
238  }
239  }
240 
242  {
243  bNoMore=true;
245  {
246  nInliers=mnBestInliers;
247  vbInliers = vector<bool>(mvpMapPointMatches.size(),false);
248  for(int i=0; i<N; i++)
249  {
250  if(mvbBestInliers[i])
251  vbInliers[mvKeyPointIndices[i]] = true;
252  }
253  return mBestTcw.clone();
254  }
255  }
256 
257  return cv::Mat();
258 }
259 
261 {
262  vector<int> vIndices;
263  vIndices.reserve(mvbBestInliers.size());
264 
265  for(size_t i=0; i<mvbBestInliers.size(); i++)
266  {
267  if(mvbBestInliers[i])
268  {
269  vIndices.push_back(i);
270  }
271  }
272 
273  set_maximum_number_of_correspondences(vIndices.size());
274 
276 
277  for(size_t i=0; i<vIndices.size(); i++)
278  {
279  int idx = vIndices[i];
280  add_correspondence(mvP3Dw[idx].x,mvP3Dw[idx].y,mvP3Dw[idx].z,mvP2D[idx].x,mvP2D[idx].y);
281  }
282 
283  // Compute camera pose
284  compute_pose(mRi, mti);
285 
286  // Check inliers
287  CheckInliers();
288 
291 
293  {
294  cv::Mat Rcw(3,3,CV_64F,mRi);
295  cv::Mat tcw(3,1,CV_64F,mti);
296  Rcw.convertTo(Rcw,CV_32F);
297  tcw.convertTo(tcw,CV_32F);
298  mRefinedTcw = cv::Mat::eye(4,4,CV_32F);
299  Rcw.copyTo(mRefinedTcw.rowRange(0,3).colRange(0,3));
300  tcw.copyTo(mRefinedTcw.rowRange(0,3).col(3));
301  return true;
302  }
303 
304  return false;
305 }
306 
307 
309 {
310  mnInliersi=0;
311 
312  for(int i=0; i<N; i++)
313  {
314  cv::Point3f P3Dw = mvP3Dw[i];
315  cv::Point2f P2D = mvP2D[i];
316 
317  float Xc = mRi[0][0]*P3Dw.x+mRi[0][1]*P3Dw.y+mRi[0][2]*P3Dw.z+mti[0];
318  float Yc = mRi[1][0]*P3Dw.x+mRi[1][1]*P3Dw.y+mRi[1][2]*P3Dw.z+mti[1];
319  float invZc = 1/(mRi[2][0]*P3Dw.x+mRi[2][1]*P3Dw.y+mRi[2][2]*P3Dw.z+mti[2]);
320 
321  double ue = uc + fu * Xc * invZc;
322  double ve = vc + fv * Yc * invZc;
323 
324  float distX = P2D.x-ue;
325  float distY = P2D.y-ve;
326 
327  float error2 = distX*distX+distY*distY;
328 
329  if(error2<mvMaxError[i])
330  {
331  mvbInliersi[i]=true;
332  mnInliersi++;
333  }
334  else
335  {
336  mvbInliersi[i]=false;
337  }
338  }
339 }
340 
341 
343 {
345  if (pws != 0) delete [] pws;
346  if (us != 0) delete [] us;
347  if (alphas != 0) delete [] alphas;
348  if (pcs != 0) delete [] pcs;
349 
351  pws = new double[3 * maximum_number_of_correspondences];
352  us = new double[2 * maximum_number_of_correspondences];
353  alphas = new double[4 * maximum_number_of_correspondences];
354  pcs = new double[3 * maximum_number_of_correspondences];
355  }
356 }
357 
359 {
361 }
362 
363 void PnPsolver::add_correspondence(double X, double Y, double Z, double u, double v)
364 {
365  pws[3 * number_of_correspondences ] = X;
366  pws[3 * number_of_correspondences + 1] = Y;
367  pws[3 * number_of_correspondences + 2] = Z;
368 
369  us[2 * number_of_correspondences ] = u;
370  us[2 * number_of_correspondences + 1] = v;
371 
373 }
374 
376 {
377  // Take C0 as the reference points centroid:
378  cws[0][0] = cws[0][1] = cws[0][2] = 0;
379  for(int i = 0; i < number_of_correspondences; i++)
380  for(int j = 0; j < 3; j++)
381  cws[0][j] += pws[3 * i + j];
382 
383  for(int j = 0; j < 3; j++)
384  cws[0][j] /= number_of_correspondences;
385 
386 
387  // Take C1, C2, and C3 from PCA on the reference points:
388  CvMat * PW0 = cvCreateMat(number_of_correspondences, 3, CV_64F);
389 
390  double pw0tpw0[3 * 3], dc[3], uct[3 * 3];
391  CvMat PW0tPW0 = cvMat(3, 3, CV_64F, pw0tpw0);
392  CvMat DC = cvMat(3, 1, CV_64F, dc);
393  CvMat UCt = cvMat(3, 3, CV_64F, uct);
394 
395  for(int i = 0; i < number_of_correspondences; i++)
396  for(int j = 0; j < 3; j++)
397  PW0->data.db[3 * i + j] = pws[3 * i + j] - cws[0][j];
398 
399  cvMulTransposed(PW0, &PW0tPW0, 1);
400  cvSVD(&PW0tPW0, &DC, &UCt, 0, CV_SVD_MODIFY_A | CV_SVD_U_T);
401 
402  cvReleaseMat(&PW0);
403 
404  for(int i = 1; i < 4; i++) {
405  double k = sqrt(dc[i - 1] / number_of_correspondences);
406  for(int j = 0; j < 3; j++)
407  cws[i][j] = cws[0][j] + k * uct[3 * (i - 1) + j];
408  }
409 }
410 
412 {
413  double cc[3 * 3], cc_inv[3 * 3];
414  CvMat CC = cvMat(3, 3, CV_64F, cc);
415  CvMat CC_inv = cvMat(3, 3, CV_64F, cc_inv);
416 
417  for(int i = 0; i < 3; i++)
418  for(int j = 1; j < 4; j++)
419  cc[3 * i + j - 1] = cws[j][i] - cws[0][i];
420 
421  cvInvert(&CC, &CC_inv, CV_SVD);
422  double * ci = cc_inv;
423  for(int i = 0; i < number_of_correspondences; i++) {
424  double * pi = pws + 3 * i;
425  double * a = alphas + 4 * i;
426 
427  for(int j = 0; j < 3; j++)
428  a[1 + j] =
429  ci[3 * j ] * (pi[0] - cws[0][0]) +
430  ci[3 * j + 1] * (pi[1] - cws[0][1]) +
431  ci[3 * j + 2] * (pi[2] - cws[0][2]);
432  a[0] = 1.0f - a[1] - a[2] - a[3];
433  }
434 }
435 
436 void PnPsolver::fill_M(CvMat * M,
437  const int row, const double * as, const double u, const double v)
438 {
439  double * M1 = M->data.db + row * 12;
440  double * M2 = M1 + 12;
441 
442  for(int i = 0; i < 4; i++) {
443  M1[3 * i ] = as[i] * fu;
444  M1[3 * i + 1] = 0.0;
445  M1[3 * i + 2] = as[i] * (uc - u);
446 
447  M2[3 * i ] = 0.0;
448  M2[3 * i + 1] = as[i] * fv;
449  M2[3 * i + 2] = as[i] * (vc - v);
450  }
451 }
452 
453 void PnPsolver::compute_ccs(const double * betas, const double * ut)
454 {
455  for(int i = 0; i < 4; i++)
456  ccs[i][0] = ccs[i][1] = ccs[i][2] = 0.0f;
457 
458  for(int i = 0; i < 4; i++) {
459  const double * v = ut + 12 * (11 - i);
460  for(int j = 0; j < 4; j++)
461  for(int k = 0; k < 3; k++)
462  ccs[j][k] += betas[i] * v[3 * j + k];
463  }
464 }
465 
467 {
468  for(int i = 0; i < number_of_correspondences; i++) {
469  double * a = alphas + 4 * i;
470  double * pc = pcs + 3 * i;
471 
472  for(int j = 0; j < 3; j++)
473  pc[j] = a[0] * ccs[0][j] + a[1] * ccs[1][j] + a[2] * ccs[2][j] + a[3] * ccs[3][j];
474  }
475 }
476 
477 double PnPsolver::compute_pose(double R[3][3], double t[3])
478 {
481 
482  CvMat * M = cvCreateMat(2 * number_of_correspondences, 12, CV_64F);
483 
484  for(int i = 0; i < number_of_correspondences; i++)
485  fill_M(M, 2 * i, alphas + 4 * i, us[2 * i], us[2 * i + 1]);
486 
487  double mtm[12 * 12], d[12], ut[12 * 12];
488  CvMat MtM = cvMat(12, 12, CV_64F, mtm);
489  CvMat D = cvMat(12, 1, CV_64F, d);
490  CvMat Ut = cvMat(12, 12, CV_64F, ut);
491 
492  cvMulTransposed(M, &MtM, 1);
493  cvSVD(&MtM, &D, &Ut, 0, CV_SVD_MODIFY_A | CV_SVD_U_T);
494  cvReleaseMat(&M);
495 
496  double l_6x10[6 * 10], rho[6];
497  CvMat L_6x10 = cvMat(6, 10, CV_64F, l_6x10);
498  CvMat Rho = cvMat(6, 1, CV_64F, rho);
499 
500  compute_L_6x10(ut, l_6x10);
501  compute_rho(rho);
502 
503  double Betas[4][4], rep_errors[4];
504  double Rs[4][3][3], ts[4][3];
505 
506  find_betas_approx_1(&L_6x10, &Rho, Betas[1]);
507  gauss_newton(&L_6x10, &Rho, Betas[1]);
508  rep_errors[1] = compute_R_and_t(ut, Betas[1], Rs[1], ts[1]);
509 
510  find_betas_approx_2(&L_6x10, &Rho, Betas[2]);
511  gauss_newton(&L_6x10, &Rho, Betas[2]);
512  rep_errors[2] = compute_R_and_t(ut, Betas[2], Rs[2], ts[2]);
513 
514  find_betas_approx_3(&L_6x10, &Rho, Betas[3]);
515  gauss_newton(&L_6x10, &Rho, Betas[3]);
516  rep_errors[3] = compute_R_and_t(ut, Betas[3], Rs[3], ts[3]);
517 
518  int N = 1;
519  if (rep_errors[2] < rep_errors[1]) N = 2;
520  if (rep_errors[3] < rep_errors[N]) N = 3;
521 
522  copy_R_and_t(Rs[N], ts[N], R, t);
523 
524  return rep_errors[N];
525 }
526 
527 void PnPsolver::copy_R_and_t(const double R_src[3][3], const double t_src[3],
528  double R_dst[3][3], double t_dst[3])
529 {
530  for(int i = 0; i < 3; i++) {
531  for(int j = 0; j < 3; j++)
532  R_dst[i][j] = R_src[i][j];
533  t_dst[i] = t_src[i];
534  }
535 }
536 
537 double PnPsolver::dist2(const double * p1, const double * p2)
538 {
539  return
540  (p1[0] - p2[0]) * (p1[0] - p2[0]) +
541  (p1[1] - p2[1]) * (p1[1] - p2[1]) +
542  (p1[2] - p2[2]) * (p1[2] - p2[2]);
543 }
544 
545 double PnPsolver::dot(const double * v1, const double * v2)
546 {
547  return v1[0] * v2[0] + v1[1] * v2[1] + v1[2] * v2[2];
548 }
549 
550 double PnPsolver::reprojection_error(const double R[3][3], const double t[3])
551 {
552  double sum2 = 0.0;
553 
554  for(int i = 0; i < number_of_correspondences; i++) {
555  double * pw = pws + 3 * i;
556  double Xc = dot(R[0], pw) + t[0];
557  double Yc = dot(R[1], pw) + t[1];
558  double inv_Zc = 1.0 / (dot(R[2], pw) + t[2]);
559  double ue = uc + fu * Xc * inv_Zc;
560  double ve = vc + fv * Yc * inv_Zc;
561  double u = us[2 * i], v = us[2 * i + 1];
562 
563  sum2 += sqrt( (u - ue) * (u - ue) + (v - ve) * (v - ve) );
564  }
565 
566  return sum2 / number_of_correspondences;
567 }
568 
569 void PnPsolver::estimate_R_and_t(double R[3][3], double t[3])
570 {
571  double pc0[3], pw0[3];
572 
573  pc0[0] = pc0[1] = pc0[2] = 0.0;
574  pw0[0] = pw0[1] = pw0[2] = 0.0;
575 
576  for(int i = 0; i < number_of_correspondences; i++) {
577  const double * pc = pcs + 3 * i;
578  const double * pw = pws + 3 * i;
579 
580  for(int j = 0; j < 3; j++) {
581  pc0[j] += pc[j];
582  pw0[j] += pw[j];
583  }
584  }
585  for(int j = 0; j < 3; j++) {
586  pc0[j] /= number_of_correspondences;
587  pw0[j] /= number_of_correspondences;
588  }
589 
590  double abt[3 * 3], abt_d[3], abt_u[3 * 3], abt_v[3 * 3];
591  CvMat ABt = cvMat(3, 3, CV_64F, abt);
592  CvMat ABt_D = cvMat(3, 1, CV_64F, abt_d);
593  CvMat ABt_U = cvMat(3, 3, CV_64F, abt_u);
594  CvMat ABt_V = cvMat(3, 3, CV_64F, abt_v);
595 
596  cvSetZero(&ABt);
597  for(int i = 0; i < number_of_correspondences; i++) {
598  double * pc = pcs + 3 * i;
599  double * pw = pws + 3 * i;
600 
601  for(int j = 0; j < 3; j++) {
602  abt[3 * j ] += (pc[j] - pc0[j]) * (pw[0] - pw0[0]);
603  abt[3 * j + 1] += (pc[j] - pc0[j]) * (pw[1] - pw0[1]);
604  abt[3 * j + 2] += (pc[j] - pc0[j]) * (pw[2] - pw0[2]);
605  }
606  }
607 
608  cvSVD(&ABt, &ABt_D, &ABt_U, &ABt_V, CV_SVD_MODIFY_A);
609 
610  for(int i = 0; i < 3; i++)
611  for(int j = 0; j < 3; j++)
612  R[i][j] = dot(abt_u + 3 * i, abt_v + 3 * j);
613 
614  const double det =
615  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] -
616  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];
617 
618  if (det < 0) {
619  R[2][0] = -R[2][0];
620  R[2][1] = -R[2][1];
621  R[2][2] = -R[2][2];
622  }
623 
624  t[0] = pc0[0] - dot(R[0], pw0);
625  t[1] = pc0[1] - dot(R[1], pw0);
626  t[2] = pc0[2] - dot(R[2], pw0);
627 }
628 
629 void PnPsolver::print_pose(const double R[3][3], const double t[3])
630 {
631  cout << R[0][0] << " " << R[0][1] << " " << R[0][2] << " " << t[0] << endl;
632  cout << R[1][0] << " " << R[1][1] << " " << R[1][2] << " " << t[1] << endl;
633  cout << R[2][0] << " " << R[2][1] << " " << R[2][2] << " " << t[2] << endl;
634 }
635 
637 {
638  if (pcs[2] < 0.0) {
639  for(int i = 0; i < 4; i++)
640  for(int j = 0; j < 3; j++)
641  ccs[i][j] = -ccs[i][j];
642 
643  for(int i = 0; i < number_of_correspondences; i++) {
644  pcs[3 * i ] = -pcs[3 * i];
645  pcs[3 * i + 1] = -pcs[3 * i + 1];
646  pcs[3 * i + 2] = -pcs[3 * i + 2];
647  }
648  }
649 }
650 
651 double PnPsolver::compute_R_and_t(const double * ut, const double * betas,
652  double R[3][3], double t[3])
653 {
654  compute_ccs(betas, ut);
655  compute_pcs();
656 
657  solve_for_sign();
658 
659  estimate_R_and_t(R, t);
660 
661  return reprojection_error(R, t);
662 }
663 
664 // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
665 // betas_approx_1 = [B11 B12 B13 B14]
666 
667 void PnPsolver::find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho,
668  double * betas)
669 {
670  double l_6x4[6 * 4], b4[4];
671  CvMat L_6x4 = cvMat(6, 4, CV_64F, l_6x4);
672  CvMat B4 = cvMat(4, 1, CV_64F, b4);
673 
674  for(int i = 0; i < 6; i++) {
675  cvmSet(&L_6x4, i, 0, cvmGet(L_6x10, i, 0));
676  cvmSet(&L_6x4, i, 1, cvmGet(L_6x10, i, 1));
677  cvmSet(&L_6x4, i, 2, cvmGet(L_6x10, i, 3));
678  cvmSet(&L_6x4, i, 3, cvmGet(L_6x10, i, 6));
679  }
680 
681  cvSolve(&L_6x4, Rho, &B4, CV_SVD);
682 
683  if (b4[0] < 0) {
684  betas[0] = sqrt(-b4[0]);
685  betas[1] = -b4[1] / betas[0];
686  betas[2] = -b4[2] / betas[0];
687  betas[3] = -b4[3] / betas[0];
688  } else {
689  betas[0] = sqrt(b4[0]);
690  betas[1] = b4[1] / betas[0];
691  betas[2] = b4[2] / betas[0];
692  betas[3] = b4[3] / betas[0];
693  }
694 }
695 
696 // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
697 // betas_approx_2 = [B11 B12 B22 ]
698 
699 void PnPsolver::find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho,
700  double * betas)
701 {
702  double l_6x3[6 * 3], b3[3];
703  CvMat L_6x3 = cvMat(6, 3, CV_64F, l_6x3);
704  CvMat B3 = cvMat(3, 1, CV_64F, b3);
705 
706  for(int i = 0; i < 6; i++) {
707  cvmSet(&L_6x3, i, 0, cvmGet(L_6x10, i, 0));
708  cvmSet(&L_6x3, i, 1, cvmGet(L_6x10, i, 1));
709  cvmSet(&L_6x3, i, 2, cvmGet(L_6x10, i, 2));
710  }
711 
712  cvSolve(&L_6x3, Rho, &B3, CV_SVD);
713 
714  if (b3[0] < 0) {
715  betas[0] = sqrt(-b3[0]);
716  betas[1] = (b3[2] < 0) ? sqrt(-b3[2]) : 0.0;
717  } else {
718  betas[0] = sqrt(b3[0]);
719  betas[1] = (b3[2] > 0) ? sqrt(b3[2]) : 0.0;
720  }
721 
722  if (b3[1] < 0) betas[0] = -betas[0];
723 
724  betas[2] = 0.0;
725  betas[3] = 0.0;
726 }
727 
728 // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
729 // betas_approx_3 = [B11 B12 B22 B13 B23 ]
730 
731 void PnPsolver::find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho,
732  double * betas)
733 {
734  double l_6x5[6 * 5], b5[5];
735  CvMat L_6x5 = cvMat(6, 5, CV_64F, l_6x5);
736  CvMat B5 = cvMat(5, 1, CV_64F, b5);
737 
738  for(int i = 0; i < 6; i++) {
739  cvmSet(&L_6x5, i, 0, cvmGet(L_6x10, i, 0));
740  cvmSet(&L_6x5, i, 1, cvmGet(L_6x10, i, 1));
741  cvmSet(&L_6x5, i, 2, cvmGet(L_6x10, i, 2));
742  cvmSet(&L_6x5, i, 3, cvmGet(L_6x10, i, 3));
743  cvmSet(&L_6x5, i, 4, cvmGet(L_6x10, i, 4));
744  }
745 
746  cvSolve(&L_6x5, Rho, &B5, CV_SVD);
747 
748  if (b5[0] < 0) {
749  betas[0] = sqrt(-b5[0]);
750  betas[1] = (b5[2] < 0) ? sqrt(-b5[2]) : 0.0;
751  } else {
752  betas[0] = sqrt(b5[0]);
753  betas[1] = (b5[2] > 0) ? sqrt(b5[2]) : 0.0;
754  }
755  if (b5[1] < 0) betas[0] = -betas[0];
756  betas[2] = b5[3] / betas[0];
757  betas[3] = 0.0;
758 }
759 
760 void PnPsolver::compute_L_6x10(const double * ut, double * l_6x10)
761 {
762  const double * v[4];
763 
764  v[0] = ut + 12 * 11;
765  v[1] = ut + 12 * 10;
766  v[2] = ut + 12 * 9;
767  v[3] = ut + 12 * 8;
768 
769  double dv[4][6][3];
770 
771  for(int i = 0; i < 4; i++) {
772  int a = 0, b = 1;
773  for(int j = 0; j < 6; j++) {
774  dv[i][j][0] = v[i][3 * a ] - v[i][3 * b];
775  dv[i][j][1] = v[i][3 * a + 1] - v[i][3 * b + 1];
776  dv[i][j][2] = v[i][3 * a + 2] - v[i][3 * b + 2];
777 
778  b++;
779  if (b > 3) {
780  a++;
781  b = a + 1;
782  }
783  }
784  }
785 
786  for(int i = 0; i < 6; i++) {
787  double * row = l_6x10 + 10 * i;
788 
789  row[0] = dot(dv[0][i], dv[0][i]);
790  row[1] = 2.0f * dot(dv[0][i], dv[1][i]);
791  row[2] = dot(dv[1][i], dv[1][i]);
792  row[3] = 2.0f * dot(dv[0][i], dv[2][i]);
793  row[4] = 2.0f * dot(dv[1][i], dv[2][i]);
794  row[5] = dot(dv[2][i], dv[2][i]);
795  row[6] = 2.0f * dot(dv[0][i], dv[3][i]);
796  row[7] = 2.0f * dot(dv[1][i], dv[3][i]);
797  row[8] = 2.0f * dot(dv[2][i], dv[3][i]);
798  row[9] = dot(dv[3][i], dv[3][i]);
799  }
800 }
801 
802 void PnPsolver::compute_rho(double * rho)
803 {
804  rho[0] = dist2(cws[0], cws[1]);
805  rho[1] = dist2(cws[0], cws[2]);
806  rho[2] = dist2(cws[0], cws[3]);
807  rho[3] = dist2(cws[1], cws[2]);
808  rho[4] = dist2(cws[1], cws[3]);
809  rho[5] = dist2(cws[2], cws[3]);
810 }
811 
812 void PnPsolver::compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho,
813  double betas[4], CvMat * A, CvMat * b)
814 {
815  for(int i = 0; i < 6; i++) {
816  const double * rowL = l_6x10 + i * 10;
817  double * rowA = A->data.db + i * 4;
818 
819  rowA[0] = 2 * rowL[0] * betas[0] + rowL[1] * betas[1] + rowL[3] * betas[2] + rowL[6] * betas[3];
820  rowA[1] = rowL[1] * betas[0] + 2 * rowL[2] * betas[1] + rowL[4] * betas[2] + rowL[7] * betas[3];
821  rowA[2] = rowL[3] * betas[0] + rowL[4] * betas[1] + 2 * rowL[5] * betas[2] + rowL[8] * betas[3];
822  rowA[3] = rowL[6] * betas[0] + rowL[7] * betas[1] + rowL[8] * betas[2] + 2 * rowL[9] * betas[3];
823 
824  cvmSet(b, i, 0, rho[i] -
825  (
826  rowL[0] * betas[0] * betas[0] +
827  rowL[1] * betas[0] * betas[1] +
828  rowL[2] * betas[1] * betas[1] +
829  rowL[3] * betas[0] * betas[2] +
830  rowL[4] * betas[1] * betas[2] +
831  rowL[5] * betas[2] * betas[2] +
832  rowL[6] * betas[0] * betas[3] +
833  rowL[7] * betas[1] * betas[3] +
834  rowL[8] * betas[2] * betas[3] +
835  rowL[9] * betas[3] * betas[3]
836  ));
837  }
838 }
839 
840 void PnPsolver::gauss_newton(const CvMat * L_6x10, const CvMat * Rho,
841  double betas[4])
842 {
843  const int iterations_number = 5;
844 
845  double a[6*4], b[6], x[4];
846  CvMat A = cvMat(6, 4, CV_64F, a);
847  CvMat B = cvMat(6, 1, CV_64F, b);
848  CvMat X = cvMat(4, 1, CV_64F, x);
849 
850  for(int k = 0; k < iterations_number; k++) {
851  compute_A_and_b_gauss_newton(L_6x10->data.db, Rho->data.db,
852  betas, &A, &B);
853  qr_solve(&A, &B, &X);
854 
855  for(int i = 0; i < 4; i++)
856  betas[i] += x[i];
857  }
858 }
859 
860 void PnPsolver::qr_solve(CvMat * A, CvMat * b, CvMat * X)
861 {
862  static int max_nr = 0;
863  static double * A1, * A2;
864 
865  const int nr = A->rows;
866  const int nc = A->cols;
867 
868  if (max_nr != 0 && max_nr < nr) {
869  delete [] A1;
870  delete [] A2;
871  }
872  if (max_nr < nr) {
873  max_nr = nr;
874  A1 = new double[nr];
875  A2 = new double[nr];
876  }
877 
878  double * pA = A->data.db, * ppAkk = pA;
879  for(int k = 0; k < nc; k++) {
880  double * ppAik = ppAkk, eta = fabs(*ppAik);
881  for(int i = k + 1; i < nr; i++) {
882  double elt = fabs(*ppAik);
883  if (eta < elt) eta = elt;
884  ppAik += nc;
885  }
886 
887  if (eta == 0) {
888  A1[k] = A2[k] = 0.0;
889  cerr << "God damnit, A is singular, this shouldn't happen." << endl;
890  return;
891  } else {
892  double * ppAik = ppAkk, sum = 0.0, inv_eta = 1. / eta;
893  for(int i = k; i < nr; i++) {
894  *ppAik *= inv_eta;
895  sum += *ppAik * *ppAik;
896  ppAik += nc;
897  }
898  double sigma = sqrt(sum);
899  if (*ppAkk < 0)
900  sigma = -sigma;
901  *ppAkk += sigma;
902  A1[k] = sigma * *ppAkk;
903  A2[k] = -eta * sigma;
904  for(int j = k + 1; j < nc; j++) {
905  double * ppAik = ppAkk, sum = 0;
906  for(int i = k; i < nr; i++) {
907  sum += *ppAik * ppAik[j - k];
908  ppAik += nc;
909  }
910  double tau = sum / A1[k];
911  ppAik = ppAkk;
912  for(int i = k; i < nr; i++) {
913  ppAik[j - k] -= tau * *ppAik;
914  ppAik += nc;
915  }
916  }
917  }
918  ppAkk += nc + 1;
919  }
920 
921  // b <- Qt b
922  double * ppAjj = pA, * pb = b->data.db;
923  for(int j = 0; j < nc; j++) {
924  double * ppAij = ppAjj, tau = 0;
925  for(int i = j; i < nr; i++) {
926  tau += *ppAij * pb[i];
927  ppAij += nc;
928  }
929  tau /= A1[j];
930  ppAij = ppAjj;
931  for(int i = j; i < nr; i++) {
932  pb[i] -= tau * *ppAij;
933  ppAij += nc;
934  }
935  ppAjj += nc + 1;
936  }
937 
938  // X = R-1 b
939  double * pX = X->data.db;
940  pX[nc - 1] = pb[nc - 1] / A2[nc - 1];
941  for(int i = nc - 2; i >= 0; i--) {
942  double * ppAij = pA + i * nc + (i + 1), sum = 0;
943 
944  for(int j = i + 1; j < nc; j++) {
945  sum += *ppAij * pX[j];
946  ppAij++;
947  }
948  pX[i] = (pb[i] - sum) / A2[i];
949  }
950 }
951 
952 
953 
954 void PnPsolver::relative_error(double & rot_err, double & transl_err,
955  const double Rtrue[3][3], const double ttrue[3],
956  const double Rest[3][3], const double test[3])
957 {
958  double qtrue[4], qest[4];
959 
960  mat_to_quat(Rtrue, qtrue);
961  mat_to_quat(Rest, qest);
962 
963  double rot_err1 = sqrt((qtrue[0] - qest[0]) * (qtrue[0] - qest[0]) +
964  (qtrue[1] - qest[1]) * (qtrue[1] - qest[1]) +
965  (qtrue[2] - qest[2]) * (qtrue[2] - qest[2]) +
966  (qtrue[3] - qest[3]) * (qtrue[3] - qest[3]) ) /
967  sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]);
968 
969  double rot_err2 = sqrt((qtrue[0] + qest[0]) * (qtrue[0] + qest[0]) +
970  (qtrue[1] + qest[1]) * (qtrue[1] + qest[1]) +
971  (qtrue[2] + qest[2]) * (qtrue[2] + qest[2]) +
972  (qtrue[3] + qest[3]) * (qtrue[3] + qest[3]) ) /
973  sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]);
974 
975  rot_err = min(rot_err1, rot_err2);
976 
977  transl_err =
978  sqrt((ttrue[0] - test[0]) * (ttrue[0] - test[0]) +
979  (ttrue[1] - test[1]) * (ttrue[1] - test[1]) +
980  (ttrue[2] - test[2]) * (ttrue[2] - test[2])) /
981  sqrt(ttrue[0] * ttrue[0] + ttrue[1] * ttrue[1] + ttrue[2] * ttrue[2]);
982 }
983 
984 void PnPsolver::mat_to_quat(const double R[3][3], double q[4])
985 {
986  double tr = R[0][0] + R[1][1] + R[2][2];
987  double n4;
988 
989  if (tr > 0.0f) {
990  q[0] = R[1][2] - R[2][1];
991  q[1] = R[2][0] - R[0][2];
992  q[2] = R[0][1] - R[1][0];
993  q[3] = tr + 1.0f;
994  n4 = q[3];
995  } else if ( (R[0][0] > R[1][1]) && (R[0][0] > R[2][2]) ) {
996  q[0] = 1.0f + R[0][0] - R[1][1] - R[2][2];
997  q[1] = R[1][0] + R[0][1];
998  q[2] = R[2][0] + R[0][2];
999  q[3] = R[1][2] - R[2][1];
1000  n4 = q[0];
1001  } else if (R[1][1] > R[2][2]) {
1002  q[0] = R[1][0] + R[0][1];
1003  q[1] = 1.0f + R[1][1] - R[0][0] - R[2][2];
1004  q[2] = R[2][1] + R[1][2];
1005  q[3] = R[2][0] - R[0][2];
1006  n4 = q[1];
1007  } else {
1008  q[0] = R[2][0] + R[0][2];
1009  q[1] = R[2][1] + R[1][2];
1010  q[2] = 1.0f + R[2][2] - R[0][0] - R[1][1];
1011  q[3] = R[0][1] - R[1][0];
1012  n4 = q[2];
1013  }
1014  double scale = 0.5f / double(sqrt(n4));
1015 
1016  q[0] *= scale;
1017  q[1] *= scale;
1018  q[2] *= scale;
1019  q[3] *= scale;
1020 }
1021 
1022 } //namespace ORB_SLAM
d
void estimate_R_and_t(double R[3][3], double t[3])
Definition: PnPsolver.cc:569
void compute_L_6x10(const double *ut, double *l_6x10)
Definition: PnPsolver.cc:760
std::vector< MapPoint * > mvpMapPoints
Definition: Frame.h:153
void find_betas_approx_3(const CvMat *L_6x10, const CvMat *Rho, double *betas)
Definition: PnPsolver.cc:731
static float fy
Definition: Frame.h:114
vector< bool > mvbBestInliers
Definition: PnPsolver.h:159
f
vector< float > mvSigma2
Definition: PnPsolver.h:142
void print_pose(const double R[3][3], const double t[3])
Definition: PnPsolver.cc:629
void compute_rho(double *rho)
Definition: PnPsolver.cc:802
static float cx
Definition: Frame.h:115
double mRi[3][3]
Definition: PnPsolver.h:151
static float fx
Definition: Frame.h:113
double compute_R_and_t(const double *ut, const double *betas, double R[3][3], double t[3])
Definition: PnPsolver.cc:651
static float cy
Definition: Frame.h:116
void gauss_newton(const CvMat *L_6x10, const CvMat *Rho, double current_betas[4])
Definition: PnPsolver.cc:840
cv::Mat GetWorldPos()
Definition: MapPoint.cc:80
double cws[4][3]
Definition: PnPsolver.h:135
void compute_barycentric_coordinates(void)
Definition: PnPsolver.cc:411
cv::Mat iterate(int nIterations, bool &bNoMore, vector< bool > &vbInliers, int &nInliers)
Definition: PnPsolver.cc:165
TFSIMD_FORCE_INLINE const tfScalar & y() const
cv::Mat find(vector< bool > &vbInliers, int &nInliers)
Definition: PnPsolver.cc:159
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:138
vector< cv::Point2f > mvP2D
Definition: PnPsolver.h:141
void set_maximum_number_of_correspondences(const int n)
Definition: PnPsolver.cc:342
vector< float > mvLevelSigma2
Definition: Frame.h:179
double dist2(const double *p1, const double *p2)
Definition: PnPsolver.cc:537
int maximum_number_of_correspondences
Definition: PnPsolver.h:132
TFSIMD_FORCE_INLINE const tfScalar & x() const
double compute_pose(double R[3][3], double T[3])
Definition: PnPsolver.cc:477
void find_betas_approx_1(const CvMat *L_6x10, const CvMat *Rho, double *betas)
Definition: PnPsolver.cc:667
vector< float > mvMaxError
Definition: PnPsolver.h:193
double reprojection_error(const double R[3][3], const double t[3])
Definition: PnPsolver.cc:550
static int RandomInt(int min, int max)
Definition: Random.cpp:47
TFSIMD_FORCE_INLINE const tfScalar & z() const
void relative_error(double &rot_err, double &transl_err, const double Rtrue[3][3], const double ttrue[3], const double Rest[3][3], const double test[3])
Definition: PnPsolver.cc:954
vector< cv::Point3f > mvP3Dw
Definition: PnPsolver.h:145
void SetRansacParameters(double probability=0.99, int minInliers=8, int maxIterations=300, int minSet=4, float epsilon=0.4, float th2=5.991)
Definition: PnPsolver.cc:121
vector< bool > mvbInliersi
Definition: PnPsolver.h:154
void reset_correspondences(void)
Definition: PnPsolver.cc:358
double dot(const double *v1, const double *v2)
Definition: PnPsolver.cc:545
void compute_A_and_b_gauss_newton(const double *l_6x10, const double *rho, double cb[4], CvMat *A, CvMat *b)
Definition: PnPsolver.cc:812
vector< MapPoint * > mvpMapPointMatches
Definition: PnPsolver.h:138
int min(int a, int b)
void copy_R_and_t(const double R_dst[3][3], const double t_dst[3], double R_src[3][3], double t_src[3])
Definition: PnPsolver.cc:527
vector< size_t > mvAllIndices
Definition: PnPsolver.h:172
void compute_pcs(void)
Definition: PnPsolver.cc:466
vector< bool > mvbRefinedInliers
Definition: PnPsolver.h:165
void compute_ccs(const double *betas, const double *ut)
Definition: PnPsolver.cc:453
void find_betas_approx_2(const CvMat *L_6x10, const CvMat *Rho, double *betas)
Definition: PnPsolver.cc:699
void solve_for_sign(void)
Definition: PnPsolver.cc:636
void mat_to_quat(const double R[3][3], double q[4])
Definition: PnPsolver.cc:984
void add_correspondence(const double X, const double Y, const double Z, const double u, const double v)
Definition: PnPsolver.cc:363
void qr_solve(CvMat *A, CvMat *b, CvMat *X)
Definition: PnPsolver.cc:860
vector< size_t > mvKeyPointIndices
Definition: PnPsolver.h:148
double ccs[4][3]
Definition: PnPsolver.h:135
void choose_control_points(void)
Definition: PnPsolver.cc:375
void fill_M(CvMat *M, const int row, const double *alphas, const double u, const double v)
Definition: PnPsolver.cc:436


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