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.
Bundle.h
Go to the documentation of this file.
1 // -*- c++ -*-
2 // Copyright 2008 Isis Innovation Limited
3 #ifndef __BUNDLE_H
4 #define __BUNDLE_H
5 // Bundle.h
6 //
7 // This file declares the Bundle class along with a few helper classes.
8 // Bundle is the bundle adjustment core of the mapping system; instances
9 // of Bundle are generated by MapMaker to adjust the positions of
10 // keyframes (called Cameras in this file) and map points.
11 //
12 // It's a pretty straight-forward Levenberg-Marquardt bundle adjustment
13 // implementation closely following Hartley and Zisserman's MVG book, with
14 // the addition of a robust M-Estimator.
15 //
16 // Unfortunately, having undergone a few tweaks, the code is now
17 // not the easiest to read!
18 //
19 // Basic operation: MapMaker creates a new Bundle object;
20 // then adds map points and keyframes to adjust;
21 // then adds measurements of map points in keyframes;
22 // then calls Compute() to do bundle adjustment;
23 // then reads results back to update the map.
24 
25 #include "ATANCamera.h"
26 #include "TooN.h"
27 using namespace TooN;
28 #include "se3.h"
29 #include <vector>
30 #include <map>
31 #include <set>
32 #include <list>
33 #include "globals.h"
34 
35 
36 // An index into the big measurement map which stores all the measurements.
37 
38 // Camera struct holds the pose of a keyframe
39 // and some computation intermediates
40 struct Camera
41 {
42  bool bFixed;
45  Matrix<6> m6U; // Accumulator
46  Vector<6> v6EpsilonA; // Accumulator
47  int nStartRow;
48 };
49 
50 // Camera-camera pair index
52 {
53  int j;
54  int k;
55 };
56 
57 // A map point, plus computation intermediates.
59 {
61  { nMeasurements = 0; nOutliers = 0;}
64  Matrix<3> m3V; // Accumulator
65  Vector<3> v3EpsilonB; // Accumulator
67 
69  int nOutliers;
70  std::set<int> sCameras; // Which cameras observe this point?
71  std::vector<OffDiagScriptEntry> vOffDiagonalScript; // A record of all camera-camera pairs observing this point
72 };
73 
74 // A measurement of a point by a camera, plus
75 // computation intermediates.
76 struct Meas
77 {
78  inline Meas()
79  {bBad = false;}
80 
81  // Which camera/point did this measurement come from?
82  int p; // The point - called i in MVG
83  int c; // The camera - called j in MVG
84 
85  inline bool operator<(const Meas &rhs) const
86  { return(c<rhs.c ||(c==rhs.c && p < rhs.p)); }
87 
88  bool bBad;
89 
96  double dSqrtInvNoise;
97 
98  // Temporary projection quantities
102 };
103 
104 // Core bundle adjustment class
105 class Bundle
106 {
107 public:
108 
109  Bundle(const ATANCamera &TCam); // We need the camera model because we do full distorting projection in the bundle adjuster. Could probably get away with a linear approximation.
110  int AddCamera(SE3<> se3CamFromWorld, bool bFixed); // Add a viewpoint. bFixed signifies that this one is not to be adjusted.
111  int AddPoint(Vector<3> v3Pos); // Add a map point.
112  void AddMeas(int nCam, int nPoint, Vector<2> v2Pos, double dSigmaSquared); // Add a measurement
113  int Compute(bool *pbAbortSignal); // Perform bundle adjustment. Aborts if *pbAbortSignal gets set to true. Returns number of accepted update iterations, or negative on error.
114  inline bool Converged() { return mbConverged;} // Has bundle adjustment converged?
115  Vector<3> GetPoint(int n); // Point coords after adjustment
116  SE3<> GetCamera(int n); // Camera pose after adjustment
117  std::vector<std::pair<int,int> > GetOutlierMeasurements(); // Measurements flagged as outliers
118  std::set<int> GetOutliers(); // Points flagged as outliers
119 
120 protected:
121 
122  inline void ProjectAndFindSquaredError(Meas &meas); // Project a single point in a single view, compare to measurement
123  template<class MEstimator> bool Do_LM_Step(bool *pbAbortSignal, double *lastMdSigmaSquared);
124  template<class MEstimator> double FindNewError();
125  void GenerateMeasLUTs();
126  void GenerateOffDiagScripts();
127  void ClearAccumulators(); // Zero temporary quantities stored in cameras and points
128  void ModifyLambda_GoodStep();
129  void ModifyLambda_BadStep();
130 
131  std::vector<ExtendedMapPoint> mvPoints;
132  std::vector<Camera> mvCameras;
133  std::list<Meas> mMeasList;
134  std::vector<std::pair<int,int> > mvOutlierMeasurementIdx; // p-c pair
135  std::vector<std::vector<Meas*> > mvMeasLUTs; //Each camera gets a per-point table of pointers to valid measurements
136 
141  double mdLambda;
147 
151 
153 
154 };
155 
156 
157 
158 
159 
160 
161 #endif
double mdLambda
Definition: Bundle.h:141
int mnCounter
Definition: Bundle.h:145
Matrix< 2, 3 > m23B
Definition: Bundle.h:93
std::set< int > sCameras
Definition: Bundle.h:70
int c
Definition: Bundle.h:83
bool operator<(const Meas &rhs) const
Definition: Bundle.h:85
SE3 se3CfW
Definition: Bundle.h:43
int mgvnBundleCout
Definition: Bundle.h:150
Matrix< 3 > m3V
Definition: Bundle.h:64
Matrix< 6, 3 > m63W
Definition: Bundle.h:94
Vector< 2 > v2Epsilon
Definition: Bundle.h:91
Definition: Bundle.h:105
double mgvdUpdateConvergenceLimit
Definition: Bundle.h:149
bool mbHitMaxIterations
Definition: Bundle.h:144
Everything lives inside this namespace.
Definition: allocator.hh:48
bool bFixed
Definition: Bundle.h:42
Definition: Bundle.h:76
int mnStartRow
Definition: Bundle.h:139
bool mbConverged
Definition: Bundle.h:143
Vector< 3 > v3Cam
Definition: Bundle.h:99
double mdSigmaSquared
Definition: Bundle.h:140
double mdLambdaFactor
Definition: Bundle.h:142
Matrix< 6 > m6U
Definition: Bundle.h:45
double dErrorSquared
Definition: Bundle.h:100
Vector< 2 > v2Found
Definition: Bundle.h:90
Vector< 3 > v3PosNew
Definition: Bundle.h:63
std::list< Meas > mMeasList
Definition: Bundle.h:133
Definition: se3.h:50
bool * mpbAbortSignal
Definition: Bundle.h:152
int p
Definition: Bundle.h:82
Matrix< 2, 6 > m26A
Definition: Bundle.h:92
std::vector< Camera > mvCameras
Definition: Bundle.h:132
int nMeasurements
Definition: Bundle.h:68
bool bBad
Definition: Bundle.h:88
ATANCamera mCamera
Definition: Bundle.h:137
Vector< 6 > v6EpsilonA
Definition: Bundle.h:46
int mnAccepted
Definition: Bundle.h:146
ExtendedMapPoint()
Definition: Bundle.h:60
Vector< 3 > v3Pos
Definition: Bundle.h:62
Matrix< 6, 3 > m63Y
Definition: Bundle.h:95
Meas()
Definition: Bundle.h:78
std::vector< OffDiagScriptEntry > vOffDiagonalScript
Definition: Bundle.h:71
Matrix< 2 > m2CamDerivs
Definition: Bundle.h:101
int nStartRow
Definition: Bundle.h:47
Matrix< 3 > m3VStarInv
Definition: Bundle.h:66
double dSqrtInvNoise
Definition: Bundle.h:96
int mgvnMaxIterations
Definition: Bundle.h:148
std::vector< ExtendedMapPoint > mvPoints
Definition: Bundle.h:131
SE3 se3CfWNew
Definition: Bundle.h:44
bool Converged()
Definition: Bundle.h:114
std::vector< std::pair< int, int > > mvOutlierMeasurementIdx
Definition: Bundle.h:134
int mnCamsToUpdate
Definition: Bundle.h:138
std::vector< std::vector< Meas * > > mvMeasLUTs
Definition: Bundle.h:135
Definition: Bundle.h:40
Vector< 3 > v3EpsilonB
Definition: Bundle.h:65