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