SLAMflex SE  0.1.0
SLAMflex provides detection and tracking of dominant planes for smartphone devices. This plane can then be used to show AR content relative to the plane orientation. The detection of plane is performed in the field of view of the smartphone camera. In subsequent frames it is tracked. The interface returns the plane position and orientation.
MapMaker.h
Go to the documentation of this file.
1 // -*- c++ -*-
2 // Copyright 2008 Isis Innovation Limited
3 
4 //
5 // This header declares the MapMaker class
6 // MapMaker makes and maintains the Map struct
7 // Starting with stereo initialisation from a bunch of matches
8 // over keyframe insertion, continual bundle adjustment and
9 // data-association refinement.
10 // MapMaker runs in its own thread, although some functions
11 // (notably stereo init) are called by the tracker and run in the
12 // tracker's thread.
13 
14 #ifndef __MAPMAKER_H
15 #define __MAPMAKER_H
16 #include "image.h"
17 #include "byte.h"
18 #include "thread.h"
19 
20 #include "Map.h"
21 #include "KeyFrame.h"
22 #include "ATANCamera.h"
23 #include <queue>
24 #include "SendMessage.h"
25 
26 
27 // Each MapPoint has an associated MapMakerData class
28 // Where the mapmaker can store extra information
29 
31 {
32  std::set<KeyFrame*> sMeasurementKFs; // Which keyframes has this map point got measurements in?
33  std::set<KeyFrame*> sNeverRetryKFs; // Which keyframes have measurements failed enough so I should never retry?
34  inline int GoodMeasCount()
35  { return sMeasurementKFs.size(); }
36 };
37 
38 // MapMaker dervives from CVD::Thread, so everything in void run() is its own thread.
39 class MapMaker : protected CVD::Thread
40 {
41 public:
42  MapMaker(Map &m, const ATANCamera &cam);
43  ~MapMaker();
44 
45  // Make a map from scratch. Called by the tracker.
46  bool InitFromStereo(KeyFrame &kFirst, KeyFrame &kSecond,
47  std::vector<std::pair<CVD::ImageRef, CVD::ImageRef> > &vMatches,
48  SE3<> &se3CameraPos);
49 
50  bool InitFromStereo_OLD(KeyFrame &kFirst, KeyFrame &kSecond, // EXPERIMENTAL HACK
51  std::vector<std::pair<CVD::ImageRef, CVD::ImageRef> > &vMatches,
52  SE3<> &se3CameraPos);
53 
54 
55  void AddKeyFrame(KeyFrame &k); // Add a key-frame to the map. Called by the tracker.
56  void RequestReset(); // Request that the we reset. Called by the tracker.
57  bool ResetDone(); // Returns true if the has been done.
58  int QueueSize() { return mvpKeyFrameQueue.size() ;} // How many KFs in the queue waiting to be added?
59  bool NeedNewKeyFrame(KeyFrame &kCurrent); // Is it a good camera pose to add another KeyFrame?
60  bool IsDistanceToNearestKeyFrameExcessive(KeyFrame &kCurrent); // Is the camera far away from the nearest KeyFrame (i.e. maybe lost?)
61  void SetSendMessageToUnity(SendMessage sm); //Used for setting one way communication between Tracker and Unity
62 
63 protected:
64 
65  Map &mMap; // The map
66  ATANCamera mCamera; // Same as the tracker's camera: N.B. not a reference variable!
67  virtual void run(); // The MapMaker thread code lives here
68 
69  // Functions for starting the map from scratch:
71  void ApplyGlobalTransformationToMap(SE3<> se3NewFromOld);
72  void ApplyGlobalScaleToMap(double dScale);
73 
74  // Map expansion functions:
76  void ThinCandidates(KeyFrame &k, int nLevel);
77  void AddSomeMapPoints(int nLevel);
78  bool AddPointEpipolar(KeyFrame &kSrc, KeyFrame &kTarget, int nLevel, int nCandidate);
79  // Returns point in ref frame B
80  Vector<3> ReprojectPoint(SE3<> se3AfromB, const Vector<2> &v2A, const Vector<2> &v2B);
81 
82  // Bundle adjustment functions:
83  void BundleAdjust(std::set<KeyFrame*>, std::set<KeyFrame*>, std::set<MapPoint*>, bool);
84  void BundleAdjustAll();
85  void BundleAdjustRecent();
86 
87  // Data association functions:
90  void ReFindNewlyMade();
91  void ReFindAll();
92  bool ReFind_Common(KeyFrame &k, MapPoint &p);
93  void SubPixelRefineMatches(KeyFrame &k, int nLevel);
94 
95  // General Maintenance/Utility:
96  void Reset();
97  void HandleBadPoints();
98  double DistToNearestKeyFrame(KeyFrame &kCurrent);
99  double KeyFrameLinearDist(KeyFrame &k1, KeyFrame &k2);
101  std::vector<KeyFrame*> NClosestKeyFrames(KeyFrame &k, unsigned int N);
102  void RefreshSceneDepth(KeyFrame *pKF);
103 
104 
105  // GUI Interface:
106  void GUICommandHandler(std::string sCommand, std::string sParams);
107  static void GUICommandCallBack(void* ptr, std::string sCommand, std::string sParams);
108  struct Command {std::string sCommand; std::string sParams; };
109  std::vector<Command> mvQueuedCommands;
110 
111 
112  // Member variables:
113  std::vector<KeyFrame*> mvpKeyFrameQueue; // Queue of keyframes from the tracker waiting to be processed
114  std::vector<std::pair<KeyFrame*, MapPoint*> > mvFailureQueue; // Queue of failed observations to re-find
115  std::queue<MapPoint*> mqNewQueue; // Queue of newly-made map points to re-find in other KeyFrames
116 
117  double mdWiggleScale; // Metric distance between the first two KeyFrames (copied from GVar)
118  // This sets the scale of the map
119  double mgvdWiggleScale; // GVar for above
120  double mdWiggleScaleDepthNormalized; // The above normalized against scene depth,
121  // this controls keyframe separation
122 
123  bool mbBundleConverged_Full; // Has global bundle adjustment converged?
124  bool mbBundleConverged_Recent; // Has local bundle adjustment converged?
125 
126  // Thread interaction signalling stuff
127  bool mbResetRequested; // A reset has been requested
128  bool mbResetDone; // The reset was done.
129  bool mbBundleAbortRequested; // We should stop bundle adjustment
130  bool mbBundleRunning; // Bundle adjustment is running
131  bool mbBundleRunningIsRecent; // ... and it's a local bundle adjustment.
132 
133  //SLAMflex
134  SendMessage sendStringToUnity; //Used to send message to Unity
137 
138 
139 
140 };
141 
142 #endif
143 
144 
145 
146 
147 
148 
149 
150 
151 
152 
153 
154 
155 
156 
157 
158 
159 
160 
bool mbBundleConverged_Recent
Definition: MapMaker.h:124
KeyFrame * ClosestKeyFrame(KeyFrame &k)
Definition: MapMaker.cpp:680
bool IsDistanceToNearestKeyFrameExcessive(KeyFrame &kCurrent)
Definition: MapMaker.cpp:1046
void GUICommandHandler(std::string sCommand, std::string sParams)
Definition: MapMaker.cpp:1186
std::queue< MapPoint * > mqNewQueue
Definition: MapMaker.h:115
Vector< 3 > ReprojectPoint(SE3<> se3AfromB, const Vector< 2 > &v2A, const Vector< 2 > &v2B)
Definition: MapMaker.cpp:173
void SubPixelRefineMatches(KeyFrame &k, int nLevel)
void AddSomeMapPoints(int nLevel)
Definition: MapMaker.cpp:407
std::vector< KeyFrame * > NClosestKeyFrames(KeyFrame &k, unsigned int N)
Definition: MapMaker.cpp:660
std::vector< Command > mvQueuedCommands
Definition: MapMaker.h:109
int counterForConvergenceLimit
Definition: MapMaker.h:136
bool AddPointEpipolar(KeyFrame &kSrc, KeyFrame &kTarget, int nLevel, int nCandidate)
Definition: MapMaker.cpp:497
void SetSendMessageToUnity(SendMessage sm)
Definition: MapMaker.cpp:56
SendMessage sendStringToUnity
Definition: MapMaker.h:134
int QueueSize()
Definition: MapMaker.h:58
bool ResetDone()
Definition: MapMaker.cpp:126
bool NeedNewKeyFrame(KeyFrame &kCurrent)
Definition: MapMaker.cpp:706
void ReFindAll()
bool ReFind_Common(KeyFrame &k, MapPoint &p)
Definition: MapMaker.cpp:911
void AddKeyFrame(KeyFrame &k)
Definition: MapMaker.cpp:453
double mdWiggleScaleDepthNormalized
Definition: MapMaker.h:120
SE3 CalcPlaneAligner()
Definition: MapMaker.cpp:1052
bool mbBundleRunningIsRecent
Definition: MapMaker.h:131
virtual void run()
Override this method to do whatever it is the thread should do.
Definition: MapMaker.cpp:66
MapMaker(Map &m, const ATANCamera &cam)
Definition: MapMaker.cpp:29
void BundleAdjustRecent()
Definition: MapMaker.cpp:739
void ApplyGlobalTransformationToMap(SE3<> se3NewFromOld)
Definition: MapMaker.cpp:420
std::string sParams
Definition: MapMaker.h:108
void ReFindFromFailureQueue()
Definition: MapMaker.cpp:1031
bool mbBundleRunning
Definition: MapMaker.h:130
ATANCamera mCamera
Definition: MapMaker.h:66
Definition: se3.h:50
void RequestReset()
Definition: MapMaker.cpp:120
std::vector< std::pair< KeyFrame *, MapPoint * > > mvFailureQueue
Definition: MapMaker.h:114
bool InitFromStereo(KeyFrame &kFirst, KeyFrame &kSecond, std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > &vMatches, SE3<> &se3CameraPos)
Definition: MapMaker.cpp:196
std::set< KeyFrame * > sMeasurementKFs
Definition: MapMaker.h:32
int ReFindInSingleKeyFrame(KeyFrame &k)
Definition: MapMaker.cpp:992
bool mbBundleConverged_Full
Definition: MapMaker.h:123
void HandleBadPoints()
Definition: MapMaker.cpp:133
bool mbBundleAbortRequested
Definition: MapMaker.h:129
Definition: Map.h:24
double DistToNearestKeyFrame(KeyFrame &kCurrent)
Definition: MapMaker.cpp:699
void ThinCandidates(KeyFrame &k, int nLevel)
Definition: MapMaker.cpp:369
void RefreshSceneDepth(KeyFrame *pKF)
Definition: MapMaker.cpp:1159
bool mbResetRequested
Definition: MapMaker.h:127
void BundleAdjustAll()
Definition: MapMaker.cpp:718
int GoodMeasCount()
Definition: MapMaker.h:34
static void GUICommandCallBack(void *ptr, std::string sCommand, std::string sParams)
Definition: MapMaker.cpp:1178
bool InitFromStereo_OLD(KeyFrame &kFirst, KeyFrame &kSecond, std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > &vMatches, SE3<> &se3CameraPos)
double mdWiggleScale
Definition: MapMaker.h:117
std::vector< KeyFrame * > mvpKeyFrameQueue
Definition: MapMaker.h:113
void AddKeyFrameFromTopOfQueue()
Definition: MapMaker.cpp:464
void ApplyGlobalScaleToMap(double dScale)
Definition: MapMaker.cpp:435
std::string sCommand
Definition: MapMaker.h:108
Map & mMap
Definition: MapMaker.h:65
int counterForConvergence
Definition: MapMaker.h:135
void ReFindNewlyMade()
Definition: MapMaker.cpp:1009
double KeyFrameLinearDist(KeyFrame &k1, KeyFrame &k2)
Definition: MapMaker.cpp:651
std::set< KeyFrame * > sNeverRetryKFs
Definition: MapMaker.h:33
bool mbResetDone
Definition: MapMaker.h:128
void Reset()
Definition: MapMaker.cpp:38
void BundleAdjust(std::set< KeyFrame * >, std::set< KeyFrame * >, std::set< MapPoint * >, bool)
Definition: MapMaker.cpp:789
double mgvdWiggleScale
Definition: MapMaker.h:119