Public Member Functions |
void | addConstraint (int pr, int p0, int p1, Eigen::Matrix< double, 12, 1 > &mean, Eigen::Matrix< double, 12, 12 > &prec) |
bool | addConstraint (int nd0, int nd1, Eigen::Vector3d &tmean, Eigen::Quaterniond &qpmean, Eigen::Matrix< double, 6, 6 > &prec) |
| Adds a pose constraint to the system.
|
int | addNode (Eigen::Matrix< double, 4, 1 > &trans, Eigen::Quaternion< double > &qrot, bool isFixed=false) |
| Adds a node to the system.
|
double | calcCost (double dist) |
| calculate error assuming outliers > dist
|
double | calcCost (bool tcost=false) |
int | doSPA (int niter, double sLambda=1.0e-4, int useCSparse=SBA_SPARSE_CHOLESKY, double initTol=1.0e-8, int CGiters=50) |
void | printStats () |
| print some system stats
|
void | setupSparseSys (double sLambda, int iter, int sparseType) |
void | setupSys (double sLambda) |
void | spanningTree (int node=0) |
| Spanning tree initialization.
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | SysSPA () |
| constructor
|
void | writeSparseA (char *fname, bool useCSparse=false) |
Public Attributes |
Eigen::MatrixXd | A |
| linear system matrix and vector
|
Eigen::VectorXd | B |
CSparse | csp |
| sparse matrix object
|
double | lambda |
int | nFixed |
| Number of fixed nodes.
|
std::vector< Node,
Eigen::aligned_allocator< Node > > | nodes |
| set of nodes (camera frames) for SPA system, indexed by position;
|
Eigen::Matrix< double, 4, 1 > | oldqrot |
Eigen::Matrix< double, 4, 1 > | oldtrans |
std::vector< ConP2,
Eigen::aligned_allocator
< ConP2 > > | p2cons |
| Set of P2 constraints.
|
std::vector< double > | scales |
| set of scale for SPA system, indexed by position;
|
std::vector< ConScale,
Eigen::aligned_allocator
< ConScale > > | scons |
| Set of scale constraints.
|
double | sqMinDelta |
| Convergence bound (square of minimum acceptable delta change).
|
bool | useLocalAngles |
| local or global angle coordinates
|
bool | verbose |
| print info
|
int sba::SysSPA::doSPA |
( |
int |
niter, |
|
|
double |
sLambda = 1.0e-4 , |
|
|
int |
useCSparse = SBA_SPARSE_CHOLESKY , |
|
|
double |
initTol = 1.0e-8 , |
|
|
int |
maxCGiters = 50 | |
|
) |
| | |
do LM solution for system; returns number of iterations on finish. Argument is max number of iterations to perform, initial diagonal augmentation, and sparse form of Cholesky.
Run the LM algorithm that computes a nonlinear SPA estimate. <niter> is the max number of iterations to perform; returns the number actually performed. <lambda> is the diagonal augmentation for LM. <useCSparse> is true for sparse Cholesky. 2 for gradient system, 3 for block jacobian PCG <initTol> is the initial tolerance for CG <maxCGiters> is max # of iterations in BPCG
Definition at line 950 of file spa.cpp.