SysSPA2d holds a set of nodes and constraints for sparse pose adjustment.
More...
#include <spa2d.h>
List of all members.
Public Member Functions |
bool | addConstraint (int nd0, int nd1, const Vector3d &mean, const Matrix3d &prec) |
int | addNode (const Vector3d &pos, int id) |
double | calcCost (bool tcost=false) |
double | calcCost (double dist) |
| calculate error assuming outliers > dist
|
int | doSPA (int niter, double sLambda=1.0e-4, int useCSparse=SBA_SPARSE_CHOLESKY, double initTol=1.0e-8, int CGiters=50) |
int | doSPAwindowed (int window, int niter, double sLambda, int useCSparse) |
void | getGraph (std::vector< float > &graph) |
std::vector< Node2d,
Eigen::aligned_allocator
< Node2d > > | getNodes () |
void | printStats () |
| print some system stats
|
bool | removeConstraint (int ndi0, int ndi1) |
void | removeNode (int id) |
void | setupSparseSys (double sLambda, int iter, int sparseType) |
void | setupSys (double sLambda) |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | SysSPA2d () |
| constructor
|
void | useCholmod (bool yes) |
| use CHOLMOD or CSparse
|
void | writeSparseA (char *fname, bool useCSparse=false) |
Public Attributes |
Eigen::MatrixXd | A |
| linear system matrix and vector
|
Eigen::VectorXd | B |
CSparse2d | csp |
| sparse matrix object
|
double | errcost |
double | lambda |
int | nFixed |
| Number of fixed nodes.
|
std::vector< Node2d,
Eigen::aligned_allocator
< Node2d > > | nodes |
| set of nodes (camera frames) for SPA system, indexed by position;
|
std::vector< Con2dP2,
Eigen::aligned_allocator
< Con2dP2 > > | p2cons |
| Set of P2 constraints.
|
bool | print_iros_stats |
std::vector< std::vector
< Eigen::Vector2d,
Eigen::aligned_allocator
< Eigen::Vector2d > > > | scans |
| set of point scans, corresponding to nodes
|
double | sqMinDelta |
| Convergence bound (square of minimum acceptable delta change)
|
bool | verbose |
| if we want statistics
|
Detailed Description
SysSPA2d holds a set of nodes and constraints for sparse pose adjustment.
Definition at line 192 of file spa2d.h.
Constructor & Destructor Documentation
constructor
Definition at line 198 of file spa2d.h.
Member Function Documentation
add a node at a pose <pos> is x,y,th, with th in radians
Definition at line 211 of file spa2d.cpp.
calculate the error in the system; if <tcost> is true, just the distance error without weighting
Definition at line 177 of file spa2d.cpp.
calculate error assuming outliers > dist
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> = 0 for dense Cholesky, 1 for sparse system, 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 429 of file spa2d.cpp.
return the graph of constraints x,y -> x',y' 4 floats per connection
Definition at line 976 of file spa2d.cpp.
set up linear system, from RSS submission (konolige 2010) <sLambda> is the diagonal augmentation for the LM step
Definition at line 262 of file spa2d.cpp.
Member Data Documentation
linear system matrix and vector
Definition at line 263 of file spa2d.h.
sparse matrix object
Definition at line 267 of file spa2d.h.
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. useCSParse = 0 for dense Cholesky, 1 for sparse Cholesky, 2 for BPCG
Definition at line 248 of file spa2d.h.
Number of fixed nodes.
Definition at line 222 of file spa2d.h.
set of nodes (camera frames) for SPA system, indexed by position;
Definition at line 214 of file spa2d.h.
Set of P2 constraints.
Definition at line 225 of file spa2d.h.
std::vector< std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > > sba::SysSPA2d::scans |
set of point scans, corresponding to nodes
Definition at line 219 of file spa2d.h.
Convergence bound (square of minimum acceptable delta change)
Definition at line 260 of file spa2d.h.
if we want statistics
Definition at line 274 of file spa2d.h.
The documentation for this class was generated from the following files: