Go to the documentation of this file.00001
00002
00003 #ifndef __BUNDLE_H
00004 #define __BUNDLE_H
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #include "ATANCamera.h"
00026 #include <TooN/TooN.h>
00027 using namespace TooN;
00028 #include <TooN/se3.h>
00029 #include <vector>
00030 #include <map>
00031 #include <set>
00032 #include <list>
00033
00034
00035
00036
00037
00038 struct Camera
00039 {
00040 bool bFixed;
00041 SE3<> se3CfW;
00042 SE3<> se3CfWNew;
00043 Matrix<6> m6U;
00044 Vector<6> v6EpsilonA;
00045 int nStartRow;
00046 };
00047
00048
00049 struct OffDiagScriptEntry
00050 {
00051 int j;
00052 int k;
00053 };
00054
00055
00056 struct Point
00057 {
00058 inline Point()
00059 { nMeasurements = 0; nOutliers = 0;}
00060 Vector<3> v3Pos;
00061 Vector<3> v3PosNew;
00062 Matrix<3> m3V;
00063 Vector<3> v3EpsilonB;
00064 Matrix<3> m3VStarInv;
00065
00066 int nMeasurements;
00067 int nOutliers;
00068 std::set<int> sCameras;
00069 std::vector<OffDiagScriptEntry> vOffDiagonalScript;
00070 };
00071
00072
00073
00074 struct Meas
00075 {
00076 inline Meas()
00077 {bBad = false;}
00078
00079
00080 int p;
00081 int c;
00082
00083 inline bool operator<(const Meas &rhs) const
00084 { return(c<rhs.c ||(c==rhs.c && p < rhs.p)); }
00085
00086 bool bBad;
00087
00088 Vector<2> v2Found;
00089 Vector<2> v2Epsilon;
00090 Matrix<2,6> m26A;
00091 Matrix<2,3> m23B;
00092 Matrix<6,3> m63W;
00093 Matrix<6,3> m63Y;
00094 double dSqrtInvNoise;
00095
00096
00097 Vector<3> v3Cam;
00098 double dErrorSquared;
00099 Matrix<2> m2CamDerivs;
00100 };
00101
00102
00103 class Bundle
00104 {
00105 public:
00106
00107 Bundle(const ATANCamera &TCam);
00108 int AddCamera(SE3<> se3CamFromWorld, bool bFixed);
00109 int AddPoint(Vector<3> v3Pos);
00110 void AddMeas(int nCam, int nPoint, Vector<2> v2Pos, double dSigmaSquared);
00111 int Compute(bool *pbAbortSignal);
00112 inline bool Converged() { return mbConverged;}
00113 Vector<3> GetPoint(int n);
00114 SE3<> GetCamera(int n);
00115 std::vector<std::pair<int,int> > GetOutlierMeasurements();
00116 std::set<int> GetOutliers();
00117
00118 protected:
00119
00120 inline void ProjectAndFindSquaredError(Meas &meas);
00121 template<class MEstimator> bool Do_LM_Step(bool *pbAbortSignal);
00122 template<class MEstimator> double FindNewError();
00123 void GenerateMeasLUTs();
00124 void GenerateOffDiagScripts();
00125 void ClearAccumulators();
00126 void ModifyLambda_GoodStep();
00127 void ModifyLambda_BadStep();
00128
00129 std::vector<Point> mvPoints;
00130 std::vector<Camera> mvCameras;
00131 std::list<Meas> mMeasList;
00132 std::vector<std::pair<int,int> > mvOutlierMeasurementIdx;
00133 std::vector<std::vector<Meas*> > mvMeasLUTs;
00134
00135 ATANCamera mCamera;
00136 int mnCamsToUpdate;
00137 int mnStartRow;
00138 double mdSigmaSquared;
00139 double mdLambda;
00140 double mdLambdaFactor;
00141 bool mbConverged;
00142 bool mbHitMaxIterations;
00143 int mnCounter;
00144 int mnAccepted;
00145
00146 GVars3::gvar3<int> mgvnMaxIterations;
00147 GVars3::gvar3<double> mgvdUpdateConvergenceLimit;
00148 GVars3::gvar3<int> mgvnBundleCout;
00149
00150 bool *mpbAbortSignal;
00151 };
00152
00153
00154
00155
00156
00157 #endif