epnp.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 using namespace std;
00003 
00004 #include "epnp.h"
00005 
00006 epnp::epnp(void)
00007 {
00008   maximum_number_of_correspondences = 0;
00009   number_of_correspondences = 0;
00010 
00011   pws = 0;
00012   us = 0;
00013   alphas = 0;
00014   pcs = 0;
00015 }
00016 
00017 epnp::~epnp()
00018 {
00019   delete [] pws;
00020   delete [] us;
00021   delete [] alphas;
00022   delete [] pcs;
00023 }
00024 
00025 void epnp::set_internal_parameters(double uc, double vc, double fu, double fv)
00026 {
00027   this->uc = uc;
00028   this->vc = vc;
00029   this->fu = fu;
00030   this->fv = fv;
00031 }
00032 
00033 void epnp::set_maximum_number_of_correspondences(int n)
00034 {
00035   if (maximum_number_of_correspondences < n) {
00036     if (pws != 0) delete [] pws;
00037     if (us != 0) delete [] us;
00038     if (alphas != 0) delete [] alphas;
00039     if (pcs != 0) delete [] pcs;
00040 
00041     maximum_number_of_correspondences = n;
00042     pws = new double[3 * maximum_number_of_correspondences];
00043     us = new double[2 * maximum_number_of_correspondences];
00044     alphas = new double[4 * maximum_number_of_correspondences];
00045     pcs = new double[3 * maximum_number_of_correspondences];
00046   }
00047 }
00048 
00049 void epnp::reset_correspondences(void)
00050 {
00051   number_of_correspondences = 0;
00052 }
00053 
00054 void epnp::add_correspondence(double X, double Y, double Z, double u, double v)
00055 {
00056   pws[3 * number_of_correspondences    ] = X;
00057   pws[3 * number_of_correspondences + 1] = Y;
00058   pws[3 * number_of_correspondences + 2] = Z;
00059 
00060   us[2 * number_of_correspondences    ] = u;
00061   us[2 * number_of_correspondences + 1] = v;
00062 
00063   number_of_correspondences++;
00064 }
00065 
00066 void epnp::choose_control_points(void)
00067 {
00068   // Take C0 as the reference points centroid:
00069   cws[0][0] = cws[0][1] = cws[0][2] = 0;
00070   for(int i = 0; i < number_of_correspondences; i++)
00071     for(int j = 0; j < 3; j++)
00072       cws[0][j] += pws[3 * i + j];
00073 
00074   for(int j = 0; j < 3; j++)
00075     cws[0][j] /= number_of_correspondences;
00076 
00077 
00078   // Take C1, C2, and C3 from PCA on the reference points:
00079   CvMat * PW0 = cvCreateMat(number_of_correspondences, 3, CV_64F);
00080 
00081   double pw0tpw0[3 * 3], dc[3], uct[3 * 3];
00082   CvMat PW0tPW0 = cvMat(3, 3, CV_64F, pw0tpw0);
00083   CvMat DC      = cvMat(3, 1, CV_64F, dc);
00084   CvMat UCt     = cvMat(3, 3, CV_64F, uct);
00085 
00086   for(int i = 0; i < number_of_correspondences; i++)
00087     for(int j = 0; j < 3; j++)
00088       PW0->data.db[3 * i + j] = pws[3 * i + j] - cws[0][j];
00089 
00090   cvMulTransposed(PW0, &PW0tPW0, 1);
00091   cvSVD(&PW0tPW0, &DC, &UCt, 0, CV_SVD_MODIFY_A | CV_SVD_U_T);
00092 
00093   cvReleaseMat(&PW0);
00094 
00095   for(int i = 1; i < 4; i++) {
00096     double k = sqrt(dc[i - 1] / number_of_correspondences);
00097     for(int j = 0; j < 3; j++)
00098       cws[i][j] = cws[0][j] + k * uct[3 * (i - 1) + j];
00099   }
00100 }
00101 
00102 void epnp::compute_barycentric_coordinates(void)
00103 {
00104   double cc[3 * 3], cc_inv[3 * 3];
00105   CvMat CC     = cvMat(3, 3, CV_64F, cc);
00106   CvMat CC_inv = cvMat(3, 3, CV_64F, cc_inv);
00107 
00108   for(int i = 0; i < 3; i++)
00109     for(int j = 1; j < 4; j++)
00110       cc[3 * i + j - 1] = cws[j][i] - cws[0][i];
00111 
00112   cvInvert(&CC, &CC_inv, CV_SVD);
00113   double * ci = cc_inv;
00114   for(int i = 0; i < number_of_correspondences; i++) {
00115     double * pi = pws + 3 * i;
00116     double * a = alphas + 4 * i;
00117 
00118     for(int j = 0; j < 3; j++)
00119       a[1 + j] =
00120         ci[3 * j    ] * (pi[0] - cws[0][0]) +
00121         ci[3 * j + 1] * (pi[1] - cws[0][1]) +
00122         ci[3 * j + 2] * (pi[2] - cws[0][2]);
00123     a[0] = 1.0f - a[1] - a[2] - a[3];
00124   }
00125 }
00126 
00127 void epnp::fill_M(CvMat * M,
00128                   const int row, const double * as, const double u, const double v)
00129 {
00130   double * M1 = M->data.db + row * 12;
00131   double * M2 = M1 + 12;
00132 
00133   for(int i = 0; i < 4; i++) {
00134     M1[3 * i    ] = as[i] * fu;
00135     M1[3 * i + 1] = 0.0;
00136     M1[3 * i + 2] = as[i] * (uc - u);
00137 
00138     M2[3 * i    ] = 0.0;
00139     M2[3 * i + 1] = as[i] * fv;
00140     M2[3 * i + 2] = as[i] * (vc - v);
00141   }
00142 }
00143 
00144 void epnp::compute_ccs(const double * betas, const double * ut)
00145 {
00146   for(int i = 0; i < 4; i++)
00147     ccs[i][0] = ccs[i][1] = ccs[i][2] = 0.0f;
00148 
00149   for(int i = 0; i < 4; i++) {
00150     const double * v = ut + 12 * (11 - i);
00151     for(int j = 0; j < 4; j++)
00152       for(int k = 0; k < 3; k++)
00153         ccs[j][k] += betas[i] * v[3 * j + k];
00154   }
00155 }
00156 
00157 void epnp::compute_pcs(void)
00158 {
00159   for(int i = 0; i < number_of_correspondences; i++) {
00160     double * a = alphas + 4 * i;
00161     double * pc = pcs + 3 * i;
00162 
00163     for(int j = 0; j < 3; j++)
00164       pc[j] = a[0] * ccs[0][j] + a[1] * ccs[1][j] + a[2] * ccs[2][j] + a[3] * ccs[3][j];
00165   }
00166 }
00167 
00168 double epnp::compute_pose(double R[3][3], double t[3])
00169 {
00170   choose_control_points();
00171   compute_barycentric_coordinates();
00172 
00173   CvMat * M = cvCreateMat(2 * number_of_correspondences, 12, CV_64F);
00174 
00175   for(int i = 0; i < number_of_correspondences; i++)
00176     fill_M(M, 2 * i, alphas + 4 * i, us[2 * i], us[2 * i + 1]);
00177 
00178   double mtm[12 * 12], d[12], ut[12 * 12];
00179   CvMat MtM = cvMat(12, 12, CV_64F, mtm);
00180   CvMat D   = cvMat(12,  1, CV_64F, d);
00181   CvMat Ut  = cvMat(12, 12, CV_64F, ut);
00182 
00183   cvMulTransposed(M, &MtM, 1);
00184   cvSVD(&MtM, &D, &Ut, 0, CV_SVD_MODIFY_A | CV_SVD_U_T);
00185   cvReleaseMat(&M);
00186 
00187   double l_6x10[6 * 10], rho[6];
00188   CvMat L_6x10 = cvMat(6, 10, CV_64F, l_6x10);
00189   CvMat Rho    = cvMat(6,  1, CV_64F, rho);
00190 
00191   compute_L_6x10(ut, l_6x10);
00192   compute_rho(rho);
00193 
00194   double Betas[4][4], rep_errors[4];
00195   double Rs[4][3][3], ts[4][3];
00196 
00197   find_betas_approx_1(&L_6x10, &Rho, Betas[1]);
00198   gauss_newton(&L_6x10, &Rho, Betas[1]);
00199   rep_errors[1] = compute_R_and_t(ut, Betas[1], Rs[1], ts[1]);
00200 
00201   find_betas_approx_2(&L_6x10, &Rho, Betas[2]);
00202   gauss_newton(&L_6x10, &Rho, Betas[2]);
00203   rep_errors[2] = compute_R_and_t(ut, Betas[2], Rs[2], ts[2]);
00204 
00205   find_betas_approx_3(&L_6x10, &Rho, Betas[3]);
00206   gauss_newton(&L_6x10, &Rho, Betas[3]);
00207   rep_errors[3] = compute_R_and_t(ut, Betas[3], Rs[3], ts[3]);
00208 
00209   int N = 1;
00210   if (rep_errors[2] < rep_errors[1]) N = 2;
00211   if (rep_errors[3] < rep_errors[N]) N = 3;
00212 
00213   copy_R_and_t(Rs[N], ts[N], R, t);
00214 
00215   return rep_errors[N];
00216 }
00217 
00218 void epnp::copy_R_and_t(const double R_src[3][3], const double t_src[3],
00219                         double R_dst[3][3], double t_dst[3])
00220 {
00221   for(int i = 0; i < 3; i++) {
00222     for(int j = 0; j < 3; j++)
00223       R_dst[i][j] = R_src[i][j];
00224     t_dst[i] = t_src[i];
00225   }
00226 }
00227 
00228 double epnp::dist2(const double * p1, const double * p2)
00229 {
00230   return
00231     (p1[0] - p2[0]) * (p1[0] - p2[0]) +
00232     (p1[1] - p2[1]) * (p1[1] - p2[1]) +
00233     (p1[2] - p2[2]) * (p1[2] - p2[2]);
00234 }
00235 
00236 double epnp::dot(const double * v1, const double * v2)
00237 {
00238   return v1[0] * v2[0] + v1[1] * v2[1] + v1[2] * v2[2];
00239 }
00240 
00241 double epnp::reprojection_error(const double R[3][3], const double t[3])
00242 {
00243   double sum2 = 0.0;
00244 
00245   for(int i = 0; i < number_of_correspondences; i++) {
00246     double * pw = pws + 3 * i;
00247     double Xc = dot(R[0], pw) + t[0];
00248     double Yc = dot(R[1], pw) + t[1];
00249     double inv_Zc = 1.0 / (dot(R[2], pw) + t[2]);
00250     double ue = uc + fu * Xc * inv_Zc;
00251     double ve = vc + fv * Yc * inv_Zc;
00252     double u = us[2 * i], v = us[2 * i + 1];
00253 
00254     sum2 += sqrt( (u - ue) * (u - ue) + (v - ve) * (v - ve) );
00255   }
00256 
00257   return sum2 / number_of_correspondences;
00258 }
00259 
00260 void epnp::estimate_R_and_t(double R[3][3], double t[3])
00261 {
00262   double pc0[3], pw0[3];
00263 
00264   pc0[0] = pc0[1] = pc0[2] = 0.0;
00265   pw0[0] = pw0[1] = pw0[2] = 0.0;
00266 
00267   for(int i = 0; i < number_of_correspondences; i++) {
00268     const double * pc = pcs + 3 * i;
00269     const double * pw = pws + 3 * i;
00270 
00271     for(int j = 0; j < 3; j++) {
00272       pc0[j] += pc[j];
00273       pw0[j] += pw[j];
00274     }
00275   }
00276   for(int j = 0; j < 3; j++) {
00277     pc0[j] /= number_of_correspondences;
00278     pw0[j] /= number_of_correspondences;
00279   }
00280 
00281   double abt[3 * 3], abt_d[3], abt_u[3 * 3], abt_v[3 * 3];
00282   CvMat ABt   = cvMat(3, 3, CV_64F, abt);
00283   CvMat ABt_D = cvMat(3, 1, CV_64F, abt_d);
00284   CvMat ABt_U = cvMat(3, 3, CV_64F, abt_u);
00285   CvMat ABt_V = cvMat(3, 3, CV_64F, abt_v);
00286 
00287   cvSetZero(&ABt);
00288   for(int i = 0; i < number_of_correspondences; i++) {
00289     double * pc = pcs + 3 * i;
00290     double * pw = pws + 3 * i;
00291 
00292     for(int j = 0; j < 3; j++) {
00293       abt[3 * j    ] += (pc[j] - pc0[j]) * (pw[0] - pw0[0]);
00294       abt[3 * j + 1] += (pc[j] - pc0[j]) * (pw[1] - pw0[1]);
00295       abt[3 * j + 2] += (pc[j] - pc0[j]) * (pw[2] - pw0[2]);
00296     }
00297   }
00298 
00299   cvSVD(&ABt, &ABt_D, &ABt_U, &ABt_V, CV_SVD_MODIFY_A);
00300 
00301   for(int i = 0; i < 3; i++)
00302     for(int j = 0; j < 3; j++)
00303       R[i][j] = dot(abt_u + 3 * i, abt_v + 3 * j);
00304 
00305   const double det =
00306     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] -
00307     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];
00308 
00309   if (det < 0) {
00310     R[2][0] = -R[2][0];
00311     R[2][1] = -R[2][1];
00312     R[2][2] = -R[2][2];
00313   }
00314 
00315   t[0] = pc0[0] - dot(R[0], pw0);
00316   t[1] = pc0[1] - dot(R[1], pw0);
00317   t[2] = pc0[2] - dot(R[2], pw0);
00318 }
00319 
00320 void epnp::print_pose(const double R[3][3], const double t[3])
00321 {
00322   cout << R[0][0] << " " << R[0][1] << " " << R[0][2] << " " << t[0] << endl;
00323   cout << R[1][0] << " " << R[1][1] << " " << R[1][2] << " " << t[1] << endl;
00324   cout << R[2][0] << " " << R[2][1] << " " << R[2][2] << " " << t[2] << endl;
00325 }
00326 
00327 void epnp::solve_for_sign(void)
00328 {
00329   if (pcs[2] < 0.0) {
00330     for(int i = 0; i < 4; i++)
00331       for(int j = 0; j < 3; j++)
00332         ccs[i][j] = -ccs[i][j];
00333 
00334     for(int i = 0; i < number_of_correspondences; i++) {
00335       pcs[3 * i    ] = -pcs[3 * i];
00336       pcs[3 * i + 1] = -pcs[3 * i + 1];
00337       pcs[3 * i + 2] = -pcs[3 * i + 2];
00338     }
00339   }
00340 }
00341 
00342 double epnp::compute_R_and_t(const double * ut, const double * betas,
00343                              double R[3][3], double t[3])
00344 {
00345   compute_ccs(betas, ut);
00346   compute_pcs();
00347 
00348   solve_for_sign();
00349 
00350   estimate_R_and_t(R, t);
00351 
00352   return reprojection_error(R, t);
00353 }
00354 
00355 // betas10        = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
00356 // betas_approx_1 = [B11 B12     B13         B14]
00357 
00358 void epnp::find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho,
00359                                double * betas)
00360 {
00361   double l_6x4[6 * 4], b4[4];
00362   CvMat L_6x4 = cvMat(6, 4, CV_64F, l_6x4);
00363   CvMat B4    = cvMat(4, 1, CV_64F, b4);
00364 
00365   for(int i = 0; i < 6; i++) {
00366     cvmSet(&L_6x4, i, 0, cvmGet(L_6x10, i, 0));
00367     cvmSet(&L_6x4, i, 1, cvmGet(L_6x10, i, 1));
00368     cvmSet(&L_6x4, i, 2, cvmGet(L_6x10, i, 3));
00369     cvmSet(&L_6x4, i, 3, cvmGet(L_6x10, i, 6));
00370   }
00371 
00372   cvSolve(&L_6x4, Rho, &B4, CV_SVD);
00373 
00374   if (b4[0] < 0) {
00375     betas[0] = sqrt(-b4[0]);
00376     betas[1] = -b4[1] / betas[0];
00377     betas[2] = -b4[2] / betas[0];
00378     betas[3] = -b4[3] / betas[0];
00379   } else {
00380     betas[0] = sqrt(b4[0]);
00381     betas[1] = b4[1] / betas[0];
00382     betas[2] = b4[2] / betas[0];
00383     betas[3] = b4[3] / betas[0];
00384   }
00385 }
00386 
00387 // betas10        = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
00388 // betas_approx_2 = [B11 B12 B22                            ]
00389 
00390 void epnp::find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho,
00391                                double * betas)
00392 {
00393   double l_6x3[6 * 3], b3[3];
00394   CvMat L_6x3  = cvMat(6, 3, CV_64F, l_6x3);
00395   CvMat B3     = cvMat(3, 1, CV_64F, b3);
00396 
00397   for(int i = 0; i < 6; i++) {
00398     cvmSet(&L_6x3, i, 0, cvmGet(L_6x10, i, 0));
00399     cvmSet(&L_6x3, i, 1, cvmGet(L_6x10, i, 1));
00400     cvmSet(&L_6x3, i, 2, cvmGet(L_6x10, i, 2));
00401   }
00402 
00403   cvSolve(&L_6x3, Rho, &B3, CV_SVD);
00404 
00405   if (b3[0] < 0) {
00406     betas[0] = sqrt(-b3[0]);
00407     betas[1] = (b3[2] < 0) ? sqrt(-b3[2]) : 0.0;
00408   } else {
00409     betas[0] = sqrt(b3[0]);
00410     betas[1] = (b3[2] > 0) ? sqrt(b3[2]) : 0.0;
00411   }
00412 
00413   if (b3[1] < 0) betas[0] = -betas[0];
00414 
00415   betas[2] = 0.0;
00416   betas[3] = 0.0;
00417 }
00418 
00419 // betas10        = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44]
00420 // betas_approx_3 = [B11 B12 B22 B13 B23                    ]
00421 
00422 void epnp::find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho,
00423                                double * betas)
00424 {
00425   double l_6x5[6 * 5], b5[5];
00426   CvMat L_6x5 = cvMat(6, 5, CV_64F, l_6x5);
00427   CvMat B5    = cvMat(5, 1, CV_64F, b5);
00428 
00429   for(int i = 0; i < 6; i++) {
00430     cvmSet(&L_6x5, i, 0, cvmGet(L_6x10, i, 0));
00431     cvmSet(&L_6x5, i, 1, cvmGet(L_6x10, i, 1));
00432     cvmSet(&L_6x5, i, 2, cvmGet(L_6x10, i, 2));
00433     cvmSet(&L_6x5, i, 3, cvmGet(L_6x10, i, 3));
00434     cvmSet(&L_6x5, i, 4, cvmGet(L_6x10, i, 4));
00435   }
00436 
00437   cvSolve(&L_6x5, Rho, &B5, CV_SVD);
00438 
00439   if (b5[0] < 0) {
00440     betas[0] = sqrt(-b5[0]);
00441     betas[1] = (b5[2] < 0) ? sqrt(-b5[2]) : 0.0;
00442   } else {
00443     betas[0] = sqrt(b5[0]);
00444     betas[1] = (b5[2] > 0) ? sqrt(b5[2]) : 0.0;
00445   }
00446   if (b5[1] < 0) betas[0] = -betas[0];
00447   betas[2] = b5[3] / betas[0];
00448   betas[3] = 0.0;
00449 }
00450 
00451 void epnp::compute_L_6x10(const double * ut, double * l_6x10)
00452 {
00453   const double * v[4];
00454 
00455   v[0] = ut + 12 * 11;
00456   v[1] = ut + 12 * 10;
00457   v[2] = ut + 12 *  9;
00458   v[3] = ut + 12 *  8;
00459 
00460   double dv[4][6][3];
00461 
00462   for(int i = 0; i < 4; i++) {
00463     int a = 0, b = 1;
00464     for(int j = 0; j < 6; j++) {
00465       dv[i][j][0] = v[i][3 * a    ] - v[i][3 * b];
00466       dv[i][j][1] = v[i][3 * a + 1] - v[i][3 * b + 1];
00467       dv[i][j][2] = v[i][3 * a + 2] - v[i][3 * b + 2];
00468 
00469       b++;
00470       if (b > 3) {
00471         a++;
00472         b = a + 1;
00473       }
00474     }
00475   }
00476 
00477   for(int i = 0; i < 6; i++) {
00478     double * row = l_6x10 + 10 * i;
00479 
00480     row[0] =        dot(dv[0][i], dv[0][i]);
00481     row[1] = 2.0f * dot(dv[0][i], dv[1][i]);
00482     row[2] =        dot(dv[1][i], dv[1][i]);
00483     row[3] = 2.0f * dot(dv[0][i], dv[2][i]);
00484     row[4] = 2.0f * dot(dv[1][i], dv[2][i]);
00485     row[5] =        dot(dv[2][i], dv[2][i]);
00486     row[6] = 2.0f * dot(dv[0][i], dv[3][i]);
00487     row[7] = 2.0f * dot(dv[1][i], dv[3][i]);
00488     row[8] = 2.0f * dot(dv[2][i], dv[3][i]);
00489     row[9] =        dot(dv[3][i], dv[3][i]);
00490   }
00491 }
00492 
00493 void epnp::compute_rho(double * rho)
00494 {
00495   rho[0] = dist2(cws[0], cws[1]);
00496   rho[1] = dist2(cws[0], cws[2]);
00497   rho[2] = dist2(cws[0], cws[3]);
00498   rho[3] = dist2(cws[1], cws[2]);
00499   rho[4] = dist2(cws[1], cws[3]);
00500   rho[5] = dist2(cws[2], cws[3]);
00501 }
00502 
00503 void epnp::compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho,
00504                                         double betas[4], CvMat * A, CvMat * b)
00505 {
00506   for(int i = 0; i < 6; i++) {
00507     const double * rowL = l_6x10 + i * 10;
00508     double * rowA = A->data.db + i * 4;
00509 
00510     rowA[0] = 2 * rowL[0] * betas[0] +     rowL[1] * betas[1] +     rowL[3] * betas[2] +     rowL[6] * betas[3];
00511     rowA[1] =     rowL[1] * betas[0] + 2 * rowL[2] * betas[1] +     rowL[4] * betas[2] +     rowL[7] * betas[3];
00512     rowA[2] =     rowL[3] * betas[0] +     rowL[4] * betas[1] + 2 * rowL[5] * betas[2] +     rowL[8] * betas[3];
00513     rowA[3] =     rowL[6] * betas[0] +     rowL[7] * betas[1] +     rowL[8] * betas[2] + 2 * rowL[9] * betas[3];
00514 
00515     cvmSet(b, i, 0, rho[i] -
00516            (
00517             rowL[0] * betas[0] * betas[0] +
00518             rowL[1] * betas[0] * betas[1] +
00519             rowL[2] * betas[1] * betas[1] +
00520             rowL[3] * betas[0] * betas[2] +
00521             rowL[4] * betas[1] * betas[2] +
00522             rowL[5] * betas[2] * betas[2] +
00523             rowL[6] * betas[0] * betas[3] +
00524             rowL[7] * betas[1] * betas[3] +
00525             rowL[8] * betas[2] * betas[3] +
00526             rowL[9] * betas[3] * betas[3]
00527             ));
00528   }
00529 }
00530 
00531 void epnp::gauss_newton(const CvMat * L_6x10, const CvMat * Rho,
00532                         double betas[4])
00533 {
00534   const int iterations_number = 5;
00535 
00536   double a[6*4], b[6], x[4];
00537   CvMat A = cvMat(6, 4, CV_64F, a);
00538   CvMat B = cvMat(6, 1, CV_64F, b);
00539   CvMat X = cvMat(4, 1, CV_64F, x);
00540 
00541   for(int k = 0; k < iterations_number; k++) {
00542     compute_A_and_b_gauss_newton(L_6x10->data.db, Rho->data.db,
00543                                  betas, &A, &B);
00544     qr_solve(&A, &B, &X);
00545 
00546     for(int i = 0; i < 4; i++)
00547       betas[i] += x[i];
00548   }
00549 }
00550 
00551 void epnp::qr_solve(CvMat * A, CvMat * b, CvMat * X)
00552 {
00553   static int max_nr = 0;
00554   static double * A1, * A2;
00555 
00556   const int nr = A->rows;
00557   const int nc = A->cols;
00558 
00559   if (max_nr != 0 && max_nr < nr) {
00560     delete [] A1;
00561     delete [] A2;
00562   }
00563   if (max_nr < nr) {
00564     max_nr = nr;
00565     A1 = new double[nr];
00566     A2 = new double[nr];
00567   }
00568 
00569   double * pA = A->data.db, * ppAkk = pA;
00570   for(int k = 0; k < nc; k++) {
00571     double * ppAik = ppAkk, eta = fabs(*ppAik);
00572     for(int i = k + 1; i < nr; i++) {
00573       double elt = fabs(*ppAik);
00574       if (eta < elt) eta = elt;
00575       ppAik += nc;
00576     }
00577 
00578     if (eta == 0) {
00579       A1[k] = A2[k] = 0.0;
00580       cerr << "God damnit, A is singular, this shouldn't happen." << endl;
00581       return;
00582     } else {
00583       double * ppAik = ppAkk, sum = 0.0, inv_eta = 1. / eta;
00584       for(int i = k; i < nr; i++) {
00585         *ppAik *= inv_eta;
00586         sum += *ppAik * *ppAik;
00587         ppAik += nc;
00588       }
00589       double sigma = sqrt(sum);
00590       if (*ppAkk < 0)
00591         sigma = -sigma;
00592       *ppAkk += sigma;
00593       A1[k] = sigma * *ppAkk;
00594       A2[k] = -eta * sigma;
00595       for(int j = k + 1; j < nc; j++) {
00596         double * ppAik = ppAkk, sum = 0;
00597         for(int i = k; i < nr; i++) {
00598           sum += *ppAik * ppAik[j - k];
00599           ppAik += nc;
00600         }
00601         double tau = sum / A1[k];
00602         ppAik = ppAkk;
00603         for(int i = k; i < nr; i++) {
00604           ppAik[j - k] -= tau * *ppAik;
00605           ppAik += nc;
00606         }
00607       }
00608     }
00609     ppAkk += nc + 1;
00610   }
00611 
00612   // b <- Qt b
00613   double * ppAjj = pA, * pb = b->data.db;
00614   for(int j = 0; j < nc; j++) {
00615     double * ppAij = ppAjj, tau = 0;
00616     for(int i = j; i < nr; i++) {
00617       tau += *ppAij * pb[i];
00618       ppAij += nc;
00619     }
00620     tau /= A1[j];
00621     ppAij = ppAjj;
00622     for(int i = j; i < nr; i++) {
00623       pb[i] -= tau * *ppAij;
00624       ppAij += nc;
00625     }
00626     ppAjj += nc + 1;
00627   }
00628 
00629   // X = R-1 b
00630   double * pX = X->data.db;
00631   pX[nc - 1] = pb[nc - 1] / A2[nc - 1];
00632   for(int i = nc - 2; i >= 0; i--) {
00633     double * ppAij = pA + i * nc + (i + 1), sum = 0;
00634 
00635     for(int j = i + 1; j < nc; j++) {
00636       sum += *ppAij * pX[j];
00637       ppAij++;
00638     }
00639     pX[i] = (pb[i] - sum) / A2[i];
00640   }
00641 }
00642 
00643 
00644 
00645 void epnp::relative_error(double & rot_err, double & transl_err,
00646                           const double Rtrue[3][3], const double ttrue[3],
00647                           const double Rest[3][3],  const double test[3])
00648 {
00649   double qtrue[4], qest[4];
00650 
00651   mat_to_quat(Rtrue, qtrue);
00652   mat_to_quat(Rest, qest);
00653 
00654   double rot_err1 = sqrt((qtrue[0] - qest[0]) * (qtrue[0] - qest[0]) +
00655                          (qtrue[1] - qest[1]) * (qtrue[1] - qest[1]) +
00656                          (qtrue[2] - qest[2]) * (qtrue[2] - qest[2]) +
00657                          (qtrue[3] - qest[3]) * (qtrue[3] - qest[3]) ) /
00658     sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]);
00659 
00660   double rot_err2 = sqrt((qtrue[0] + qest[0]) * (qtrue[0] + qest[0]) +
00661                          (qtrue[1] + qest[1]) * (qtrue[1] + qest[1]) +
00662                          (qtrue[2] + qest[2]) * (qtrue[2] + qest[2]) +
00663                          (qtrue[3] + qest[3]) * (qtrue[3] + qest[3]) ) /
00664     sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]);
00665 
00666   rot_err = min(rot_err1, rot_err2);
00667 
00668   transl_err =
00669     sqrt((ttrue[0] - test[0]) * (ttrue[0] - test[0]) +
00670          (ttrue[1] - test[1]) * (ttrue[1] - test[1]) +
00671          (ttrue[2] - test[2]) * (ttrue[2] - test[2])) /
00672     sqrt(ttrue[0] * ttrue[0] + ttrue[1] * ttrue[1] + ttrue[2] * ttrue[2]);
00673 }
00674 
00675 void epnp::mat_to_quat(const double R[3][3], double q[4])
00676 {
00677   double tr = R[0][0] + R[1][1] + R[2][2];
00678   double n4;
00679 
00680   if (tr > 0.0f) {
00681     q[0] = R[1][2] - R[2][1];
00682     q[1] = R[2][0] - R[0][2];
00683     q[2] = R[0][1] - R[1][0];
00684     q[3] = tr + 1.0f;
00685     n4 = q[3];
00686   } else if ( (R[0][0] > R[1][1]) && (R[0][0] > R[2][2]) ) {
00687     q[0] = 1.0f + R[0][0] - R[1][1] - R[2][2];
00688     q[1] = R[1][0] + R[0][1];
00689     q[2] = R[2][0] + R[0][2];
00690     q[3] = R[1][2] - R[2][1];
00691     n4 = q[0];
00692   } else if (R[1][1] > R[2][2]) {
00693     q[0] = R[1][0] + R[0][1];
00694     q[1] = 1.0f + R[1][1] - R[0][0] - R[2][2];
00695     q[2] = R[2][1] + R[1][2];
00696     q[3] = R[2][0] - R[0][2];
00697     n4 = q[1];
00698   } else {
00699     q[0] = R[2][0] + R[0][2];
00700     q[1] = R[2][1] + R[1][2];
00701     q[2] = 1.0f + R[2][2] - R[0][0] - R[1][1];
00702     q[3] = R[0][1] - R[1][0];
00703     n4 = q[2];
00704   }
00705   double scale = 0.5f / double(sqrt(n4));
00706 
00707   q[0] *= scale;
00708   q[1] *= scale;
00709   q[2] *= scale;
00710   q[3] *= scale;
00711 }


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:31:08