00001
00002 #include "Bundle.h"
00003 #include "MEstimator.h"
00004 #include <TooN/helpers.h>
00005 #include <TooN/Cholesky.h>
00006 #include <fstream>
00007 #include <iomanip>
00008 #include <gvars3/instances.h>
00009
00010 using namespace GVars3;
00011 using namespace std;
00012
00013 #ifdef WIN32
00014 inline bool isnan(double d) {return !(d==d);}
00015 #endif
00016
00017 #include "settingsCustom.h"
00018
00019 #define cout if(*mgvnBundleCout) cout
00020
00021
00022
00023 inline void BundleTriangle_UpdateM6U_LL(Matrix<6> &m6U, Matrix<2,6> &m26A)
00024 {
00025 for(int r=0; r<6; r++)
00026 for(int c=0; c<=r; c++)
00027 m6U(r,c)+= m26A.T()(r,0)*m26A(0,c) + m26A.T()(r,1)*m26A(1,c);
00028 }
00029 inline void BundleTriangle_UpdateM3V_LL(Matrix<3> &m3V, Matrix<2,3> &m23B)
00030 {
00031 for(int r=0; r<3; r++)
00032 for(int c=0; c<=r; c++)
00033 m3V(r,c)+= m23B.T()(r,0)*m23B(0,c) + m23B.T()(r,1)*m23B(1,c);
00034 }
00035
00036
00037 Bundle::Bundle(const ATANCamera &TCam)
00038 : mCamera(TCam)
00039 {
00040 mnCamsToUpdate = 0;
00041 mnStartRow = 0;
00042 GV3::Register(mgvnMaxIterations, "Bundle.MaxIterations", BUNDLE_MAX_ITERATIONS, SILENT);
00043 GV3::Register(mgvdUpdateConvergenceLimit, "Bundle.UpdateSquaredConvergenceLimit", BUNDLE_UPDATE_SQUARED_CONV_LIMIT, SILENT);
00044 GV3::Register(mgvnBundleCout, "Bundle.Cout", BUNDLE_COUT, SILENT);
00045 };
00046
00047
00048 int Bundle::AddCamera(SE3<> se3CamFromWorld, bool bFixed)
00049 {
00050 int n = mvCameras.size();
00051 Camera c;
00052 c.bFixed = bFixed;
00053 c.se3CfW = se3CamFromWorld;
00054 if(!bFixed)
00055 {
00056 c.nStartRow = mnStartRow;
00057 mnStartRow += 6;
00058 mnCamsToUpdate++;
00059 }
00060 else
00061 c.nStartRow = -999999999;
00062 mvCameras.push_back(c);
00063
00064 return n;
00065 }
00066
00067
00068 int Bundle::AddPoint(Vector<3> v3Pos)
00069 {
00070 int n = mvPoints.size();
00071 Point p;
00072 if(isnan(v3Pos * v3Pos))
00073 {
00074 cerr << " You sucker, tried to give me a nan " << v3Pos << endl;
00075 v3Pos = Zeros;
00076 }
00077 p.v3Pos = v3Pos;
00078 mvPoints.push_back(p);
00079 return n;
00080 }
00081
00082
00083 void Bundle::AddMeas(int nCam, int nPoint, Vector<2> v2Pos, double dSigmaSquared)
00084 {
00085 assert(nCam < (int) mvCameras.size());
00086 assert(nPoint < (int) mvPoints.size());
00087 mvPoints[nPoint].nMeasurements++;
00088 mvPoints[nPoint].sCameras.insert(nCam);
00089 Meas m;
00090 m.p = nPoint;
00091 m.c = nCam;
00092 m.v2Found = v2Pos;
00093 m.dSqrtInvNoise = sqrt(1.0 / dSigmaSquared);
00094 mMeasList.push_back(m);
00095 }
00096
00097
00098 void Bundle::ClearAccumulators()
00099 {
00100 for(size_t i=0; i<mvPoints.size(); ++i)
00101 {
00102 mvPoints[i].m3V = Zeros;
00103 mvPoints[i].v3EpsilonB = Zeros;
00104 }
00105 for(size_t i=0; i<mvCameras.size(); ++i)
00106 {
00107 mvCameras[i].m6U = Zeros;
00108 mvCameras[i].v6EpsilonA = Zeros;
00109 }
00110 }
00111
00112
00113
00114
00115
00116
00117 int Bundle::Compute(bool *pbAbortSignal)
00118 {
00119 mpbAbortSignal = pbAbortSignal;
00120
00121
00122 GenerateMeasLUTs();
00123 GenerateOffDiagScripts();
00124
00125
00126 mdLambda = 0.0001;
00127 mdLambdaFactor = 2.0;
00128 mbConverged = false;
00129 mbHitMaxIterations = false;
00130 mnCounter = 0;
00131 mnAccepted = 0;
00132
00133
00134 static gvar3<string> gvsMEstimator("BundleMEstimator", BUNDLE_M_ESTIMATOR, SILENT);
00135
00136 while(!mbConverged && !mbHitMaxIterations && !*pbAbortSignal)
00137 {
00138 bool bNoError;
00139 if(*gvsMEstimator == "Cauchy")
00140 bNoError = Do_LM_Step<Cauchy>(pbAbortSignal);
00141 else if(*gvsMEstimator == "Tukey")
00142 bNoError = Do_LM_Step<Tukey>(pbAbortSignal);
00143 else if(*gvsMEstimator == "Huber")
00144 bNoError = Do_LM_Step<Huber>(pbAbortSignal);
00145 else
00146 {
00147 cout << "Invalid BundleMEstimator selected !! " << endl;
00148 cout << "Defaulting to Tukey." << endl;
00149 *gvsMEstimator = "Tukey";
00150 bNoError = Do_LM_Step<Tukey>(pbAbortSignal);
00151 };
00152
00153 if(!bNoError)
00154 return -1;
00155 }
00156
00157 if(mbHitMaxIterations)
00158 cout << " Hit max iterations." << endl;
00159 cout << "Final Sigma Squared: " << mdSigmaSquared << " (= " << sqrt(mdSigmaSquared) / 4.685 << " pixels.)" << endl;
00160 return mnAccepted;
00161 };
00162
00163
00164 inline void Bundle::ProjectAndFindSquaredError(Meas &meas)
00165 {
00166 Camera &cam = mvCameras[meas.c];
00167 Point &point = mvPoints[meas.p];
00168
00169
00170 meas.v3Cam = cam.se3CfW * point.v3Pos;
00171 if(meas.v3Cam[2] <= 0)
00172 {
00173 meas.bBad = true;
00174 return;
00175 }
00176 meas.bBad = false;
00177 Vector<2> v2ImPlane = project(meas.v3Cam);
00178 Vector<2> v2Image = mCamera.Project(v2ImPlane);
00179 meas.m2CamDerivs = mCamera.GetProjectionDerivs();
00180 meas.v2Epsilon = meas.dSqrtInvNoise * (meas.v2Found - v2Image);
00181 meas.dErrorSquared = meas.v2Epsilon * meas.v2Epsilon;
00182 }
00183
00184 template<class MEstimator>
00185 bool Bundle::Do_LM_Step(bool *pbAbortSignal)
00186 {
00187
00188 ClearAccumulators();
00189
00190
00191
00192
00193 vector<double> vdErrorSquared;
00194 for(list<Meas>::iterator itr = mMeasList.begin(); itr!=mMeasList.end(); itr++)
00195 {
00196 Meas &meas = *itr;
00197 ProjectAndFindSquaredError(meas);
00198 if(!meas.bBad)
00199 vdErrorSquared.push_back(meas.dErrorSquared);
00200 };
00201
00202
00203
00204
00205
00206 if(vdErrorSquared.size() < 1) return false;
00207 mdSigmaSquared = MEstimator::FindSigmaSquared(vdErrorSquared);
00208
00209
00210
00211 static gvar3<double> gvdMinSigma("Bundle.MinTukeySigma", BUNDLE_MIN_TUKEY_SIGMA, SILENT);
00212 const double dMinSigmaSquared = *gvdMinSigma * *gvdMinSigma;
00213 if(mdSigmaSquared < dMinSigmaSquared)
00214 mdSigmaSquared = dMinSigmaSquared;
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227 double dCurrentError = 0.0;
00228 for(list<Meas>::iterator itr = mMeasList.begin(); itr!=mMeasList.end(); itr++)
00229 {
00230 Meas &meas = *itr;
00231 Camera &cam = mvCameras[meas.c];
00232 Point &point = mvPoints[meas.p];
00233
00234
00235
00236 if(meas.bBad)
00237 {
00238 dCurrentError += 1.0;
00239 continue;
00240 };
00241
00242
00243
00244
00245
00246
00247 double dWeight= MEstimator::SquareRootWeight(meas.dErrorSquared, mdSigmaSquared);
00248
00249 meas.v2Epsilon = dWeight * meas.v2Epsilon;
00250
00251 if(dWeight == 0)
00252 {
00253 meas.bBad = true;
00254 dCurrentError += 1.0;
00255 continue;
00256 }
00257
00258 dCurrentError += MEstimator::ObjectiveScore(meas.dErrorSquared, mdSigmaSquared);
00259
00260
00261
00262 Matrix<2> m2CamDerivs = dWeight * meas.m2CamDerivs;
00263
00264 const double dOneOverCameraZ = 1.0 / meas.v3Cam[2];
00265 const Vector<4> v4Cam = unproject(meas.v3Cam);
00266
00267
00268 if(cam.bFixed)
00269 meas.m26A = Zeros;
00270 else
00271 {
00272 for(int m=0;m<6;m++)
00273 {
00274 const Vector<4> v4Motion = SE3<>::generator_field(m, v4Cam);
00275 Vector<2> v2CamFrameMotion;
00276 v2CamFrameMotion[0] = (v4Motion[0] - v4Cam[0] * v4Motion[2] * dOneOverCameraZ) * dOneOverCameraZ;
00277 v2CamFrameMotion[1] = (v4Motion[1] - v4Cam[1] * v4Motion[2] * dOneOverCameraZ) * dOneOverCameraZ;
00278 meas.m26A.T()[m] = meas.dSqrtInvNoise * m2CamDerivs * v2CamFrameMotion;
00279 };
00280 }
00281
00282
00283 for(int m=0;m<3;m++)
00284 {
00285 const Vector<3> v3Motion = cam.se3CfW.get_rotation().get_matrix().T()[m];
00286 Vector<2> v2CamFrameMotion;
00287 v2CamFrameMotion[0] = (v3Motion[0] - v4Cam[0] * v3Motion[2] * dOneOverCameraZ) * dOneOverCameraZ;
00288 v2CamFrameMotion[1] = (v3Motion[1] - v4Cam[1] * v3Motion[2] * dOneOverCameraZ) * dOneOverCameraZ;
00289 meas.m23B.T()[m] = meas.dSqrtInvNoise * m2CamDerivs * v2CamFrameMotion;
00290 };
00291
00292
00293 if(!cam.bFixed)
00294 {
00295
00296 BundleTriangle_UpdateM6U_LL(cam.m6U, meas.m26A);
00297 cam.v6EpsilonA += meas.m26A.T() * meas.v2Epsilon;
00298
00299 }
00300
00301
00302 BundleTriangle_UpdateM3V_LL(point.m3V, meas.m23B);
00303 point.v3EpsilonB += meas.m23B.T() * meas.v2Epsilon;
00304
00305 if(cam.bFixed)
00306 meas.m63W = Zeros;
00307 else
00308 meas.m63W = meas.m26A.T() * meas.m23B;
00309 }
00310
00311
00312
00313
00314 double dNewError = dCurrentError + 9999;
00315 while(dNewError > dCurrentError && !mbConverged && !mbHitMaxIterations && !*pbAbortSignal)
00316 {
00317
00318 for(vector<Point>::iterator itr = mvPoints.begin(); itr!=mvPoints.end(); itr++)
00319 {
00320 Point &point = *itr;
00321 Matrix<3> m3VStar = point.m3V;
00322 if(m3VStar[0][0] * m3VStar[1][1] * m3VStar[2][2] == 0)
00323 point.m3VStarInv = Zeros;
00324 else
00325 {
00326
00327 m3VStar[0][1] = m3VStar[1][0];
00328 m3VStar[0][2] = m3VStar[2][0];
00329 m3VStar[1][2] = m3VStar[2][1];
00330
00331 for(int i=0; i<3; i++)
00332 m3VStar[i][i] *= (1.0 + mdLambda);
00333 Cholesky<3> chol(m3VStar);
00334 point.m3VStarInv = chol.get_inverse();
00335 };
00336 }
00337
00338
00339
00340
00341
00342 Matrix<> mS(mnCamsToUpdate * 6, mnCamsToUpdate * 6);
00343 mS = Zeros;
00344 Vector<> vE(mnCamsToUpdate * 6);
00345 vE = Zeros;
00346
00347 Matrix<6> m6;
00348 Vector<6> v6;
00349
00350
00351 for(unsigned int j=0; j<mvCameras.size(); j++)
00352 {
00353 Camera &cam_j = mvCameras[j];
00354 if(cam_j.bFixed) continue;
00355 int nCamJStartRow = cam_j.nStartRow;
00356
00357
00358
00359 for(int r=0; r<6; r++)
00360 {
00361 for(int c=0; c<r; c++)
00362 m6[r][c] = m6[c][r] = cam_j.m6U[r][c];
00363 m6[r][r] = cam_j.m6U[r][r];
00364 };
00365
00366 for(int nn = 0; nn< 6; nn++)
00367 m6[nn][nn] *= (1.0 + mdLambda);
00368
00369 v6 = cam_j.v6EpsilonA;
00370
00371 vector<Meas*> &vMeasLUTj = mvMeasLUTs[j];
00372
00373 for(unsigned int i=0; i<mvPoints.size(); i++)
00374 {
00375 Meas* pMeas = vMeasLUTj[i];
00376 if(pMeas == NULL || pMeas->bBad)
00377 continue;
00378 m6 -= pMeas->m63W * mvPoints[i].m3VStarInv * pMeas->m63W.T();
00379 v6 -= pMeas->m63W * (mvPoints[i].m3VStarInv * mvPoints[i].v3EpsilonB);
00380 }
00381 mS.slice(nCamJStartRow, nCamJStartRow, 6, 6) = m6;
00382 vE.slice(nCamJStartRow,6) = v6;
00383 }
00384
00385
00386
00387 for(unsigned int i=0; i<mvPoints.size(); i++)
00388 {
00389 Point &p = mvPoints[i];
00390 int nCurrentJ = -1;
00391 int nJRow = -1;
00392 Meas* pMeas_ij;
00393 Meas* pMeas_ik;
00394 Matrix<6,3> m63_MIJW_times_m3VStarInv;
00395
00396 for(vector<OffDiagScriptEntry>::iterator it=p.vOffDiagonalScript.begin();
00397 it!=p.vOffDiagonalScript.end();
00398 it++)
00399 {
00400 OffDiagScriptEntry &e = *it;
00401 pMeas_ik = mvMeasLUTs[e.k][i];
00402 if(pMeas_ik == NULL || pMeas_ik->bBad)
00403 continue;
00404 if(e.j != nCurrentJ)
00405 {
00406 pMeas_ij = mvMeasLUTs[e.j][i];
00407 if(pMeas_ij == NULL || pMeas_ij->bBad)
00408 continue;
00409 nCurrentJ = e.j;
00410 nJRow = mvCameras[e.j].nStartRow;
00411 m63_MIJW_times_m3VStarInv = pMeas_ij->m63W * p.m3VStarInv;
00412 }
00413 int nKRow = mvCameras[pMeas_ik->c].nStartRow;
00414 #ifndef WIN32
00415 mS.slice(nJRow, nKRow, 6, 6) -= m63_MIJW_times_m3VStarInv * pMeas_ik->m63W.T();
00416 #else
00417 Matrix<6> m = mS.slice(nJRow, nKRow, 6, 6);
00418 m -= m63_MIJW_times_m3VStarInv * pMeas_ik->m63W.T();
00419 mS.slice(nJRow, nKRow, 6, 6) = m;
00420 #endif
00421 assert(nKRow < nJRow);
00422 }
00423 }
00424
00425
00426
00427
00428 for(int i=0; i<mS.num_rows(); i++)
00429 for(int j=0; j<i; j++)
00430 mS[j][i] = mS[i][j];
00431
00432
00433
00434 Vector<> vCamerasUpdate(mS.num_rows());
00435 vCamerasUpdate = Cholesky<>(mS).backsub(vE);
00436
00437
00438 Vector<> vMapUpdates(mvPoints.size() * 3);
00439 for(unsigned int i=0; i<mvPoints.size(); i++)
00440 {
00441 Vector<3> v3Sum;
00442 v3Sum = Zeros;
00443 for(unsigned int j=0; j<mvCameras.size(); j++)
00444 {
00445 Camera &cam = mvCameras[j];
00446 if(cam.bFixed)
00447 continue;
00448 Meas *pMeas = mvMeasLUTs[j][i];
00449 if(pMeas == NULL || pMeas->bBad)
00450 continue;
00451 v3Sum+=pMeas->m63W.T() * vCamerasUpdate.slice(cam.nStartRow,6);
00452 }
00453 Vector<3> v3 = mvPoints[i].v3EpsilonB - v3Sum;
00454 vMapUpdates.slice(i * 3, 3) = mvPoints[i].m3VStarInv * v3;
00455 if(isnan(vMapUpdates.slice(i * 3, 3) * vMapUpdates.slice(i * 3, 3)))
00456 {
00457 cerr << "NANNERY! " << endl;
00458 cerr << mvPoints[i].m3VStarInv << endl;
00459 };
00460 }
00461
00462
00463
00464
00465 double dSumSquaredUpdate = vCamerasUpdate * vCamerasUpdate + vMapUpdates * vMapUpdates;
00466 if(dSumSquaredUpdate< *mgvdUpdateConvergenceLimit)
00467 mbConverged = true;
00468
00469
00470
00471
00472
00473 for(unsigned int j=0; j<mvCameras.size(); j++)
00474 {
00475 if(mvCameras[j].bFixed)
00476 mvCameras[j].se3CfWNew = mvCameras[j].se3CfW;
00477 else
00478 mvCameras[j].se3CfWNew = SE3<>::exp(vCamerasUpdate.slice(mvCameras[j].nStartRow, 6)) * mvCameras[j].se3CfW;
00479 }
00480 for(unsigned int i=0; i<mvPoints.size(); i++)
00481 mvPoints[i].v3PosNew = mvPoints[i].v3Pos + vMapUpdates.slice(i*3, 3);
00482
00483 dNewError = FindNewError<MEstimator>();
00484
00485 cout <<setprecision(1) << "L" << mdLambda << setprecision(3) << "\tOld " << dCurrentError << " New " << dNewError << " Diff " << dCurrentError - dNewError << "\t";
00486
00487
00488
00489 if(dNewError > dCurrentError)
00490 {
00491 cout << " TRY AGAIN " << endl;
00492 ModifyLambda_BadStep();
00493 };
00494
00495 mnCounter++;
00496 if(mnCounter >= *mgvnMaxIterations)
00497 mbHitMaxIterations = true;
00498 }
00499
00500 if(dNewError < dCurrentError)
00501 {
00502 cout << " WINNER ------------ " << endl;
00503
00504 ModifyLambda_GoodStep();
00505 for(unsigned int j=0; j<mvCameras.size(); j++)
00506 mvCameras[j].se3CfW = mvCameras[j].se3CfWNew;
00507 for(unsigned int i=0; i<mvPoints.size(); i++)
00508 mvPoints[i].v3Pos = mvPoints[i].v3PosNew;
00509 mnAccepted++;
00510 }
00511
00512
00513 vector<list<Meas>::iterator> vit;
00514 for(list<Meas>::iterator itr = mMeasList.begin(); itr!=mMeasList.end(); itr++)
00515 if(itr->bBad)
00516 {
00517 vit.push_back(itr);
00518 mvOutlierMeasurementIdx.push_back(make_pair(itr->p, itr->c));
00519 mvPoints[itr->p].nOutliers++;
00520 mvMeasLUTs[itr->c][itr->p] = NULL;
00521 };
00522
00523 for(unsigned int i=0; i<vit.size(); i++)
00524 mMeasList.erase(vit[i]);
00525
00526 cout << "Nuked " << vit.size() << " measurements." << endl;
00527 return true;
00528 }
00529
00530
00531
00532 template<class MEstimator>
00533 double Bundle::FindNewError()
00534 {
00535 ofstream ofs;
00536 double dNewError = 0;
00537 vector<double> vdErrorSquared;
00538 for(list<Meas>::iterator itr = mMeasList.begin(); itr!=mMeasList.end(); itr++)
00539 {
00540 Meas &meas = *itr;
00541
00542 Vector<3> v3Cam = mvCameras[meas.c].se3CfWNew * mvPoints[meas.p].v3PosNew;
00543 if(v3Cam[2] <= 0)
00544 {
00545 dNewError += 1.0;
00546 cout << ".";
00547 continue;
00548 };
00549 Vector<2> v2ImPlane = project(v3Cam);
00550 Vector<2> v2Image = mCamera.Project(v2ImPlane);
00551 Vector<2> v2Error = meas.dSqrtInvNoise * (meas.v2Found - v2Image);
00552 double dErrorSquared = v2Error * v2Error;
00553 dNewError += MEstimator::ObjectiveScore(dErrorSquared, mdSigmaSquared);
00554 }
00555 return dNewError;
00556 }
00557
00558
00559
00560
00561 void Bundle::GenerateMeasLUTs()
00562 {
00563 mvMeasLUTs.clear();
00564 for(unsigned int nCam = 0; nCam < mvCameras.size(); nCam++)
00565 {
00566 mvMeasLUTs.push_back(vector<Meas*>());
00567 mvMeasLUTs.back().resize(mvPoints.size(), NULL);
00568 };
00569 for(list<Meas>::iterator it = mMeasList.begin(); it!=mMeasList.end(); it++)
00570 mvMeasLUTs[it->c][it->p] = &(*it);
00571 }
00572
00573
00574
00575
00576 void Bundle::GenerateOffDiagScripts()
00577 {
00578 for(unsigned int i=0; i<mvPoints.size(); i++)
00579 {
00580 Point &p = mvPoints[i];
00581 p.vOffDiagonalScript.clear();
00582 for(set<int>::iterator it_j = p.sCameras.begin(); it_j!=p.sCameras.end(); it_j++)
00583 {
00584 int j = *it_j;
00585 if(mvCameras[j].bFixed)
00586 continue;
00587 Meas *pMeas_j = mvMeasLUTs[j][i];
00588 assert(pMeas_j != NULL);
00589
00590 for(set<int>::iterator it_k = p.sCameras.begin(); it_k!=it_j; it_k++)
00591 {
00592 int k = *it_k;
00593 if(mvCameras[k].bFixed)
00594 continue;
00595
00596 Meas *pMeas_k = mvMeasLUTs[k][i];
00597 assert(pMeas_k != NULL);
00598
00599 OffDiagScriptEntry e;
00600 e.j = j;
00601 e.k = k;
00602 p.vOffDiagonalScript.push_back(e);
00603 }
00604 }
00605 }
00606 }
00607
00608 void Bundle::ModifyLambda_GoodStep()
00609 {
00610 mdLambdaFactor = 2.0;
00611 mdLambda *= 0.3;
00612 };
00613
00614 void Bundle::ModifyLambda_BadStep()
00615 {
00616 mdLambda = mdLambda * mdLambdaFactor;
00617 mdLambdaFactor = mdLambdaFactor * 2;
00618 };
00619
00620
00621 Vector<3> Bundle::GetPoint(int n)
00622 {
00623 return mvPoints.at(n).v3Pos;
00624 }
00625
00626 SE3<> Bundle::GetCamera(int n)
00627 {
00628 return mvCameras.at(n).se3CfW;
00629 }
00630
00631 set<int> Bundle::GetOutliers()
00632 {
00633 set<int> sOutliers;
00634 set<int>::iterator hint = sOutliers.begin();
00635 for(unsigned int i=0; i<mvPoints.size(); i++)
00636 {
00637 Point &p = mvPoints[i];
00638 if(p.nMeasurements > 0 && p.nMeasurements == p.nOutliers)
00639 hint = sOutliers.insert(hint, i);
00640 }
00641 return sOutliers;
00642 };
00643
00644
00645 vector<pair<int, int> > Bundle::GetOutlierMeasurements()
00646 {
00647 return mvOutlierMeasurementIdx;
00648 }
00649
00650
00651
00652
00653
00654
00655
00656
00657