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