42 #ifndef EIGEN_USE_NEW_STDVECTOR    43 #define EIGEN_USE_NEW_STDVECTOR    44 #endif // EIGEN_USE_NEW_STDVECTOR    49 #include <Eigen/Geometry>    51 #include <Eigen/StdVector>    54 #include <Eigen/Cholesky>    66 #define SBA_DENSE_CHOLESKY 0    67 #define SBA_SPARSE_CHOLESKY 1    68 #define SBA_GRADIENT 2    69 #define SBA_BLOCK_JACOBIAN_PCG 3    78       EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
    86           verbose = 1; 
huber = 0.0; }
    89       std::vector<Node, Eigen::aligned_allocator<Node> > 
nodes;
    95       std::vector<Track, Eigen::aligned_allocator<Track> > 
tracks;
   158       int doSBA(
int niter, 
double lambda = 1.0e-4, 
int useCSparse = 0, 
double initTol = 1.0e-8,
   159                   int maxCGiters = 100);
   171       int addNode(Eigen::Matrix<double,4,1> &trans, 
   172                       Eigen::Quaternion<double> &qrot,
   174                       bool isFixed = 
false);
   192       bool addProj(
int ci, 
int pi, Eigen::Vector3d &q, 
bool stereo=
true);
   203       bool addMonoProj(
int ci, 
int pi, Eigen::Vector2d &q);
   234       void addPointPlaneMatch(
int ci0, 
int pi0, Eigen::Vector3d normal0, 
int ci1, 
int pi1, Eigen::Vector3d normal1);
   260       void mergeTracks(std::vector<std::pair<int,int> > &prs);
   279       void tsplit(
int tri, 
int len);
   282       std::vector<Point, Eigen::aligned_allocator<Point> > 
oldpoints;
   285       std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > 
tps;
   288         std::vector<JacobProds, Eigen::aligned_allocator<JacobProds> > 
jps;
   300     EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
   311     Eigen::Matrix<double,6,6> 
prec;
   315     Eigen::Matrix<double,6,1> 
err;
   317     inline double calcErr(
const Node &nd0, 
const Node &nd1);
   320     double calcErrDist(
const Node &nd0, 
const Node &nd1);
   324     Eigen::Matrix<double,6,6> J0,J0t,J1,
J1t;
   328     const static double qScale = 1.0;
   339     void setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > &
nodes);
   352     EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
   372       inline double calcErr(
const Node &nd0, 
const Node &nd1, 
double alpha);
   383     void setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > &
nodes);
   397     EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
   406     Eigen::Matrix<double,12,1> 
mean;
   407     Eigen::Matrix<double,12,12> 
prec;
   410     Eigen::Matrix<double,12,1> 
err;
   412     Eigen::Matrix<double,12,1> calcErr(
const Node &nd, 
const Point &pt);
   415     Eigen::Matrix<double,6,6> J10, J11, J20, 
J22;
   426     void setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > 
nodes);
   429     Eigen::Matrix<double,3,6> 
Hpc;
   430     Eigen::Matrix<double,6,3> 
Tpc;
   443       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
   457       int addNode(Eigen::Matrix<double,4,1> &trans, 
   458                       Eigen::Quaternion<double> &qrot,
   459                       bool isFixed = 
false);
   468       bool addConstraint(
int nd0, 
int nd1,
   469                         Eigen::Vector3d &tmean,
   470                         Eigen::Quaterniond &qpmean,
   471                         Eigen::Matrix<double,6,6> &prec);
   474       std::vector<Node,Eigen::aligned_allocator<Node> > 
nodes;
   483       std::vector<ConP2,Eigen::aligned_allocator<ConP2> >  
p2cons;
   486       std::vector<ConScale,Eigen::aligned_allocator<ConScale> >  
scons;
   493       double calcCost(
bool tcost = 
false);
   500       void writeSparseA(
char *fname, 
bool useCSparse = 
false); 
   512                   double initTol = 1.0e-8, 
int CGiters = 50);
   518       void spanningTree(
int node=0);
   522       void addConstraint(
int pr, 
int p0, 
int p1, Eigen::Matrix<double,12,1> &mean, Eigen::Matrix<double,12,12> &prec);
 
