00001
00002 #include "OpenGL.h"
00003 #include "Tracker.h"
00004 #include "MEstimator.h"
00005 #include "ShiTomasi.h"
00006 #include "SmallMatrixOpts.h"
00007 #include "PatchFinder.h"
00008 #include "TrackerData.h"
00009
00010 #include <cvd/utility.h>
00011 #include <cvd/gl_helpers.h>
00012 #include <cvd/fast_corner.h>
00013 #include <cvd/vision.h>
00014 #include <TooN/wls.h>
00015 #include <gvars3/instances.h>
00016 #include <gvars3/GStringUtil.h>
00017
00018 #include <fstream>
00019 #include <fcntl.h>
00020
00021 #include "settingsCustom.h"
00022
00023 using namespace CVD;
00024 using namespace std;
00025 using namespace GVars3;
00026
00027
00028
00029 Tracker::Tracker(ImageRef irVideoSize, const ATANCamera &c, Map &m, MapMaker &mm) :
00030 mMap(m),
00031 mMapMaker(mm),
00032 mCamera(c),
00033 mRelocaliser(mMap, mCamera),
00034 mirSize(irVideoSize)
00035 {
00036 mCurrentKF.bFixed = false;
00037
00038
00039
00040 TrackerData::irImageSize = mirSize;
00041
00042 mpSBILastFrame = NULL;
00043 mpSBIThisFrame = NULL;
00044 mnLastKeyFrameDroppedClock = 0;
00045
00046
00047
00048 Reset();
00049 }
00050
00051
00052
00053
00054 void Tracker::Reset()
00055 {
00056 mbDidCoarse = false;
00057 mbUserPressedSpacebar = false;
00058 mTrackingQuality = GOOD;
00059 mnLostFrames = 0;
00060 mdMSDScaledVelocityMagnitude = 0;
00061 mCurrentKF.dSceneDepthMean = 1.0;
00062 mCurrentKF.dSceneDepthSigma = 1.0;
00063 mnInitialStage = TRAIL_TRACKING_NOT_STARTED;
00064 mlTrails.clear();
00065 mCamera.SetImageSize(mirSize);
00066 mCurrentKF.mMeasurements.clear();
00067 mnLastKeyFrameDropped = -20;
00068 mnLastKeyFrameDroppedClock = 0;
00069 mnFrame=0;
00070 mv6CameraVelocity = Zeros;
00071 mbJustRecoveredSoUseCoarse = false;
00072 predictedCFromW = SE3<>();
00073
00074
00075
00076
00077
00078 mMapMaker.RequestReset();
00079 while(!mMapMaker.ResetDone())
00080 #ifndef WIN32
00081 usleep(10);
00082 #else
00083 Sleep(1);
00084 #endif
00085 }
00086
00087
00088
00089
00090
00091 void Tracker::TrackFrame(Image<byte> &imFrame, bool bDraw)
00092 {
00093 mbDraw = bDraw;
00094 mMessageForUser.str("");
00095
00096
00097
00098 mCurrentKF.mMeasurements.clear();
00099 mCurrentKF.MakeKeyFrame_Lite(imFrame);
00100
00101
00102 static gvar3<double> gvdSBIBlur("Tracker.RotationEstimatorBlur", TRACKER_ROTATION_ESTIMATOR_BLUR, SILENT);
00103 static gvar3<int> gvnUseSBI("Tracker.UseRotationEstimator", 1, SILENT);
00104 mbUseSBIInit = *gvnUseSBI;
00105 if(!mpSBIThisFrame)
00106 {
00107 mpSBIThisFrame = new SmallBlurryImage(mCurrentKF, *gvdSBIBlur);
00108 mpSBILastFrame = new SmallBlurryImage(mCurrentKF, *gvdSBIBlur);
00109 }
00110 else
00111 {
00112 delete mpSBILastFrame;
00113 mpSBILastFrame = mpSBIThisFrame;
00114 mpSBIThisFrame = new SmallBlurryImage(mCurrentKF, *gvdSBIBlur);
00115 }
00116
00117
00118 mnFrame++;
00119
00120 if(mbDraw)
00121 {
00122 glDrawPixels(mCurrentKF.aLevels[0].im);
00123 if(GV2.GetInt("Tracker.DrawFASTCorners",TRACKER_DRAW_FAST_CORNERS_DEFAULT, SILENT))
00124 {
00125 glColor3f(1,0,1); glPointSize(1); glBegin(GL_POINTS);
00126 for(unsigned int i=0; i<mCurrentKF.aLevels[0].vCorners.size(); i++)
00127 glVertex(mCurrentKF.aLevels[0].vCorners[i]);
00128 glEnd();
00129 }
00130 }
00131
00132
00133 if(mMap.IsGood())
00134 {
00135 if(mnLostFrames < 3)
00136 {
00137 if(mbUseSBIInit)
00138 CalcSBIRotation();
00139
00140 ApplyMotionModel();
00141 TrackMap();
00142 UpdateMotionModel();
00143
00144 AssessTrackingQuality();
00145 if(mTrackingQuality == GOOD)
00146 lastStepResult = T_GOOD;
00147 if(mTrackingQuality == DODGY)
00148 lastStepResult = T_DODGY;
00149 if(mTrackingQuality == BAD)
00150 lastStepResult = T_LOST;
00151
00152
00153 {
00154 mMessageForUser << "Tracking Map, quality ";
00155 if(mTrackingQuality == GOOD) mMessageForUser << "good.";
00156 if(mTrackingQuality == DODGY) mMessageForUser << "poor.";
00157 if(mTrackingQuality == BAD) mMessageForUser << "bad.";
00158 mMessageForUser << " Found:";
00159 for(int i=0; i<LEVELS; i++) mMessageForUser << " " << manMeasFound[i] << "/" << manMeasAttempted[i];
00160
00161 mMessageForUser << " Map: " << mMap.vpPoints.size() << "P, " << mMap.vpKeyFrames.size() << "KF";
00162 }
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174 }
00175 else
00176 {
00177 tryToRecover();
00178 }
00179
00180
00181 }
00182 else
00183 {
00184
00185
00186
00187 TrackForInitialMap();
00188 }
00189
00190
00191 while(!mvQueuedCommands.empty())
00192 {
00193 GUICommandHandler(mvQueuedCommands.begin()->sCommand, mvQueuedCommands.begin()->sParams);
00194 mvQueuedCommands.erase(mvQueuedCommands.begin());
00195 }
00196 };
00197
00198
00199 void Tracker::tryToRecover()
00200 {
00201 if(mMap.IsGood())
00202 {
00203 mMessageForUser.str("");
00204 mMessageForUser << "** Attempting recovery **.";
00205 if(AttemptRecovery())
00206 {
00207 TrackMap();
00208 AssessTrackingQuality();
00209
00210 if(mTrackingQuality == GOOD)
00211 lastStepResult = T_RECOVERED_GOOD;
00212 if(mTrackingQuality == DODGY)
00213 lastStepResult = T_RECOVERED_DODGY;
00214 if(mTrackingQuality == BAD)
00215 lastStepResult = T_LOST;
00216 }
00217 else
00218 lastStepResult = T_LOST;
00219 }
00220 }
00221
00222 void Tracker::TakeKF(bool force)
00223 {
00224 if(mMap.IsGood())
00225 {
00226
00227 if(mTrackingQuality == GOOD && (force || (
00228 mMapMaker.NeedNewKeyFrame(mCurrentKF) &&
00229 ((double)(clock() - mnLastKeyFrameDroppedClock))/CLOCKS_PER_SEC > minKFTimeDist &&
00230 mMapMaker.QueueSize() < 3)))
00231 {
00232 mMessageForUser << " Adding key-frame.";
00233 AddNewKeyFrame();
00234 lastStepResult = T_TOOK_KF;
00235 };
00236 }
00237 }
00238
00239
00240
00241
00242
00243
00244
00245
00246 bool Tracker::AttemptRecovery()
00247 {
00248 if(true)
00249 {
00250 bool bRelocGood = mRelocaliser.AttemptRecovery(mCurrentKF);
00251 if(!bRelocGood)
00252 return false;
00253
00254 SE3<> se3Best = mRelocaliser.BestPose();
00255 mse3CamFromWorld = mse3StartPos = se3Best;
00256 mv6CameraVelocity = Zeros;
00257 mbJustRecoveredSoUseCoarse = true;
00258 return true;
00259 }
00260 else
00261 {
00262 SE3<> se3Best = predictedCFromW;
00263 mse3CamFromWorld = mse3StartPos = se3Best;
00264 mv6CameraVelocity = Zeros;
00265 mbJustRecoveredSoUseCoarse = true;
00266 return true;
00267 }
00268 }
00269
00270
00271 void Tracker::RenderGrid()
00272 {
00273
00274
00275 if(mbDidCoarse)
00276 glColor4f(.0, 0.5, .0, 0.6);
00277 else
00278 glColor4f(0,0,0,0.6);
00279
00280
00281 int nHalfCells = 8;
00282 int nTot = nHalfCells * 2 + 1;
00283 Image<Vector<2> > imVertices(ImageRef(nTot,nTot));
00284 for(int i=0; i<nTot; i++)
00285 for(int j=0; j<nTot; j++)
00286 {
00287 Vector<3> v3;
00288 v3[0] = (i - nHalfCells) * 0.1;
00289 v3[1] = (j - nHalfCells) * 0.1;
00290 v3[2] = 0.0;
00291 Vector<3> v3Cam = mse3CamFromWorld * v3;
00292 if(v3Cam[2] < 0.001)
00293 v3Cam[2] = 0.001;
00294 imVertices[i][j] = mCamera.Project(project(v3Cam));
00295 }
00296 glEnable(GL_LINE_SMOOTH);
00297 glEnable(GL_BLEND);
00298 glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
00299 glLineWidth(2);
00300 for(int i=0; i<nTot; i++)
00301 {
00302 glBegin(GL_LINE_STRIP);
00303 for(int j=0; j<nTot; j++)
00304 glVertex(imVertices[i][j]);
00305 glEnd();
00306
00307 glBegin(GL_LINE_STRIP);
00308 for(int j=0; j<nTot; j++)
00309 glVertex(imVertices[j][i]);
00310 glEnd();
00311 };
00312
00313 glLineWidth(1);
00314 glColor3f(1,0,0);
00315 }
00316
00317
00318
00319
00320 void Tracker::GUICommandCallBack(void* ptr, string sCommand, string sParams)
00321 {
00322 Command c;
00323 c.sCommand = sCommand;
00324 c.sParams = sParams;
00325 ((Tracker*) ptr)->mvQueuedCommands.push_back(c);
00326 }
00327
00328
00329 void Tracker::GUICommandHandler(string sCommand, string sParams)
00330 {
00331 if(sCommand=="Reset")
00332 {
00333 Reset();
00334 return;
00335 }
00336
00337
00338 if(sCommand=="KeyPress")
00339 {
00340 if(sParams == "Space")
00341 {
00342 mbUserPressedSpacebar = true;
00343 }
00344 else if(sParams == "r")
00345 {
00346 Reset();
00347 }
00348 else if(sParams == "q" || sParams == "Escape")
00349 {
00350 GUI.ParseLine("quit");
00351 }
00352 return;
00353 }
00354 if((sCommand=="PokeTracker"))
00355 {
00356 mbUserPressedSpacebar = true;
00357 return;
00358 }
00359
00360
00361 cout << "! Tracker::GUICommandHandler: unhandled command "<< sCommand << endl;
00362 exit(1);
00363 };
00364
00365
00366
00367
00368
00369
00370 void Tracker::TrackForInitialMap()
00371 {
00372
00373
00374 static gvar3<int> gvnMaxSSD("Tracker.MiniPatchMaxSSD", TRACKER_MINIPATCH_MAX_SSD_DEFAULT, SILENT);
00375 MiniPatch::mnMaxSSD = *gvnMaxSSD;
00376
00377
00378 if(mnInitialStage == TRAIL_TRACKING_NOT_STARTED)
00379 {
00380 if(mbUserPressedSpacebar)
00381 {
00382 mbUserPressedSpacebar = false;
00383 TrailTracking_Start();
00384 mnInitialStage = TRAIL_TRACKING_STARTED;
00385 lastStepResult = I_FIRST;
00386 KFZeroDesiredCamFromWorld = predictedCFromW;
00387 }
00388 else
00389 {
00390 lastStepResult = NOT_TRACKING;
00391 mMessageForUser << "Point camera at planar scene and press spacebar to start tracking for initial map." << endl;
00392 }
00393
00394 return;
00395 };
00396
00397 if(mnInitialStage == TRAIL_TRACKING_STARTED)
00398 {
00399 int nGoodTrails = TrailTracking_Advance();
00400 if(nGoodTrails < 10)
00401 {
00402 Reset();
00403 lastStepResult = NOT_TRACKING;
00404 return;
00405 }
00406
00407
00408 if(mbUserPressedSpacebar)
00409 {
00410 mbUserPressedSpacebar = false;
00411 vector<pair<ImageRef, ImageRef> > vMatches;
00412 for(list<Trail>::iterator i = mlTrails.begin(); i!=mlTrails.end(); i++)
00413 vMatches.push_back(pair<ImageRef, ImageRef>(i->irInitialPos,
00414 i->irCurrentPos));
00415 bool succ = mMapMaker.InitFromStereo(mFirstKF, mCurrentKF, vMatches, mse3CamFromWorld, KFZeroDesiredCamFromWorld, predictedCFromW);
00416 if(succ)
00417 lastStepResult = I_SECOND;
00418 else
00419 lastStepResult = I_FAILED;
00420 mnInitialStage = TRAIL_TRACKING_COMPLETE;
00421 }
00422 else
00423 {
00424 lastStepResult = INITIALIZING;
00425 mMessageForUser << "Translate the camera slowly sideways, and press spacebar again to perform stereo init." << endl;
00426 }
00427 }
00428 }
00429
00430
00431 void Tracker::TrailTracking_Start()
00432 {
00433 mCurrentKF.MakeKeyFrame_Rest();
00434 mFirstKF = mCurrentKF;
00435 vector<pair<double,ImageRef> > vCornersAndSTScores;
00436 for(unsigned int i=0; i<mCurrentKF.aLevels[0].vCandidates.size(); i++)
00437 {
00438 Candidate &c = mCurrentKF.aLevels[0].vCandidates[i];
00439 if(!mCurrentKF.aLevels[0].im.in_image_with_border(c.irLevelPos, MiniPatch::mnHalfPatchSize))
00440 continue;
00441 vCornersAndSTScores.push_back(pair<double,ImageRef>(-1.0 * c.dSTScore, c.irLevelPos));
00442 };
00443 sort(vCornersAndSTScores.begin(), vCornersAndSTScores.end());
00444 int nToAdd = GV2.GetInt("MaxInitialTrails", 1000, SILENT);
00445 for(unsigned int i = 0; i<vCornersAndSTScores.size() && nToAdd > 0; i++)
00446 {
00447 if(!mCurrentKF.aLevels[0].im.in_image_with_border(vCornersAndSTScores[i].second, MiniPatch::mnHalfPatchSize))
00448 continue;
00449 Trail t;
00450 t.mPatch.SampleFromImage(vCornersAndSTScores[i].second, mCurrentKF.aLevels[0].im);
00451 t.irInitialPos = vCornersAndSTScores[i].second;
00452 t.irCurrentPos = t.irInitialPos;
00453 mlTrails.push_back(t);
00454 nToAdd--;
00455 }
00456 mPreviousFrameKF = mFirstKF;
00457 }
00458
00459
00460 int Tracker::TrailTracking_Advance()
00461 {
00462 int nGoodTrails = 0;
00463 if(mbDraw)
00464 {
00465 glPointSize(5);
00466 glLineWidth(2);
00467 glEnable(GL_POINT_SMOOTH);
00468 glEnable(GL_LINE_SMOOTH);
00469 glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
00470 glEnable(GL_BLEND);
00471 glBegin(GL_LINES);
00472 }
00473
00474 MiniPatch BackwardsPatch;
00475 Level &lCurrentFrame = mCurrentKF.aLevels[0];
00476 Level &lPreviousFrame = mPreviousFrameKF.aLevels[0];
00477
00478 for(list<Trail>::iterator i = mlTrails.begin(); i!=mlTrails.end();)
00479 {
00480 list<Trail>::iterator next = i; next++;
00481
00482 Trail &trail = *i;
00483 ImageRef irStart = trail.irCurrentPos;
00484 ImageRef irEnd = irStart;
00485 bool bFound = trail.mPatch.FindPatch(irEnd, lCurrentFrame.im, 10, lCurrentFrame.vCorners);
00486 if(bFound)
00487 {
00488
00489 BackwardsPatch.SampleFromImage(irEnd, lCurrentFrame.im);
00490 ImageRef irBackWardsFound = irEnd;
00491 bFound = BackwardsPatch.FindPatch(irBackWardsFound, lPreviousFrame.im, 10, lPreviousFrame.vCorners);
00492 if((irBackWardsFound - irStart).mag_squared() > 2)
00493 bFound = false;
00494
00495 trail.irCurrentPos = irEnd;
00496 nGoodTrails++;
00497 }
00498 if(mbDraw)
00499 {
00500 if(!bFound)
00501 glColor3f(0,1,1);
00502 else
00503 glColor3f(1,1,0);
00504 glVertex(trail.irInitialPos);
00505 if(bFound) glColor3f(1,0,0);
00506 glVertex(trail.irCurrentPos);
00507 }
00508 if(!bFound)
00509 {
00510 mlTrails.erase(i);
00511 }
00512 i = next;
00513 }
00514 if(mbDraw)
00515 glEnd();
00516
00517 mPreviousFrameKF = mCurrentKF;
00518 return nGoodTrails;
00519 }
00520
00521
00522
00523
00524
00525
00526
00527
00528
00529
00530
00531 void Tracker::TrackMap()
00532 {
00533
00534 for(int i=0; i<LEVELS; i++)
00535 manMeasAttempted[i] = manMeasFound[i] = 0;
00536
00537
00538 vector<TrackerData*> avPVS[LEVELS];
00539 for(int i=0; i<LEVELS; i++)
00540 avPVS[i].reserve(500);
00541
00542
00543 for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
00544 {
00545 MapPoint &p= *(mMap.vpPoints[i]);
00546
00547 if(!p.pTData) p.pTData = new TrackerData(&p);
00548 TrackerData &TData = *p.pTData;
00549
00550
00551 TData.Project(mse3CamFromWorld, mCamera);
00552 if(!TData.bInImage)
00553 continue;
00554
00555
00556 TData.GetDerivsUnsafe(mCamera);
00557
00558
00559 TData.nSearchLevel = TData.Finder.CalcSearchLevelAndWarpMatrix(TData.Point, mse3CamFromWorld, TData.m2CamDerivs);
00560 if(TData.nSearchLevel == -1)
00561 continue;
00562
00563
00564 TData.bSearched = false;
00565 TData.bFound = false;
00566 avPVS[TData.nSearchLevel].push_back(&TData);
00567 };
00568
00569
00570
00571 for(int i=0; i<LEVELS; i++)
00572 random_shuffle(avPVS[i].begin(), avPVS[i].end());
00573
00574
00575
00576 vector<TrackerData*> vNextToSearch;
00577 vector<TrackerData*> vIterationSet;
00578
00579
00580 static gvar3<unsigned int> gvnCoarseMin("Tracker.CoarseMin", TRACKER_COARSE_MIN_DEFAULT, SILENT);
00581 static gvar3<unsigned int> gvnCoarseMax("Tracker.CoarseMax", TRACKER_COARSE_MAX_DEFAULT, SILENT);
00582 static gvar3<unsigned int> gvnCoarseRange("Tracker.CoarseRange", TRACKER_COARSE_RANGE_DEFAULT, SILENT);
00583 static gvar3<int> gvnCoarseSubPixIts("Tracker.CoarseSubPixIts", TRACKER_COARSE_SUBPIXELITS_DEFAULT, SILENT);
00584 static gvar3<int> gvnCoarseDisabled("Tracker.DisableCoarse", TRACKER_COARSE_DISABLE_DEFAULT, SILENT);
00585 static gvar3<double> gvdCoarseMinVel("Tracker.CoarseMinVelocity", TRACKER_COARSE_MIN_VELOCITY_DEFAULT, SILENT);
00586
00587 unsigned int nCoarseMax = *gvnCoarseMax;
00588 unsigned int nCoarseRange = *gvnCoarseRange;
00589
00590 mbDidCoarse = false;
00591
00592
00593 bool bTryCoarse = true;
00594 if(*gvnCoarseDisabled ||
00595 mdMSDScaledVelocityMagnitude < *gvdCoarseMinVel ||
00596 nCoarseMax == 0)
00597 bTryCoarse = false;
00598 if(mbJustRecoveredSoUseCoarse)
00599 {
00600 bTryCoarse = true;
00601 nCoarseMax *=2;
00602 nCoarseRange *=2;
00603 mbJustRecoveredSoUseCoarse = false;
00604 };
00605
00606
00607
00608
00609 if(bTryCoarse && avPVS[LEVELS-1].size() + avPVS[LEVELS-2].size() > *gvnCoarseMin )
00610 {
00611
00612
00613
00614
00615 if(avPVS[LEVELS-1].size() <= nCoarseMax)
00616 {
00617 vNextToSearch = avPVS[LEVELS-1];
00618 avPVS[LEVELS-1].clear();
00619 }
00620 else
00621 {
00622 for(unsigned int i=0; i<nCoarseMax; i++)
00623 vNextToSearch.push_back(avPVS[LEVELS-1][i]);
00624 avPVS[LEVELS-1].erase(avPVS[LEVELS-1].begin(), avPVS[LEVELS-1].begin() + nCoarseMax);
00625 }
00626
00627
00628 if(vNextToSearch.size() < nCoarseMax)
00629 {
00630 unsigned int nMoreCoarseNeeded = nCoarseMax - vNextToSearch.size();
00631 if(avPVS[LEVELS-2].size() <= nMoreCoarseNeeded)
00632 {
00633 vNextToSearch = avPVS[LEVELS-2];
00634 avPVS[LEVELS-2].clear();
00635 }
00636 else
00637 {
00638 for(unsigned int i=0; i<nMoreCoarseNeeded; i++)
00639 vNextToSearch.push_back(avPVS[LEVELS-2][i]);
00640 avPVS[LEVELS-2].erase(avPVS[LEVELS-2].begin(), avPVS[LEVELS-2].begin() + nMoreCoarseNeeded);
00641 }
00642 }
00643
00644 unsigned int nFound = SearchForPoints(vNextToSearch, nCoarseRange, *gvnCoarseSubPixIts);
00645 vIterationSet = vNextToSearch;
00646 if(nFound >= *gvnCoarseMin)
00647 {
00648 mbDidCoarse = true;
00649 for(int iter = 0; iter<10; iter++)
00650 {
00651 if(iter != 0)
00652 {
00653 for(unsigned int i=0; i<vIterationSet.size(); i++)
00654 if(vIterationSet[i]->bFound)
00655 vIterationSet[i]->ProjectAndDerivs(mse3CamFromWorld, mCamera);
00656 }
00657 for(unsigned int i=0; i<vIterationSet.size(); i++)
00658 if(vIterationSet[i]->bFound)
00659 vIterationSet[i]->CalcJacobian();
00660 double dOverrideSigma = 0.0;
00661
00662
00663 if(iter > 5)
00664 dOverrideSigma = 1.0;
00665
00666
00667 Vector<6> v6Update =
00668 CalcPoseUpdate(vIterationSet, dOverrideSigma);
00669 mse3CamFromWorld = SE3<>::exp(v6Update) * mse3CamFromWorld;
00670 };
00671 }
00672 };
00673
00674
00675
00676
00677 int nFineRange = 10;
00678 if(mbDidCoarse)
00679 nFineRange = 5;
00680
00681
00682
00683 {
00684 int l = LEVELS - 1;
00685 for(unsigned int i=0; i<avPVS[l].size(); i++)
00686 avPVS[l][i]->ProjectAndDerivs(mse3CamFromWorld, mCamera);
00687 SearchForPoints(avPVS[l], nFineRange, 8);
00688 for(unsigned int i=0; i<avPVS[l].size(); i++)
00689 vIterationSet.push_back(avPVS[l][i]);
00690 };
00691
00692
00693 vNextToSearch.clear();
00694 for(int l=LEVELS - 2; l>=0; l--)
00695 for(unsigned int i=0; i<avPVS[l].size(); i++)
00696 vNextToSearch.push_back(avPVS[l][i]);
00697
00698
00699
00700 static gvar3<int> gvnMaxPatchesPerFrame("Tracker.MaxPatchesPerFrame", TRACKER_MAX_PATCHES_PER_FRAME_DEFAULT, SILENT);
00701 int nFinePatchesToUse = *gvnMaxPatchesPerFrame - vIterationSet.size();
00702 if(nFinePatchesToUse < 0)
00703 nFinePatchesToUse = 0;
00704 if((int) vNextToSearch.size() > nFinePatchesToUse)
00705 {
00706 random_shuffle(vNextToSearch.begin(), vNextToSearch.end());
00707 vNextToSearch.resize(nFinePatchesToUse);
00708 };
00709
00710
00711 if(mbDidCoarse)
00712 for(unsigned int i=0; i<vNextToSearch.size(); i++)
00713 vNextToSearch[i]->ProjectAndDerivs(mse3CamFromWorld, mCamera);
00714
00715
00716 SearchForPoints(vNextToSearch, nFineRange, 0);
00717
00718 for(unsigned int i=0; i<vNextToSearch.size(); i++)
00719 vIterationSet.push_back(vNextToSearch[i]);
00720
00721
00722 Vector<6> v6LastUpdate;
00723 v6LastUpdate = Zeros;
00724 for(int iter = 0; iter<10; iter++)
00725 {
00726 bool bNonLinearIteration;
00727
00728 if(iter == 0 || iter == 4 || iter == 9)
00729 bNonLinearIteration = true;
00730 else
00731 bNonLinearIteration = false;
00732
00733 if(iter != 0)
00734 {
00735 if(bNonLinearIteration)
00736 {
00737 for(unsigned int i=0; i<vIterationSet.size(); i++)
00738 if(vIterationSet[i]->bFound)
00739 vIterationSet[i]->ProjectAndDerivs(mse3CamFromWorld, mCamera);
00740 }
00741 else
00742 {
00743 for(unsigned int i=0; i<vIterationSet.size(); i++)
00744 if(vIterationSet[i]->bFound)
00745 vIterationSet[i]->LinearUpdate(v6LastUpdate);
00746 };
00747 }
00748
00749 if(bNonLinearIteration)
00750 for(unsigned int i=0; i<vIterationSet.size(); i++)
00751 if(vIterationSet[i]->bFound)
00752 vIterationSet[i]->CalcJacobian();
00753
00754
00755 double dOverrideSigma = 0.0;
00756 if(iter > 5)
00757 dOverrideSigma = 16.0;
00758
00759
00760 Vector<6> v6Update =
00761 CalcPoseUpdate(vIterationSet, dOverrideSigma, iter==9);
00762 mse3CamFromWorld = SE3<>::exp(v6Update) * mse3CamFromWorld;
00763 v6LastUpdate = v6Update;
00764 };
00765
00766
00767 if(mbDraw)
00768 {
00769 glPointSize(6);
00770 glEnable(GL_BLEND);
00771 glEnable(GL_POINT_SMOOTH);
00772 glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
00773 glBegin(GL_POINTS);
00774 for(vector<TrackerData*>::reverse_iterator it = vIterationSet.rbegin();
00775 it!= vIterationSet.rend();
00776 it++)
00777 {
00778 if(! (*it)->bFound)
00779 continue;
00780 glColor(gavLevelColors[(*it)->nSearchLevel]);
00781 glVertex((*it)->v2Image);
00782 }
00783 glEnd();
00784 glDisable(GL_BLEND);
00785 }
00786
00787
00788
00789
00790
00791
00792
00793
00794
00795
00796
00797
00798
00799
00800
00801
00802
00803
00804
00805
00806
00807
00808
00809
00810
00811
00812
00813
00814
00815
00816
00817
00818
00819
00820
00821
00822
00823
00824
00825
00826
00827
00828
00829
00830
00831
00832 mCurrentKF.se3CfromW = mse3CamFromWorld;
00833
00834
00835 mCurrentKF.mMeasurements.clear();
00836 for(vector<TrackerData*>::iterator it = vIterationSet.begin();
00837 it!= vIterationSet.end();
00838 it++)
00839 {
00840 if(! (*it)->bFound)
00841 continue;
00842 Measurement m;
00843 m.v2RootPos = (*it)->v2Found;
00844 m.nLevel = (*it)->nSearchLevel;
00845 m.bSubPix = (*it)->bDidSubPix;
00846 mCurrentKF.mMeasurements[& ((*it)->Point)] = m;
00847 }
00848
00849
00850 {
00851 double dSum = 0;
00852 double dSumSq = 0;
00853 int nNum = 0;
00854 for(vector<TrackerData*>::iterator it = vIterationSet.begin();
00855 it!= vIterationSet.end();
00856 it++)
00857 if((*it)->bFound)
00858 {
00859 double z = (*it)->v3Cam[2];
00860 dSum+= z;
00861 dSumSq+= z*z;
00862 nNum++;
00863 };
00864 if(nNum > 20)
00865 {
00866 mCurrentKF.dSceneDepthMean = dSum/nNum;
00867 mCurrentKF.dSceneDepthSigma = sqrt((dSumSq / nNum) - (mCurrentKF.dSceneDepthMean) * (mCurrentKF.dSceneDepthMean));
00868 }
00869 }
00870 }
00871
00872
00873 int Tracker::SearchForPoints(vector<TrackerData*> &vTD, int nRange, int nSubPixIts)
00874 {
00875 int nFound = 0;
00876 for(unsigned int i=0; i<vTD.size(); i++)
00877 {
00878
00879
00880 TrackerData &TD = *vTD[i];
00881 PatchFinder &Finder = TD.Finder;
00882 Finder.MakeTemplateCoarseCont(TD.Point);
00883 if(Finder.TemplateBad())
00884 {
00885 TD.bInImage = TD.bPotentiallyVisible = TD.bFound = false;
00886 continue;
00887 }
00888 manMeasAttempted[Finder.GetLevel()]++;
00889
00890 bool bFound =
00891 Finder.FindPatchCoarse(ir(TD.v2Image), mCurrentKF, nRange);
00892 TD.bSearched = true;
00893 if(!bFound)
00894 {
00895 TD.bFound = false;
00896 continue;
00897 }
00898
00899 TD.bFound = true;
00900 TD.dSqrtInvNoise = (1.0 / Finder.GetLevelScale());
00901
00902 nFound++;
00903 manMeasFound[Finder.GetLevel()]++;
00904
00905
00906 if(nSubPixIts > 0)
00907 {
00908 TD.bDidSubPix = true;
00909 Finder.MakeSubPixTemplate();
00910 bool bSubPixConverges=Finder.IterateSubPixToConvergence(mCurrentKF, nSubPixIts);
00911 if(!bSubPixConverges)
00912 {
00913 TD.bFound = false;
00914 nFound--;
00915 manMeasFound[Finder.GetLevel()]--;
00916 continue;
00917 }
00918 TD.v2Found = Finder.GetSubPixPos();
00919 }
00920 else
00921 {
00922 TD.v2Found = Finder.GetCoarsePosAsVector();
00923 TD.bDidSubPix = false;
00924 }
00925 }
00926 return nFound;
00927 };
00928
00929
00930
00931
00932
00933
00934
00935
00936 Vector<6> Tracker::CalcPoseUpdate(vector<TrackerData*> vTD, double dOverrideSigma, bool bMarkOutliers)
00937 {
00938
00939 int nEstimator = 0;
00940 static gvar3<string> gvsEstimator("TrackerMEstimator", TRACKER_M_ESTIMATOR_DEFAULT, SILENT);
00941 if(*gvsEstimator == "Tukey")
00942 nEstimator = 0;
00943 else if(*gvsEstimator == "Cauchy")
00944 nEstimator = 1;
00945 else if(*gvsEstimator == "Huber")
00946 nEstimator = 2;
00947 else
00948 {
00949 cout << "Invalid TrackerMEstimator, choices are Tukey, Cauchy, Huber" << endl;
00950 nEstimator = 0;
00951 *gvsEstimator = "Tukey";
00952 };
00953
00954
00955
00956 vector<double> vdErrorSquared;
00957 for(unsigned int f=0; f<vTD.size(); f++)
00958 {
00959 TrackerData &TD = *vTD[f];
00960 if(!TD.bFound)
00961 continue;
00962 TD.v2Error_CovScaled = TD.dSqrtInvNoise* (TD.v2Found - TD.v2Image);
00963 vdErrorSquared.push_back((double)(TD.v2Error_CovScaled * TD.v2Error_CovScaled));
00964 };
00965
00966
00967 if(vdErrorSquared.size() == 0)
00968 return makeVector( 0,0,0,0,0,0);
00969
00970
00971 double dSigmaSquared;
00972 if(dOverrideSigma > 0)
00973 dSigmaSquared = dOverrideSigma;
00974 else
00975 {
00976 if (nEstimator == 0)
00977 dSigmaSquared = Tukey::FindSigmaSquared(vdErrorSquared);
00978 else if(nEstimator == 1)
00979 dSigmaSquared = Cauchy::FindSigmaSquared(vdErrorSquared);
00980 else
00981 dSigmaSquared = Huber::FindSigmaSquared(vdErrorSquared);
00982 }
00983
00984
00985
00986 WLS<6> wls;
00987 wls.add_prior(100.0);
00988 for(unsigned int f=0; f<vTD.size(); f++)
00989 {
00990 TrackerData &TD = *vTD[f];
00991 if(!TD.bFound)
00992 continue;
00993 Vector<2> &v2 = TD.v2Error_CovScaled;
00994 double dErrorSq = v2 * v2;
00995 double dWeight;
00996
00997 if(nEstimator == 0)
00998 dWeight= Tukey::Weight(dErrorSq, dSigmaSquared);
00999 else if(nEstimator == 1)
01000 dWeight= Cauchy::Weight(dErrorSq, dSigmaSquared);
01001 else
01002 dWeight= Huber::Weight(dErrorSq, dSigmaSquared);
01003
01004
01005 if(dWeight == 0.0)
01006 {
01007 if(bMarkOutliers)
01008 TD.Point.nMEstimatorOutlierCount++;
01009 continue;
01010 }
01011 else
01012 if(bMarkOutliers)
01013 TD.Point.nMEstimatorInlierCount++;
01014
01015 Matrix<2,6> &m26Jac = TD.m26Jacobian;
01016 wls.add_mJ(v2[0], (Vector<6>)(TD.dSqrtInvNoise * m26Jac[0]), dWeight);
01017 wls.add_mJ(v2[1], (Vector<6>)(TD.dSqrtInvNoise * m26Jac[1]), dWeight);
01018 }
01019
01020 wls.compute();
01021 return wls.get_mu();
01022 }
01023
01024
01025
01026
01027
01028
01029 void Tracker::ApplyMotionModel()
01030 {
01031
01032 mse3StartPos = mse3CamFromWorld;
01033
01034
01035 Vector<6> v6Velocity = mv6CameraVelocity;
01036 if(mbUseSBIInit)
01037 {
01038 v6Velocity.slice<3,3>() = mv6SBIRot.slice<3,3>();
01039 v6Velocity[0] = 0.0;
01040 v6Velocity[1] = 0.0;
01041 }
01042 mse3CamFromWorld = SE3<>::exp(v6Velocity) * mse3StartPos;
01043
01044
01045
01046 };
01047
01048
01049
01050
01051 void Tracker::UpdateMotionModel()
01052 {
01053
01054 SE3<> se3NewFromOld = mse3CamFromWorld * mse3StartPos.inverse();
01055 Vector<6> v6Motion = SE3<>::ln(se3NewFromOld);
01056 Vector<6> v6OldVel = mv6CameraVelocity;
01057
01058 mv6CameraVelocity = 0.9 * (0.5 * v6Motion + 0.5 * v6OldVel);
01059 mdVelocityMagnitude = sqrt((double)(mv6CameraVelocity * mv6CameraVelocity));
01060
01061
01062
01063
01064 Vector<6> v6 = mv6CameraVelocity;
01065 v6.slice<0,3>() *= 1.0 / mCurrentKF.dSceneDepthMean;
01066 mdMSDScaledVelocityMagnitude = sqrt((double)(v6*v6));
01067 }
01068
01069
01070 void Tracker::AddNewKeyFrame()
01071 {
01072 mMapMaker.AddKeyFrame(mCurrentKF);
01073 mnLastKeyFrameDropped = mnFrame;
01074 mnLastKeyFrameDroppedClock = clock();
01075 }
01076
01077
01078
01079
01080 void Tracker::AssessTrackingQuality()
01081 {
01082 int nTotalAttempted = 0;
01083 int nTotalFound = 0;
01084 int nLargeAttempted = 0;
01085 int nLargeFound = 0;
01086
01087 for(int i=0; i<LEVELS; i++)
01088 {
01089 nTotalAttempted += manMeasAttempted[i];
01090 nTotalFound += manMeasFound[i];
01091 if(i>=2) nLargeAttempted += manMeasAttempted[i];
01092 if(i>=2) nLargeFound += manMeasFound[i];
01093 }
01094
01095 if(nTotalFound == 0 || nTotalAttempted == 0)
01096 mTrackingQuality = BAD;
01097 else
01098 {
01099 double dTotalFracFound = (double) nTotalFound / nTotalAttempted;
01100 double dLargeFracFound;
01101 if(nLargeAttempted > 10)
01102 dLargeFracFound = (double) nLargeFound / nLargeAttempted;
01103 else
01104 dLargeFracFound = dTotalFracFound;
01105
01106 static gvar3<double> gvdQualityGood("Tracker.TrackingQualityGood", TRACKER_QUALITY_GOOD_DEFAULT, SILENT);
01107 static gvar3<double> gvdQualityLost("Tracker.TrackingQualityLost", TRACKER_QUALITY_LOST_DEFAULT, SILENT);
01108
01109
01110 if(dTotalFracFound > *gvdQualityGood)
01111 mTrackingQuality = GOOD;
01112 else if(dLargeFracFound < *gvdQualityLost)
01113 mTrackingQuality = BAD;
01114 else
01115 mTrackingQuality = DODGY;
01116 }
01117
01118 if(mTrackingQuality == DODGY)
01119 {
01120
01121
01122 if(mMapMaker.IsDistanceToNearestKeyFrameExcessive(mCurrentKF))
01123 mTrackingQuality = BAD;
01124 }
01125
01126 if(mTrackingQuality==BAD)
01127 mnLostFrames++;
01128 else
01129 mnLostFrames = 0;
01130
01131 numPointsFound = nTotalFound;
01132 numPointsAttempted = nTotalAttempted;
01133 }
01134
01135 string Tracker::GetMessageForUser()
01136 {
01137 return mMessageForUser.str();
01138 }
01139
01140 void Tracker::CalcSBIRotation()
01141 {
01142 mpSBILastFrame->MakeJacs();
01143 pair<SE2<>, double> result_pair;
01144 result_pair = mpSBIThisFrame->IteratePosRelToTarget(*mpSBILastFrame, 6);
01145 SE3<> se3Adjust = SmallBlurryImage::SE3fromSE2(result_pair.first, mCamera);
01146 mv6SBIRot = se3Adjust.ln();
01147 }
01148
01149 ImageRef TrackerData::irImageSize;
01150
01151
01152
01153
01154
01155
01156
01157