MapMaker.h
Go to the documentation of this file.
00001 // -*- c++ -*-
00002 // Copyright 2008 Isis Innovation Limited
00003 
00004 //
00005 // This header declares the MapMaker class
00006 // MapMaker makes and maintains the Map struct
00007 // Starting with stereo initialisation from a bunch of matches
00008 // over keyframe insertion, continual bundle adjustment and 
00009 // data-association refinement.
00010 // MapMaker runs in its own thread, although some functions
00011 // (notably stereo init) are called by the tracker and run in the 
00012 // tracker's thread.
00013 
00014 #ifndef __MAPMAKER_H
00015 #define __MAPMAKER_H
00016 #include <cvd/image.h>
00017 #include <cvd/byte.h>
00018 #include <cvd/thread.h>
00019 
00020 #include "Map.h"
00021 #include "KeyFrame.h"
00022 #include "ATANCamera.h"
00023 #include <queue>
00024 
00025 
00026 // Each MapPoint has an associated MapMakerData class
00027 // Where the mapmaker can store extra information
00028  
00029 struct MapMakerData
00030 {
00031   std::set<KeyFrame*> sMeasurementKFs;   // Which keyframes has this map point got measurements in?
00032   std::set<KeyFrame*> sNeverRetryKFs;    // Which keyframes have measurements failed enough so I should never retry?
00033   inline int GoodMeasCount()            
00034   {  return sMeasurementKFs.size(); }
00035 };
00036 
00037 // MapMaker dervives from CVD::Thread, so everything in void run() is its own thread.
00038 class MapMaker : protected CVD::Thread
00039 {
00040 public:
00041   MapMaker(Map &m, const ATANCamera &cam);
00042   ~MapMaker();
00043   
00044   // Make a map from scratch. Called by the tracker.
00045   bool InitFromStereo(KeyFrame &kFirst, KeyFrame &kSecond, 
00046                       std::vector<std::pair<CVD::ImageRef, CVD::ImageRef> > &vMatches,
00047                       SE3<> &se3CameraPos,
00048                           SE3<> KFZeroDesiredCamFromWorld,
00049                           SE3<> KFOneDesiredCamFromWorld);
00050 
00051   bool InitFromStereo_OLD(KeyFrame &kFirst, KeyFrame &kSecond,  // EXPERIMENTAL HACK
00052                       std::vector<std::pair<CVD::ImageRef, CVD::ImageRef> > &vMatches,
00053                       SE3<> &se3CameraPos);
00054   
00055   
00056   void AddKeyFrame(KeyFrame &k);   // Add a key-frame to the map. Called by the tracker.
00057   void RequestReset();   // Request that the we reset. Called by the tracker.
00058   bool ResetDone();      // Returns true if the has been done.
00059   int  QueueSize() { return mvpKeyFrameQueue.size() ;} // How many KFs in the queue waiting to be added?
00060   bool NeedNewKeyFrame(KeyFrame &kCurrent);            // Is it a good camera pose to add another KeyFrame?
00061   bool IsDistanceToNearestKeyFrameExcessive(KeyFrame &kCurrent);  // Is the camera far away from the nearest KeyFrame (i.e. maybe lost?)
00062   
00063   void SetMinTolerance(double min_tol){
00064       this->min_tol = min_tol;
00065   }
00066 
00067   double initialScaleFactor;
00068   double currentScaleFactor;    // set exgternally for metric scale.
00069   double minKFWiggleDist;
00070   double minKFDist;
00071   double lastMetricDist;
00072   double lastWiggleDist;
00073 
00074   //Tolerance Interval
00075   double min_tol;
00076   double max_tol;
00077 
00078 protected:
00079   
00080   Map &mMap;               // The map
00081   ATANCamera mCamera;      // Same as the tracker's camera: N.B. not a reference variable!
00082   virtual void run();      // The MapMaker thread code lives here
00083 
00084   // Functions for starting the map from scratch:
00085   SE3<> CalcPlaneAligner();
00086   void ApplyGlobalTransformationToMap(SE3<> se3NewFromOld);
00087   void ApplyGlobalScaleToMap(double dScale);
00088   
00089   // Map expansion functions:
00090   void AddKeyFrameFromTopOfQueue();  
00091   void ThinCandidates(KeyFrame &k, int nLevel);
00092   void AddSomeMapPoints(int nLevel);
00093   bool AddPointEpipolar(KeyFrame &kSrc, KeyFrame &kTarget, int nLevel, int nCandidate);
00094   // Returns point in ref frame B
00095   Vector<3> ReprojectPoint(SE3<> se3AfromB, const Vector<2> &v2A, const Vector<2> &v2B);
00096   
00097   // Bundle adjustment functions:
00098   void BundleAdjust(std::set<KeyFrame*>, std::set<KeyFrame*>, std::set<MapPoint*>, bool);
00099   void BundleAdjustAll();
00100   void BundleAdjustRecent();
00101 
00102   // Data association functions:
00103   int ReFindInSingleKeyFrame(KeyFrame &k);
00104   void ReFindFromFailureQueue();
00105   void ReFindNewlyMade();
00106   void ReFindAll();
00107   bool ReFind_Common(KeyFrame &k, MapPoint &p);
00108   void SubPixelRefineMatches(KeyFrame &k, int nLevel);
00109   
00110   // General Maintenance/Utility:
00111   void Reset();
00112   void HandleBadPoints();
00113   double DistToNearestKeyFrame(KeyFrame &kCurrent);
00114   double KeyFrameLinearDist(KeyFrame &k1, KeyFrame &k2);
00115   KeyFrame* ClosestKeyFrame(KeyFrame &k);
00116   std::vector<KeyFrame*> NClosestKeyFrames(KeyFrame &k, unsigned int N);
00117   void RefreshSceneDepth(KeyFrame *pKF);
00118   
00119 
00120   // GUI Interface:
00121   void GUICommandHandler(std::string sCommand, std::string sParams);
00122   static void GUICommandCallBack(void* ptr, std::string sCommand, std::string sParams);
00123   struct Command {std::string sCommand; std::string sParams; };
00124   std::vector<Command> mvQueuedCommands;
00125   
00126 
00127   // Member variables:
00128   std::vector<KeyFrame*> mvpKeyFrameQueue;  // Queue of keyframes from the tracker waiting to be processed
00129   std::vector<std::pair<KeyFrame*, MapPoint*> > mvFailureQueue; // Queue of failed observations to re-find
00130   std::queue<MapPoint*> mqNewQueue;   // Queue of newly-made map points to re-find in other KeyFrames
00131   
00132   double mdWiggleScale;  // Metric distance between the first two KeyFrames (copied from GVar)
00133                          // This sets the scale of the map
00134   GVars3::gvar3<double> mgvdWiggleScale;   // GVar for above
00135   double mdWiggleScaleDepthNormalized;  // The above normalized against scene depth, 
00136                                         // this controls keyframe separation
00137   
00138   bool mbBundleConverged_Full;    // Has global bundle adjustment converged?
00139   bool mbBundleConverged_Recent;  // Has local bundle adjustment converged?
00140   
00141   // Thread interaction signalling stuff
00142   bool mbResetRequested;   // A reset has been requested
00143   bool mbResetDone;        // The reset was done.
00144   bool mbBundleAbortRequested;      // We should stop bundle adjustment
00145   bool mbBundleRunning;             // Bundle adjustment is running
00146   bool mbBundleRunningIsRecent;     //    ... and it's a local bundle adjustment.
00147 };
00148 
00149 #endif
00150 
00151 
00152 
00153 
00154 
00155 
00156 
00157 
00158 
00159 
00160 
00161 
00162 
00163 
00164 
00165 
00166 
00167 


uga_tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:30:11