00001
00002 #include "MapMaker.h"
00003 #include "MapPoint.h"
00004 #include "Bundle.h"
00005 #include "PatchFinder.h"
00006 #include "SmallMatrixOpts.h"
00007 #include "HomographyInit.h"
00008
00009 #include <cvd/vector_image_ref.h>
00010 #include <cvd/vision.h>
00011 #include <cvd/image_interpolate.h>
00012
00013 #include <TooN/SVD.h>
00014 #include <TooN/SymEigen.h>
00015
00016 #include <gvars3/instances.h>
00017 #include <fstream>
00018 #include <algorithm>
00019
00020 #ifdef WIN32
00021 #define WIN32_LEAN_AND_MEAN
00022 #include <windows.h>
00023 #endif
00024
00025 #include "settingsCustom.h"
00026
00027 using namespace CVD;
00028 using namespace std;
00029 using namespace GVars3;
00030
00031
00032
00033 MapMaker::MapMaker(Map& m, const ATANCamera &cam)
00034 : mMap(m), mCamera(cam)
00035 {
00036 mbResetRequested = false;
00037 Reset();
00038 start();
00039 GUI.RegisterCommand("SaveMap", GUICommandCallBack, this);
00040 GV3::Register(mgvdWiggleScale, "MapMaker.WiggleScale", 0.1, SILENT);
00041 };
00042
00043 void MapMaker::Reset()
00044 {
00045
00046 mMap.Reset();
00047 mvFailureQueue.clear();
00048 while(!mqNewQueue.empty()) mqNewQueue.pop();
00049 mMap.vpKeyFrames.clear();
00050 mvpKeyFrameQueue.clear();
00051 mbBundleRunning = false;
00052 mbBundleConverged_Full = true;
00053 mbBundleConverged_Recent = true;
00054 mbResetDone = true;
00055 mbResetRequested = false;
00056 mbBundleAbortRequested = false;
00057 }
00058
00059
00060
00061 #define CHECK_RESET if(mbResetRequested) {Reset(); continue;};
00062
00063 void MapMaker::run()
00064 {
00065
00066 #ifdef WIN32
00067
00068
00069 SetThreadPriority(GetCurrentThread(), THREAD_PRIORITY_LOWEST);
00070 #endif
00071
00072 while(!shouldStop())
00073 {
00074 CHECK_RESET;
00075 sleep(5);
00076 CHECK_RESET;
00077
00078
00079 while(!mvQueuedCommands.empty())
00080 {
00081 GUICommandHandler(mvQueuedCommands.begin()->sCommand, mvQueuedCommands.begin()->sParams);
00082 mvQueuedCommands.erase(mvQueuedCommands.begin());
00083 }
00084
00085 if(!mMap.IsGood())
00086 continue;
00087
00088
00089
00090
00091
00092 CHECK_RESET;
00093
00094 if(!mbBundleConverged_Recent && QueueSize() == 0)
00095 BundleAdjustRecent();
00096
00097 CHECK_RESET;
00098
00099 if(mbBundleConverged_Recent && QueueSize() == 0)
00100 ReFindNewlyMade();
00101
00102 CHECK_RESET;
00103
00104 if(mbBundleConverged_Recent && !mbBundleConverged_Full && QueueSize() == 0)
00105 BundleAdjustAll();
00106
00107 CHECK_RESET;
00108
00109 if(mbBundleConverged_Recent && mbBundleConverged_Full && rand()%20 == 0 && QueueSize() == 0)
00110 ReFindFromFailureQueue();
00111
00112 CHECK_RESET;
00113 HandleBadPoints();
00114
00115 CHECK_RESET;
00116
00117 if(QueueSize() > 0)
00118 AddKeyFrameFromTopOfQueue();
00119 }
00120 }
00121
00122
00123
00124 void MapMaker::RequestReset()
00125 {
00126 mbResetDone = false;
00127 mbResetRequested = true;
00128 }
00129
00130 bool MapMaker::ResetDone()
00131 {
00132 return mbResetDone;
00133 }
00134
00135
00136
00137 void MapMaker::HandleBadPoints()
00138 {
00139
00140 for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
00141 {
00142 MapPoint &p = *mMap.vpPoints[i];
00143 if(p.nMEstimatorOutlierCount > 20 && p.nMEstimatorOutlierCount > p.nMEstimatorInlierCount)
00144 p.bBad = true;
00145 }
00146
00147
00148
00149 for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
00150 if(mMap.vpPoints[i]->bBad)
00151 {
00152 MapPoint *p = mMap.vpPoints[i];
00153 for(unsigned int j=0; j<mMap.vpKeyFrames.size(); j++)
00154 {
00155 KeyFrame &k = *mMap.vpKeyFrames[j];
00156 if(k.mMeasurements.count(p))
00157 k.mMeasurements.erase(p);
00158 }
00159 }
00160
00161 mMap.MoveBadPointsToTrash();
00162 }
00163
00164 MapMaker::~MapMaker()
00165 {
00166 mbBundleAbortRequested = true;
00167 stop();
00168 cout << "Waiting for mapmaker to die.." << endl;
00169 join();
00170 cout << " .. mapmaker has died." << endl;
00171 }
00172
00173
00174
00175 Vector<3> MapMaker::ReprojectPoint(SE3<> se3AfromB, const Vector<2> &v2A, const Vector<2> &v2B)
00176 {
00177 Matrix<3,4> PDash;
00178 PDash.slice<0,0,3,3>() = se3AfromB.get_rotation().get_matrix();
00179 PDash.slice<0,3,3,1>() = se3AfromB.get_translation().as_col();
00180
00181 Matrix<4> A;
00182 A[0][0] = -1.0; A[0][1] = 0.0; A[0][2] = v2B[0]; A[0][3] = 0.0;
00183 A[1][0] = 0.0; A[1][1] = -1.0; A[1][2] = v2B[1]; A[1][3] = 0.0;
00184 A[2] = v2A[0] * PDash[2] - PDash[0];
00185 A[3] = v2A[1] * PDash[2] - PDash[1];
00186
00187 SVD<4,4> svd(A);
00188 Vector<4> v4Smallest = svd.get_VT()[3];
00189 if(v4Smallest[3] == 0.0)
00190 v4Smallest[3] = 0.00001;
00191 return project(v4Smallest);
00192 }
00193
00194
00195
00196
00197
00198 bool MapMaker::InitFromStereo(KeyFrame &kF,
00199 KeyFrame &kS,
00200 vector<pair<ImageRef, ImageRef> > &vTrailMatches,
00201 SE3<> &se3TrackerPose,
00202 SE3<> KFZeroDesiredCamFromWorld,
00203 SE3<> KFOneDesiredCamFromWorld)
00204 {
00205 mdWiggleScale = *mgvdWiggleScale;
00206
00207 mCamera.SetImageSize(kF.aLevels[0].im.size());
00208
00209
00210 vector<HomographyMatch> vMatches;
00211 for(unsigned int i=0; i<vTrailMatches.size(); i++)
00212 {
00213 HomographyMatch m;
00214 m.v2CamPlaneFirst = mCamera.UnProject(vTrailMatches[i].first);
00215 m.v2CamPlaneSecond = mCamera.UnProject(vTrailMatches[i].second);
00216 m.m2PixelProjectionJac = mCamera.GetProjectionDerivs();
00217 vMatches.push_back(m);
00218 }
00219
00220 SE3<> se3;
00221 bool bGood;
00222 HomographyInit HomographyInit;
00223 bGood = HomographyInit.Compute(vMatches, 5.0, se3);
00224 if(!bGood)
00225 {
00226 cout << " Could not init from stereo pair, try again." << endl;
00227 return false;
00228 }
00229
00230
00231 double dTransMagn = sqrt((double)(se3.get_translation() * se3.get_translation()));
00232 double dTransIMUMagn = sqrt((double)((KFZeroDesiredCamFromWorld.get_translation() - KFOneDesiredCamFromWorld.get_translation())*
00233 (KFZeroDesiredCamFromWorld.get_translation() - KFOneDesiredCamFromWorld.get_translation())));
00234
00235 if(dTransMagn == 0)
00236 {
00237 cout << " Estimated zero baseline from stereo pair, try again." << endl;
00238 return false;
00239 }
00240
00241 if(dTransIMUMagn < 0.05)
00242 {
00243 cout << " IMU Baseline smaller than 5cm, try again: " << dTransIMUMagn << endl;
00244
00245 dTransIMUMagn = 0.1;
00246 }
00247
00248
00249
00250
00251
00252 se3.get_translation() *= mdWiggleScale/dTransMagn;
00253 initialScaleFactor = dTransIMUMagn / mdWiggleScale;
00254
00255 KeyFrame *pkFirst = new KeyFrame();
00256 KeyFrame *pkSecond = new KeyFrame();
00257 *pkFirst = kF;
00258 *pkSecond = kS;
00259
00260 pkFirst->bFixed = true;
00261 pkFirst->se3CfromW = SE3<>();
00262
00263 pkSecond->bFixed = false;
00264 pkSecond->se3CfromW = se3;
00265
00266
00267 PatchFinder finder;
00268
00269 for(unsigned int i=0; i<vMatches.size(); i++)
00270 {
00271 MapPoint *p = new MapPoint();
00272
00273
00274 p->pPatchSourceKF = pkFirst;
00275 p->nSourceLevel = 0;
00276 p->v3Normal_NC = makeVector( 0,0,-1);
00277 p->irCenter = vTrailMatches[i].first;
00278 p->v3Center_NC = unproject(mCamera.UnProject(p->irCenter));
00279 p->v3OneDownFromCenter_NC = unproject(mCamera.UnProject(p->irCenter + ImageRef(0,1)));
00280 p->v3OneRightFromCenter_NC = unproject(mCamera.UnProject(p->irCenter + ImageRef(1,0)));
00281 normalize(p->v3Center_NC);
00282 normalize(p->v3OneDownFromCenter_NC);
00283 normalize(p->v3OneRightFromCenter_NC);
00284 p->RefreshPixelVectors();
00285
00286
00287 finder.MakeTemplateCoarseNoWarp(*p);
00288 finder.MakeSubPixTemplate();
00289 finder.SetSubPixPos(vec(vTrailMatches[i].second));
00290 bool bGood = finder.IterateSubPixToConvergence(*pkSecond,10);
00291 if(!bGood)
00292 {
00293 delete p; continue;
00294 }
00295
00296
00297 Vector<2> v2SecondPos = finder.GetSubPixPos();
00298 p->v3WorldPos = ReprojectPoint(se3, mCamera.UnProject(v2SecondPos), vMatches[i].v2CamPlaneFirst);
00299 if(p->v3WorldPos[2] < 0.0)
00300 {
00301 delete p; continue;
00302 }
00303
00304
00305 p->pMMData = new MapMakerData();
00306 mMap.vpPoints.push_back(p);
00307
00308
00309 Measurement mFirst;
00310 mFirst.nLevel = 0;
00311 mFirst.Source = Measurement::SRC_ROOT;
00312 mFirst.v2RootPos = vec(vTrailMatches[i].first);
00313 mFirst.bSubPix = true;
00314 pkFirst->mMeasurements[p] = mFirst;
00315 p->pMMData->sMeasurementKFs.insert(pkFirst);
00316
00317 Measurement mSecond;
00318 mSecond.nLevel = 0;
00319 mSecond.Source = Measurement::SRC_TRAIL;
00320 mSecond.v2RootPos = finder.GetSubPixPos();
00321 mSecond.bSubPix = true;
00322 pkSecond->mMeasurements[p] = mSecond;
00323 p->pMMData->sMeasurementKFs.insert(pkSecond);
00324 }
00325
00326 mMap.vpKeyFrames.push_back(pkFirst);
00327 mMap.vpKeyFrames.push_back(pkSecond);
00328 pkFirst->MakeKeyFrame_Rest();
00329 pkSecond->MakeKeyFrame_Rest();
00330
00331 for(int i=0; i<5; i++)
00332 BundleAdjustAll();
00333
00334
00335
00336 RefreshSceneDepth(pkFirst);
00337 RefreshSceneDepth(pkSecond);
00338 mdWiggleScaleDepthNormalized = mdWiggleScale / pkFirst->dSceneDepthMean;
00339
00340
00341 AddSomeMapPoints(0);
00342 AddSomeMapPoints(3);
00343 AddSomeMapPoints(1);
00344 AddSomeMapPoints(2);
00345
00346 mbBundleConverged_Full = false;
00347 mbBundleConverged_Recent = false;
00348
00349 time_t started = clock();
00350 while(!mbBundleConverged_Full)
00351 {
00352 BundleAdjustAll();
00353 if(mbResetRequested || ((double)(clock() - started))/(double)CLOCKS_PER_SEC > 1.500)
00354 {
00355 printf("ABORT mapmaking, took more than 1.5s (deadlock?)\n");
00356 return false;
00357 }
00358 }
00359
00360
00361
00362 printf("PTAM Init: re-scaleing map with %f\n",0.1/pkFirst->dSceneDepthMean);
00363 ApplyGlobalScaleToMap(1/pkFirst->dSceneDepthMean);
00364 initialScaleFactor *= pkFirst->dSceneDepthMean;
00365 ApplyGlobalTransformationToMap(KFZeroDesiredCamFromWorld.inverse());
00366
00367 mMap.bGood = true;
00368 se3TrackerPose = pkSecond->se3CfromW;
00369
00370
00371 cout << " MapMaker: made initial map with " << mMap.vpPoints.size() << " points." << endl;
00372
00373 TooN::Vector<3> ptamTrans = mMap.vpKeyFrames[1]->se3CfromW.get_translation() - mMap.vpKeyFrames[0]->se3CfromW.get_translation();
00374 TooN::Vector<3> imuTrans = KFOneDesiredCamFromWorld.get_translation() - KFZeroDesiredCamFromWorld.get_translation();
00375
00376
00377 printf("resulting PTAM Translation: (%.4f, %.4f, %.4f), IMU translation: (%.4f, %.4f, %.4f)",
00378 ptamTrans[0],
00379 ptamTrans[1],
00380 ptamTrans[2],
00381 imuTrans[0],
00382 imuTrans[1],
00383 imuTrans[2]);
00384
00385 ptamTrans = ptamTrans / sqrt((double)(ptamTrans*ptamTrans));
00386 imuTrans = imuTrans / sqrt((double)(imuTrans*imuTrans));
00387 double angle = 180*acos((double)(ptamTrans * imuTrans))/3.1415;
00388
00389
00390 if(angle > 6000)
00391 {
00392 printf("\nAngle between estimated Translation is too large (%.1f): try again!\n",angle);
00393 return false;
00394 }
00395 else
00396 printf(", angle: %.1f\n",angle);
00397
00398 return true;
00399 }
00400
00401
00402
00403
00404
00405
00406 void MapMaker::ThinCandidates(KeyFrame &k, int nLevel)
00407 {
00408 vector<Candidate> &vCSrc = k.aLevels[nLevel].vCandidates;
00409 vector<Candidate> vCGood;
00410 vector<ImageRef> irBusyLevelPos;
00411
00412
00413 for(meas_it it = k.mMeasurements.begin(); it!=k.mMeasurements.end(); it++)
00414 {
00415 if(!(it->second.nLevel == nLevel || it->second.nLevel == nLevel + 1))
00416 continue;
00417 irBusyLevelPos.push_back(ir_rounded(it->second.v2RootPos / LevelScale(nLevel)));
00418 }
00419
00420
00421 unsigned int nMinMagSquared = 5*5;
00422 for(unsigned int i=0; i<vCSrc.size(); i++)
00423 {
00424 ImageRef irC = vCSrc[i].irLevelPos;
00425 bool bGood = true;
00426 for(unsigned int j=0; j<irBusyLevelPos.size(); j++)
00427 {
00428 ImageRef irB = irBusyLevelPos[j];
00429 if((irB - irC).mag_squared() < nMinMagSquared)
00430 {
00431 bGood = false;
00432 break;
00433 }
00434 }
00435 if(bGood)
00436 vCGood.push_back(vCSrc[i]);
00437 }
00438 vCSrc = vCGood;
00439 }
00440
00441
00442
00443
00444 void MapMaker::AddSomeMapPoints(int nLevel)
00445 {
00446 KeyFrame &kSrc = *(mMap.vpKeyFrames[mMap.vpKeyFrames.size() - 1]);
00447 KeyFrame &kTarget = *(ClosestKeyFrame(kSrc));
00448 Level &l = kSrc.aLevels[nLevel];
00449
00450 ThinCandidates(kSrc, nLevel);
00451
00452 for(unsigned int i = 0; i<l.vCandidates.size(); i++)
00453 AddPointEpipolar(kSrc, kTarget, nLevel, i);
00454 };
00455
00456
00457 void MapMaker::ApplyGlobalTransformationToMap(SE3<> se3NewFromOld)
00458 {
00459 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
00460 mMap.vpKeyFrames[i]->se3CfromW = mMap.vpKeyFrames[i]->se3CfromW * se3NewFromOld.inverse();
00461
00462
00463 for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
00464 {
00465 mMap.vpPoints[i]->v3WorldPos =
00466 se3NewFromOld * mMap.vpPoints[i]->v3WorldPos;
00467 mMap.vpPoints[i]->RefreshPixelVectors();
00468 }
00469 }
00470
00471
00472 void MapMaker::ApplyGlobalScaleToMap(double dScale)
00473 {
00474 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
00475 {
00476 mMap.vpKeyFrames[i]->se3CfromW.get_translation() *= dScale;
00477 }
00478
00479 for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
00480 {
00481 (*mMap.vpPoints[i]).v3WorldPos *= dScale;
00482 (*mMap.vpPoints[i]).v3PixelRight_W *= dScale;
00483 (*mMap.vpPoints[i]).v3PixelDown_W *= dScale;
00484 (*mMap.vpPoints[i]).RefreshPixelVectors();
00485 }
00486
00487 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
00488 {
00489 RefreshSceneDepth(mMap.vpKeyFrames[i]);
00490 }
00491 }
00492
00493
00494
00495
00496
00497 void MapMaker::AddKeyFrame(KeyFrame &k)
00498 {
00499 KeyFrame *pK = new KeyFrame;
00500 *pK = k;
00501 pK->pSBI = NULL;
00502 mvpKeyFrameQueue.push_back(pK);
00503 if(mbBundleRunning)
00504 mbBundleAbortRequested = true;
00505 }
00506
00507
00508 void MapMaker::AddKeyFrameFromTopOfQueue()
00509 {
00510 if(mvpKeyFrameQueue.size() == 0)
00511 return;
00512
00513 KeyFrame *pK = mvpKeyFrameQueue[0];
00514 mvpKeyFrameQueue.erase(mvpKeyFrameQueue.begin());
00515 pK->MakeKeyFrame_Rest();
00516 mMap.vpKeyFrames.push_back(pK);
00517
00518 for(meas_it it = pK->mMeasurements.begin();
00519 it!=pK->mMeasurements.end();
00520 it++)
00521 {
00522 it->first->pMMData->sMeasurementKFs.insert(pK);
00523 it->second.Source = Measurement::SRC_TRACKER;
00524 }
00525
00526
00527 ReFindInSingleKeyFrame(*pK);
00528
00529 AddSomeMapPoints(3);
00530 AddSomeMapPoints(0);
00531 AddSomeMapPoints(1);
00532 AddSomeMapPoints(2);
00533
00534 mbBundleConverged_Full = false;
00535 mbBundleConverged_Recent = false;
00536 }
00537
00538
00539
00540
00541 bool MapMaker::AddPointEpipolar(KeyFrame &kSrc,
00542 KeyFrame &kTarget,
00543 int nLevel,
00544 int nCandidate)
00545 {
00546 static Image<Vector<2> > imUnProj;
00547 static bool bMadeCache = false;
00548 if(!bMadeCache)
00549 {
00550 imUnProj.resize(kSrc.aLevels[0].im.size());
00551 ImageRef ir;
00552 do imUnProj[ir] = mCamera.UnProject(ir);
00553 while(ir.next(imUnProj.size()));
00554 bMadeCache = true;
00555 }
00556
00557 int nLevelScale = LevelScale(nLevel);
00558 Candidate &candidate = kSrc.aLevels[nLevel].vCandidates[nCandidate];
00559 ImageRef irLevelPos = candidate.irLevelPos;
00560 Vector<2> v2RootPos = LevelZeroPos(irLevelPos, nLevel);
00561
00562 Vector<3> v3Ray_SC = unproject(mCamera.UnProject(v2RootPos));
00563 normalize(v3Ray_SC);
00564 Vector<3> v3LineDirn_TC = kTarget.se3CfromW.get_rotation() * (kSrc.se3CfromW.get_rotation().inverse() * v3Ray_SC);
00565
00566
00567
00568 double dMean = kSrc.dSceneDepthMean;
00569 double dSigma = kSrc.dSceneDepthSigma;
00570 double dStartDepth = max(mdWiggleScale*0.75, dMean - dSigma * 1.5);
00571 double dEndDepth = min(40 * mdWiggleScale * 1.5, dMean + dSigma * 1.5);
00572
00573 Vector<3> v3CamCenter_TC = kTarget.se3CfromW * kSrc.se3CfromW.inverse().get_translation();
00574 Vector<3> v3RayStart_TC = v3CamCenter_TC + dStartDepth * v3LineDirn_TC;
00575 Vector<3> v3RayEnd_TC = v3CamCenter_TC + dEndDepth * v3LineDirn_TC;
00576
00577
00578 if(v3RayEnd_TC[2] <= v3RayStart_TC[2])
00579 return false;
00580 if(v3RayEnd_TC[2] <= 0.0 ) return false;
00581 if(v3RayStart_TC[2] <= 0.0)
00582 v3RayStart_TC += v3LineDirn_TC * (0.001 - v3RayStart_TC[2] / v3LineDirn_TC[2]);
00583
00584 Vector<2> v2A = project(v3RayStart_TC);
00585 Vector<2> v2B = project(v3RayEnd_TC);
00586 Vector<2> v2AlongProjectedLine = v2A-v2B;
00587
00588 if(v2AlongProjectedLine * v2AlongProjectedLine < 0.00000001)
00589 {
00590 cout << "v2AlongProjectedLine too small." << endl;
00591 return false;
00592 }
00593 normalize(v2AlongProjectedLine);
00594 Vector<2> v2Normal;
00595 v2Normal[0] = v2AlongProjectedLine[1];
00596 v2Normal[1] = -v2AlongProjectedLine[0];
00597
00598 double dNormDist = v2A * v2Normal;
00599 if(fabs(dNormDist) > mCamera.LargestRadiusInImage() )
00600 return false;
00601
00602 double dMinLen = min(v2AlongProjectedLine * v2A, v2AlongProjectedLine * v2B) - 0.05;
00603 double dMaxLen = max(v2AlongProjectedLine * v2A, v2AlongProjectedLine * v2B) + 0.05;
00604 if(dMinLen < -2.0) dMinLen = -2.0;
00605 if(dMaxLen < -2.0) dMaxLen = -2.0;
00606 if(dMinLen > 2.0) dMinLen = 2.0;
00607 if(dMaxLen > 2.0) dMaxLen = 2.0;
00608
00609
00610 PatchFinder Finder;
00611 Finder.MakeTemplateCoarseNoWarp(kSrc, nLevel, irLevelPos);
00612 if(Finder.TemplateBad()) return false;
00613
00614 vector<Vector<2> > &vv2Corners = kTarget.aLevels[nLevel].vImplaneCorners;
00615 vector<ImageRef> &vIR = kTarget.aLevels[nLevel].vCorners;
00616 if(!kTarget.aLevels[nLevel].bImplaneCornersCached)
00617 {
00618 for(unsigned int i=0; i<vIR.size(); i++)
00619 vv2Corners.push_back(imUnProj[ir(LevelZeroPos(vIR[i], nLevel))]);
00620 kTarget.aLevels[nLevel].bImplaneCornersCached = true;
00621 }
00622
00623 int nBest = -1;
00624 int nBestZMSSD = Finder.mnMaxSSD + 1;
00625 double dMaxDistDiff = mCamera.OnePixelDist() * (4.0 + 1.0 * nLevelScale);
00626 double dMaxDistSq = dMaxDistDiff * dMaxDistDiff;
00627
00628 for(unsigned int i=0; i<vv2Corners.size(); i++)
00629 {
00630 Vector<2> v2Im = vv2Corners[i];
00631 double dDistDiff = dNormDist - v2Im * v2Normal;
00632 if(dDistDiff * dDistDiff > dMaxDistSq) continue;
00633 if(v2Im * v2AlongProjectedLine < dMinLen) continue;
00634 if(v2Im * v2AlongProjectedLine > dMaxLen) continue;
00635 int nZMSSD = Finder.ZMSSDAtPoint(kTarget.aLevels[nLevel].im, vIR[i]);
00636 if(nZMSSD < nBestZMSSD)
00637 {
00638 nBest = i;
00639 nBestZMSSD = nZMSSD;
00640 }
00641 }
00642
00643 if(nBest == -1) return false;
00644
00645
00646 Finder.MakeSubPixTemplate();
00647 Finder.SetSubPixPos(LevelZeroPos(vIR[nBest], nLevel));
00648 bool bSubPixConverges = Finder.IterateSubPixToConvergence(kTarget,10);
00649 if(!bSubPixConverges)
00650 return false;
00651
00652
00653 Vector<3> v3New;
00654 v3New = kTarget.se3CfromW.inverse() *
00655 ReprojectPoint(kSrc.se3CfromW * kTarget.se3CfromW.inverse(),
00656 mCamera.UnProject(v2RootPos),
00657 mCamera.UnProject(Finder.GetSubPixPos()));
00658
00659 MapPoint *pNew = new MapPoint;
00660 pNew->v3WorldPos = v3New;
00661 pNew->pMMData = new MapMakerData();
00662
00663
00664 pNew->pPatchSourceKF = &kSrc;
00665 pNew->nSourceLevel = nLevel;
00666 pNew->v3Normal_NC = makeVector( 0,0,-1);
00667 pNew->irCenter = irLevelPos;
00668 pNew->v3Center_NC = unproject(mCamera.UnProject(v2RootPos));
00669 pNew->v3OneRightFromCenter_NC = unproject(mCamera.UnProject(v2RootPos + vec(ImageRef(nLevelScale,0))));
00670 pNew->v3OneDownFromCenter_NC = unproject(mCamera.UnProject(v2RootPos + vec(ImageRef(0,nLevelScale))));
00671
00672 normalize(pNew->v3Center_NC);
00673 normalize(pNew->v3OneDownFromCenter_NC);
00674 normalize(pNew->v3OneRightFromCenter_NC);
00675
00676 pNew->RefreshPixelVectors();
00677
00678 mMap.vpPoints.push_back(pNew);
00679 mqNewQueue.push(pNew);
00680 Measurement m;
00681 m.Source = Measurement::SRC_ROOT;
00682 m.v2RootPos = v2RootPos;
00683 m.nLevel = nLevel;
00684 m.bSubPix = true;
00685 kSrc.mMeasurements[pNew] = m;
00686
00687 m.Source = Measurement::SRC_EPIPOLAR;
00688 m.v2RootPos = Finder.GetSubPixPos();
00689 kTarget.mMeasurements[pNew] = m;
00690 pNew->pMMData->sMeasurementKFs.insert(&kSrc);
00691 pNew->pMMData->sMeasurementKFs.insert(&kTarget);
00692 return true;
00693 }
00694
00695 double MapMaker::KeyFrameLinearDist(KeyFrame &k1, KeyFrame &k2)
00696 {
00697 Vector<3> v3KF1_CamPos = k1.se3CfromW.inverse().get_translation();
00698 Vector<3> v3KF2_CamPos = k2.se3CfromW.inverse().get_translation();
00699 Vector<3> v3Diff = v3KF2_CamPos - v3KF1_CamPos;
00700 double dDist = sqrt((double)(v3Diff * v3Diff));
00701 return dDist;
00702 }
00703
00704 vector<KeyFrame*> MapMaker::NClosestKeyFrames(KeyFrame &k, unsigned int N)
00705 {
00706 vector<pair<double, KeyFrame* > > vKFandScores;
00707 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
00708 {
00709 if(mMap.vpKeyFrames[i] == &k)
00710 continue;
00711 double dDist = KeyFrameLinearDist(k, *mMap.vpKeyFrames[i]);
00712 vKFandScores.push_back(make_pair(dDist, mMap.vpKeyFrames[i]));
00713 }
00714 if(N > vKFandScores.size())
00715 N = vKFandScores.size();
00716 partial_sort(vKFandScores.begin(), vKFandScores.begin() + N, vKFandScores.end());
00717
00718 vector<KeyFrame*> vResult;
00719 for(unsigned int i=0; i<N; i++)
00720 vResult.push_back(vKFandScores[i].second);
00721 return vResult;
00722 }
00723
00724 KeyFrame* MapMaker::ClosestKeyFrame(KeyFrame &k)
00725 {
00726 double dClosestDist = 9999999999.9;
00727 int nClosest = -1;
00728 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
00729 {
00730 if(mMap.vpKeyFrames[i] == &k)
00731 continue;
00732 double dDist = KeyFrameLinearDist(k, *mMap.vpKeyFrames[i]);
00733 if(dDist < dClosestDist)
00734 {
00735 dClosestDist = dDist;
00736 nClosest = i;
00737 }
00738 }
00739 assert(nClosest != -1);
00740 return mMap.vpKeyFrames[nClosest];
00741 }
00742
00743 double MapMaker::DistToNearestKeyFrame(KeyFrame &kCurrent)
00744 {
00745 KeyFrame *pClosest = ClosestKeyFrame(kCurrent);
00746 double dDist = KeyFrameLinearDist(kCurrent, *pClosest);
00747 return dDist;
00748 }
00749
00750 bool MapMaker::NeedNewKeyFrame(KeyFrame &kCurrent)
00751 {
00752 KeyFrame *pClosest = ClosestKeyFrame(kCurrent);
00753 double dDist = KeyFrameLinearDist(kCurrent, *pClosest);
00754 lastMetricDist = dDist * currentScaleFactor;
00755 lastWiggleDist = dDist / kCurrent.dSceneDepthMean;
00756
00757
00758
00759
00760 if(lastWiggleDist > minKFWiggleDist || lastMetricDist > minKFDist)
00761 return true;
00762 return false;
00763 }
00764
00765
00766 void MapMaker::BundleAdjustAll()
00767 {
00768
00769
00770 set<KeyFrame*> sAdj;
00771 set<KeyFrame*> sFixed;
00772 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
00773 if(mMap.vpKeyFrames[i]->bFixed)
00774 sFixed.insert(mMap.vpKeyFrames[i]);
00775 else
00776 sAdj.insert(mMap.vpKeyFrames[i]);
00777
00778 set<MapPoint*> sMapPoints;
00779 for(unsigned int i=0; i<mMap.vpPoints.size();i++)
00780 sMapPoints.insert(mMap.vpPoints[i]);
00781
00782 BundleAdjust(sAdj, sFixed, sMapPoints, false);
00783 }
00784
00785
00786
00787 void MapMaker::BundleAdjustRecent()
00788 {
00789 if(mMap.vpKeyFrames.size() < 8)
00790 {
00791 mbBundleConverged_Recent = true;
00792 return;
00793 }
00794
00795
00796
00797 set<KeyFrame*> sAdjustSet;
00798 KeyFrame *pkfNewest = mMap.vpKeyFrames.back();
00799 sAdjustSet.insert(pkfNewest);
00800 vector<KeyFrame*> vClosest = NClosestKeyFrames(*pkfNewest, 4);
00801 for(int i=0; i<4; i++)
00802 if(vClosest[i]->bFixed == false)
00803 sAdjustSet.insert(vClosest[i]);
00804
00805
00806 set<MapPoint*> sMapPoints;
00807 for(set<KeyFrame*>::iterator iter = sAdjustSet.begin();
00808 iter!=sAdjustSet.end();
00809 iter++)
00810 {
00811 map<MapPoint*,Measurement> &mKFMeas = (*iter)->mMeasurements;
00812 for(meas_it jiter = mKFMeas.begin(); jiter!= mKFMeas.end(); jiter++)
00813 sMapPoints.insert(jiter->first);
00814 };
00815
00816
00817 set<KeyFrame*> sFixedSet;
00818 for(vector<KeyFrame*>::iterator it = mMap.vpKeyFrames.begin(); it!=mMap.vpKeyFrames.end(); it++)
00819 {
00820 if(sAdjustSet.count(*it))
00821 continue;
00822 bool bInclude = false;
00823 for(meas_it jiter = (*it)->mMeasurements.begin(); jiter!= (*it)->mMeasurements.end(); jiter++)
00824 if(sMapPoints.count(jiter->first))
00825 {
00826 bInclude = true;
00827 break;
00828 }
00829 if(bInclude)
00830 sFixedSet.insert(*it);
00831 }
00832
00833 BundleAdjust(sAdjustSet, sFixedSet, sMapPoints, true);
00834 }
00835
00836
00837 void MapMaker::BundleAdjust(set<KeyFrame*> sAdjustSet, set<KeyFrame*> sFixedSet, set<MapPoint*> sMapPoints, bool bRecent)
00838 {
00839 Bundle b(mCamera);
00840 mbBundleRunning = true;
00841 mbBundleRunningIsRecent = bRecent;
00842
00843
00844
00845 map<MapPoint*, int> mPoint_BundleID;
00846 map<int, MapPoint*> mBundleID_Point;
00847 map<KeyFrame*, int> mView_BundleID;
00848 map<int, KeyFrame*> mBundleID_View;
00849
00850
00851 for(set<KeyFrame*>::iterator it = sAdjustSet.begin(); it!= sAdjustSet.end(); it++)
00852 {
00853 int nBundleID = b.AddCamera((*it)->se3CfromW, (*it)->bFixed);
00854 mView_BundleID[*it] = nBundleID;
00855 mBundleID_View[nBundleID] = *it;
00856 }
00857 for(set<KeyFrame*>::iterator it = sFixedSet.begin(); it!= sFixedSet.end(); it++)
00858 {
00859 int nBundleID = b.AddCamera((*it)->se3CfromW, true);
00860 mView_BundleID[*it] = nBundleID;
00861 mBundleID_View[nBundleID] = *it;
00862 }
00863
00864
00865 for(set<MapPoint*>::iterator it = sMapPoints.begin(); it!=sMapPoints.end(); it++)
00866 {
00867 int nBundleID = b.AddPoint((*it)->v3WorldPos);
00868 mPoint_BundleID[*it] = nBundleID;
00869 mBundleID_Point[nBundleID] = *it;
00870 }
00871
00872
00873 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
00874 {
00875 if(mView_BundleID.count(mMap.vpKeyFrames[i]) == 0)
00876 continue;
00877
00878 int nKF_BundleID = mView_BundleID[mMap.vpKeyFrames[i]];
00879 for(meas_it it= mMap.vpKeyFrames[i]->mMeasurements.begin();
00880 it!= mMap.vpKeyFrames[i]->mMeasurements.end();
00881 it++)
00882 {
00883 if(mPoint_BundleID.count(it->first) == 0)
00884 continue;
00885 int nPoint_BundleID = mPoint_BundleID[it->first];
00886 b.AddMeas(nKF_BundleID, nPoint_BundleID, it->second.v2RootPos, LevelScale(it->second.nLevel) * LevelScale(it->second.nLevel));
00887 }
00888 }
00889
00890
00891 int nAccepted = b.Compute(&mbBundleAbortRequested);
00892
00893 if(nAccepted < 0)
00894 {
00895
00896
00897
00898 cout << "!! MapMaker: Cholesky failure in bundle adjust. " << endl
00899 << " The map is probably corrupt: Ditching the map. " << endl;
00900 mbResetRequested = true;
00901 return;
00902 }
00903
00904
00905 if(nAccepted > 0)
00906 {
00907
00908 for(map<MapPoint*,int>::iterator itr = mPoint_BundleID.begin();
00909 itr!=mPoint_BundleID.end();
00910 itr++)
00911 itr->first->v3WorldPos = b.GetPoint(itr->second);
00912
00913 for(map<KeyFrame*,int>::iterator itr = mView_BundleID.begin();
00914 itr!=mView_BundleID.end();
00915 itr++)
00916 itr->first->se3CfromW = b.GetCamera(itr->second);
00917 if(bRecent)
00918 mbBundleConverged_Recent = false;
00919 mbBundleConverged_Full = false;
00920 };
00921
00922 if(b.Converged())
00923 {
00924 mbBundleConverged_Recent = true;
00925 if(!bRecent)
00926 mbBundleConverged_Full = true;
00927 }
00928
00929 mbBundleRunning = false;
00930 mbBundleAbortRequested = false;
00931
00932
00933 vector<pair<int,int> > vOutliers_PC_pair = b.GetOutlierMeasurements();
00934 for(unsigned int i=0; i<vOutliers_PC_pair.size(); i++)
00935 {
00936 MapPoint *pp = mBundleID_Point[vOutliers_PC_pair[i].first];
00937 KeyFrame *pk = mBundleID_View[vOutliers_PC_pair[i].second];
00938 Measurement &m = pk->mMeasurements[pp];
00939 if(pp->pMMData->GoodMeasCount() <= 2 || m.Source == Measurement::SRC_ROOT)
00940 pp->bBad = true;
00941 else
00942 {
00943
00944 if(m.Source == Measurement::SRC_TRACKER || m.Source == Measurement::SRC_EPIPOLAR)
00945 mvFailureQueue.push_back(pair<KeyFrame*,MapPoint*>(pk,pp));
00946 else
00947 pp->pMMData->sNeverRetryKFs.insert(pk);
00948 pk->mMeasurements.erase(pp);
00949 pp->pMMData->sMeasurementKFs.erase(pk);
00950 }
00951 }
00952 }
00953
00954
00955
00956
00957
00958
00959 bool MapMaker::ReFind_Common(KeyFrame &k, MapPoint &p)
00960 {
00961
00962
00963 if(p.pMMData->sMeasurementKFs.count(&k)
00964 || p.pMMData->sNeverRetryKFs.count(&k))
00965 return false;
00966
00967 static PatchFinder Finder;
00968 Vector<3> v3Cam = k.se3CfromW*p.v3WorldPos;
00969 if(v3Cam[2] < 0.001)
00970 {
00971 p.pMMData->sNeverRetryKFs.insert(&k);
00972 return false;
00973 }
00974 Vector<2> v2ImPlane = project(v3Cam);
00975 if(v2ImPlane* v2ImPlane > mCamera.LargestRadiusInImage() * mCamera.LargestRadiusInImage())
00976 {
00977 p.pMMData->sNeverRetryKFs.insert(&k);
00978 return false;
00979 }
00980
00981 Vector<2> v2Image = mCamera.Project(v2ImPlane);
00982 if(mCamera.Invalid())
00983 {
00984 p.pMMData->sNeverRetryKFs.insert(&k);
00985 return false;
00986 }
00987
00988 ImageRef irImageSize = k.aLevels[0].im.size();
00989 if(v2Image[0] < 0 || v2Image[1] < 0 || v2Image[0] > irImageSize[0] || v2Image[1] > irImageSize[1])
00990 {
00991 p.pMMData->sNeverRetryKFs.insert(&k);
00992 return false;
00993 }
00994
00995 Matrix<2> m2CamDerivs = mCamera.GetProjectionDerivs();
00996 Finder.MakeTemplateCoarse(p, k.se3CfromW, m2CamDerivs);
00997
00998 if(Finder.TemplateBad())
00999 {
01000 p.pMMData->sNeverRetryKFs.insert(&k);
01001 return false;
01002 }
01003
01004 bool bFound = Finder.FindPatchCoarse(ir(v2Image), k, 4);
01005 if(!bFound)
01006 {
01007 p.pMMData->sNeverRetryKFs.insert(&k);
01008 return false;
01009 }
01010
01011
01012 Measurement m;
01013 m.nLevel = Finder.GetLevel();
01014 m.Source = Measurement::SRC_REFIND;
01015
01016 if(Finder.GetLevel() > 0)
01017 {
01018 Finder.MakeSubPixTemplate();
01019 Finder.IterateSubPixToConvergence(k,8);
01020 m.v2RootPos = Finder.GetSubPixPos();
01021 m.bSubPix = true;
01022 }
01023 else
01024 {
01025 m.v2RootPos = Finder.GetCoarsePosAsVector();
01026 m.bSubPix = false;
01027 };
01028
01029 if(k.mMeasurements.count(&p))
01030 {
01031 assert(0);
01032 }
01033 k.mMeasurements[&p] = m;
01034 p.pMMData->sMeasurementKFs.insert(&k);
01035 return true;
01036 }
01037
01038
01039
01040 int MapMaker::ReFindInSingleKeyFrame(KeyFrame &k)
01041 {
01042 vector<MapPoint*> vToFind;
01043 for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
01044 vToFind.push_back(mMap.vpPoints[i]);
01045
01046 int nFoundNow = 0;
01047 for(unsigned int i=0; i<vToFind.size(); i++)
01048 if(ReFind_Common(k,*vToFind[i]))
01049 nFoundNow++;
01050
01051 return nFoundNow;
01052 };
01053
01054
01055
01056
01057 void MapMaker::ReFindNewlyMade()
01058 {
01059 if(mqNewQueue.empty())
01060 return;
01061 int nFound = 0;
01062 int nBad = 0;
01063 while(!mqNewQueue.empty() && mvpKeyFrameQueue.size() == 0)
01064 {
01065 MapPoint* pNew = mqNewQueue.front();
01066 mqNewQueue.pop();
01067 if(pNew->bBad)
01068 {
01069 nBad++;
01070 continue;
01071 }
01072 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
01073 if(ReFind_Common(*mMap.vpKeyFrames[i], *pNew))
01074 nFound++;
01075 }
01076 };
01077
01078
01079 void MapMaker::ReFindFromFailureQueue()
01080 {
01081 if(mvFailureQueue.size() == 0)
01082 return;
01083 sort(mvFailureQueue.begin(), mvFailureQueue.end());
01084 vector<pair<KeyFrame*, MapPoint*> >::iterator it;
01085 int nFound=0;
01086 for(it = mvFailureQueue.begin(); it!=mvFailureQueue.end(); it++)
01087 if(ReFind_Common(*it->first, *it->second))
01088 nFound++;
01089
01090 mvFailureQueue.erase(mvFailureQueue.begin(), it);
01091 };
01092
01093
01094 bool MapMaker::IsDistanceToNearestKeyFrameExcessive(KeyFrame &kCurrent)
01095 {
01096 return DistToNearestKeyFrame(kCurrent) > mdWiggleScale * 10.0;
01097 }
01098
01099
01100 SE3<> MapMaker::CalcPlaneAligner()
01101 {
01102 unsigned int nPoints = mMap.vpPoints.size();
01103 if(nPoints < 10)
01104 {
01105 cout << " MapMaker: CalcPlane: too few points to calc plane." << endl;
01106 return SE3<>();
01107 };
01108
01109 int nRansacs = GV2.GetInt("MapMaker.PlaneAlignerRansacs", 100, HIDDEN|SILENT);
01110 Vector<3> v3BestMean;
01111 Vector<3> v3BestNormal;
01112 double dBestDistSquared = 9999999999999999.9;
01113
01114 for(int i=0; i<nRansacs; i++)
01115 {
01116 int nA = rand()%nPoints;
01117 int nB = nA;
01118 int nC = nA;
01119 while(nB == nA)
01120 nB = rand()%nPoints;
01121 while(nC == nA || nC==nB)
01122 nC = rand()%nPoints;
01123
01124 Vector<3> v3Mean = 0.33333333 * (mMap.vpPoints[nA]->v3WorldPos +
01125 mMap.vpPoints[nB]->v3WorldPos +
01126 mMap.vpPoints[nC]->v3WorldPos);
01127
01128 Vector<3> v3CA = mMap.vpPoints[nC]->v3WorldPos - mMap.vpPoints[nA]->v3WorldPos;
01129 Vector<3> v3BA = mMap.vpPoints[nB]->v3WorldPos - mMap.vpPoints[nA]->v3WorldPos;
01130 Vector<3> v3Normal = v3CA ^ v3BA;
01131 if(v3Normal * v3Normal == 0)
01132 continue;
01133 normalize(v3Normal);
01134
01135 double dSumError = 0.0;
01136 for(unsigned int i=0; i<nPoints; i++)
01137 {
01138 Vector<3> v3Diff = mMap.vpPoints[i]->v3WorldPos - v3Mean;
01139 double dDistSq = v3Diff * v3Diff;
01140 if(dDistSq == 0.0)
01141 continue;
01142 double dNormDist = fabs((double)(v3Diff * v3Normal));
01143
01144 if(dNormDist > 0.05)
01145 dNormDist = 0.05;
01146 dSumError += dNormDist;
01147 }
01148 if(dSumError < dBestDistSquared)
01149 {
01150 dBestDistSquared = dSumError;
01151 v3BestMean = v3Mean;
01152 v3BestNormal = v3Normal;
01153 }
01154 }
01155
01156
01157 vector<Vector<3> > vv3Inliers;
01158 for(unsigned int i=0; i<nPoints; i++)
01159 {
01160 Vector<3> v3Diff = mMap.vpPoints[i]->v3WorldPos - v3BestMean;
01161 double dDistSq = v3Diff * v3Diff;
01162 if(dDistSq == 0.0)
01163 continue;
01164 double dNormDist = fabs((double)(v3Diff * v3BestNormal));
01165 if(dNormDist < 0.05)
01166 vv3Inliers.push_back(mMap.vpPoints[i]->v3WorldPos);
01167 }
01168
01169
01170 Vector<3> v3MeanOfInliers = Zeros;
01171 for(unsigned int i=0; i<vv3Inliers.size(); i++)
01172 v3MeanOfInliers+=vv3Inliers[i];
01173 v3MeanOfInliers *= (1.0 / vv3Inliers.size());
01174
01175 Matrix<3> m3Cov = Zeros;
01176 for(unsigned int i=0; i<vv3Inliers.size(); i++)
01177 {
01178 Vector<3> v3Diff = vv3Inliers[i] - v3MeanOfInliers;
01179 m3Cov += v3Diff.as_col() * v3Diff.as_row();
01180 };
01181
01182
01183 SymEigen<3> sym(m3Cov);
01184 Vector<3> v3Normal = sym.get_evectors()[0];
01185
01186
01187 if(v3Normal[2] > 0)
01188 v3Normal *= -1.0;
01189
01190 Matrix<3> m3Rot = Identity;
01191 m3Rot[2] = v3Normal;
01192 m3Rot[0] = m3Rot[0] - (v3Normal * (m3Rot[0] * v3Normal));
01193 normalize(m3Rot[0]);
01194 m3Rot[1] = m3Rot[2] ^ m3Rot[0];
01195
01196 SE3<> se3Aligner;
01197 se3Aligner.get_rotation() = m3Rot;
01198 Vector<3> v3RMean = se3Aligner * v3MeanOfInliers;
01199 se3Aligner.get_translation() = -v3RMean;
01200
01201 return se3Aligner;
01202 }
01203
01204
01205
01206
01207 void MapMaker::RefreshSceneDepth(KeyFrame *pKF)
01208 {
01209 double dSumDepth = 0.0;
01210 double dSumDepthSquared = 0.0;
01211 int nMeas = 0;
01212 for(meas_it it = pKF->mMeasurements.begin(); it!=pKF->mMeasurements.end(); it++)
01213 {
01214 MapPoint &point = *it->first;
01215 Vector<3> v3PosK = pKF->se3CfromW * point.v3WorldPos;
01216 dSumDepth += v3PosK[2];
01217 dSumDepthSquared += v3PosK[2] * v3PosK[2];
01218 nMeas++;
01219 }
01220
01221 assert(nMeas > 2);
01222 pKF->dSceneDepthMean = dSumDepth / nMeas;
01223 pKF->dSceneDepthSigma = sqrt((dSumDepthSquared / nMeas) - (pKF->dSceneDepthMean) * (pKF->dSceneDepthMean));
01224 }
01225
01226 void MapMaker::GUICommandCallBack(void* ptr, string sCommand, string sParams)
01227 {
01228 Command c;
01229 c.sCommand = sCommand;
01230 c.sParams = sParams;
01231 ((MapMaker*) ptr)->mvQueuedCommands.push_back(c);
01232 }
01233
01234 void MapMaker::GUICommandHandler(string sCommand, string sParams)
01235 {
01236 if(sCommand=="SaveMap")
01237 {
01238 cout << " MapMaker: Saving the map.... " << endl;
01239 ofstream ofs("map.dump");
01240 for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
01241 {
01242 ofs << mMap.vpPoints[i]->v3WorldPos << " ";
01243 ofs << mMap.vpPoints[i]->nSourceLevel << endl;
01244 }
01245 ofs.close();
01246
01247 for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
01248 {
01249 ostringstream ost1;
01250 ost1 << "keyframes/" << i << ".jpg";
01251
01252
01253 ostringstream ost2;
01254 ost2 << "keyframes/" << i << ".info";
01255 ofstream ofs2;
01256 ofs2.open(ost2.str().c_str());
01257 ofs2 << mMap.vpKeyFrames[i]->se3CfromW << endl;
01258 ofs2.close();
01259 }
01260 cout << " ... done saving map." << endl;
01261 return;
01262 }
01263
01264 cout << "! MapMaker::GUICommandHandler: unhandled command "<< sCommand << endl;
01265 exit(1);
01266 };
01267
01268
01269
01270
01271
01272
01273
01274
01275
01276
01277
01278