int nFixed
Number of fixed nodes (nodes with known poses) from the first node. 
#define SBA_SPARSE_CHOLESKY
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int verbose
How much information to print to console. 
SysSPA holds a set of nodes and constraints for sparse pose adjustment. 
bool readP2File(char *fname, SysSPA spa)
constraint files 
void setupSparseSys(double sLambda, int iter, int sparseType)
void setConnMat(int minpts)
bool isValid
valid or not (could be out of bounds) 
int removeBad(double dist)
Remove projections with too high of an error. 
Eigen::Matrix< double, 12, 1 > err
error 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SysSPA()
constructor 
Eigen::MatrixXd A
linear system matrix and vector 
int numBadPoints()
Find number of points with Z < 0 (projected behind the camera). 
SysSBA holds a set of nodes and points for sparse bundle adjustment. 
Eigen::Matrix< double, 6, 6 > prec
vector< map< int, int > > generateConns_()
Eigen::Matrix< double, 6, 6 > J1t
void useCholmod(bool yes)
use CHOLMOD or CSparse 
bool isValid
valid or not (could be out of bounds) 
std::vector< JacobProds, Eigen::aligned_allocator< JacobProds > > jps
storage for Jacobian products 
int nd1
Node index for the second node. 
double sqMinDelta
Convergence bound (square of minimum acceptable delta change) 
int countBad(double dist)
Find number of projections with errors over a certain value. 
void updateNormals()
Update normals in point-plane matches, if any. 
Eigen::Matrix< double, 4, 1 > oldqrot
Eigen::Vector3d tmean
Mean vector, quaternion (inverse) and precision matrix for this constraint. 
int nd1
Node index for the second node. 
double calcCost()
Calculate the total cost of the system by adding the squared error over all projections. 
Eigen::Matrix< double, 12, 1 > mean
Mean vector and precision matrix for this constraint. 
std::vector< double > scales
set of scale for SPA system, indexed by position; 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int ndr
Reference pose index. 
int reduceLongTracks(double pct)
get rid of long tracks 
double w
Weight for this constraint. 
int mergeTracksSt(int tr0, int tr1)
merge two tracks if possible (no conflicts) 
bool addMonoProj(int ci, int pi, Eigen::Vector2d &q)
Add a projection between point and camera, in setting up the system. 
NODE holds graph nodes corresponding to frames, for use in sparse bundle adjustment. Each node has a 6DOF pose, encoded as a translation vector and rotation unit quaternion (Eigen classes). These represent the pose of the node in the world frame. 
std::vector< Track, Eigen::aligned_allocator< Track > > tracks
Set of tracks for each point P (projections onto camera frames). 
static void initDr()
Sets up constant matrices for derivatives. 
int doSBA(int niter, double lambda=1.0e-4, int useCSparse=0, double initTol=1.0e-8, int maxCGiters=100)
std::vector< Point, Eigen::aligned_allocator< Point > > oldpoints
Storage for old points, for checking LM step and reverting. 
std::vector< Node, Eigen::aligned_allocator< Node > > nodes
Set of nodes (camera frames) for SBA system, indexed by node number. 
double calcRMSCost(double dist=10000.0)
Calculates total RMS cost of the system, not counting projections with errors higher than <dist>...
SysSBA()
Default constructor. 
double calcAvgError()
Calculates average cost of the system. 
std::vector< std::vector< bool > > connMat
CSparse csp
sparse matrix object 
bool useLocalAngles
local or global angle coordinates 
int addNode(Eigen::Matrix< double, 4, 1 > &trans, Eigen::Quaternion< double > &qrot, const fc::CamParams &cp, bool isFixed=false)
Adds a node to the system. 
void writeSparseA(const char *fname, SysSBA &sba)
Eigen::Matrix< double, 6, 6 > J22
Eigen::Matrix< double, 6, 3 > Tpc
int remExcessTracks(int minpts)
removes tracks that aren't needed 
int nFixed
Number of fixed nodes. 
bool isValid
valid or not (could be out of bounds) 
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > tps
variables for each track 
bool addStereoProj(int ci, int pi, Eigen::Vector3d &q)
Add a projection between point and camera, in setting up the system. 
bool addProj(int ci, int pi, Eigen::Vector3d &q, bool stereo=true)
Add a projection between point and camera, in setting up the system. 
int sv
Scale variable index. 
std::vector< Node, Eigen::aligned_allocator< Node > > nodes
set of nodes (camera frames) for SPA system, indexed by position; 
Eigen::MatrixXd A
linear system matrix and vector 
double huber
Huber parameter; greater than 0.0 for Huber weighting of cost. 
int addPoint(Point p)
Adds a point to the system. 
double sqMinDelta
Convergence bound (square of minimum acceptable delta change) 
void printStats()
Print some system stats. 
Eigen::Matrix< double, 4, 1 > oldtrans
Eigen::Vector4d Point
Point holds 3D points using in world coordinates. Currently we just represent these as 4-vectors...
Eigen::Matrix< double, 6, 1 > err
error 
Eigen::Matrix< double, 12, 12 > prec
int countProjs()
Return total number of projections. 
void setupSys(double sLambda)
void tsplit(int tri, int len)
Split a track into random tracks. (What is len?) 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int nd0
Reference pose index. 
void mergeTracks(std::vector< std::pair< int, int > > &prs)
merge tracks based on identity pairs 
Eigen::Matrix< double, 3, 6 > Hpc
temp storage for Hpc, Tpc matrices in SBA 
Eigen::Quaternion< double > qpmean
std::vector< ConP2, Eigen::aligned_allocator< ConP2 > > p2cons
Set of P2 constraints. 
bool useLocalAngles
local or global angle coordinates 
void addPointPlaneMatch(int ci0, int pi0, Eigen::Vector3d normal0, int ci1, int pi1, Eigen::Vector3d normal1)
Adds a pair of point-plane projection matches. Assumes the points have already been added to the syst...
int reduceTracks()
Reduce tracks by eliminating single tracks and invalid projections. 
double ks
Scale factor for this constraint. 
void setProjCovariance(int ci, int pi, Eigen::Matrix3d &covar)
Sets the covariance matrix of a projection. 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int ndr
Reference pose index. 
std::vector< ConScale, Eigen::aligned_allocator< ConScale > > scons
Set of scale constraints. 
void setConnMatReduced(int maxconns)
sets up connectivity matrix by greedy spanning tree