Go to the documentation of this file.
42 #ifndef EIGEN_USE_NEW_STDVECTOR
43 #define EIGEN_USE_NEW_STDVECTOR
44 #endif // EIGEN_USE_NEW_STDVECTOR
50 #include <Eigen/Geometry>
52 #include <Eigen/StdVector>
62 #define SBA_DENSE_CHOLESKY 0
63 #define SBA_SPARSE_CHOLESKY 1
64 #define SBA_GRADIENT 2
65 #define SBA_BLOCK_JACOBIAN_PCG 3
92 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
98 Eigen::Matrix<double,3,1>
trans;
108 Eigen::Matrix<double,2,3>
w2n;
139 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
150 Eigen::Matrix<double,3,3>
prec;
153 Eigen::Matrix<double,3,1>
err;
186 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
205 std::vector<Node2d,Eigen::aligned_allocator<Node2d> >
nodes;
206 std::vector<Node2d,Eigen::aligned_allocator<Node2d> >
getNodes()
210 std::vector< std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > >
scans;
216 std::vector<Con2dP2,Eigen::aligned_allocator<Con2dP2> >
p2cons;
220 double calcCost(
bool tcost =
false);
228 void writeSparseA(
char *fname,
bool useCSparse =
false);
240 int doSPA(
int niter,
double sLambda = 1.0e-4,
int useCSparse =
SBA_SPARSE_CHOLESKY,
double initTol = 1.0e-8,
int CGiters = 50);
241 int doSPAwindowed(
int window,
int niter,
double sLambda,
int useCSparse);
245 void doDSIF(
int newnode);
247 void setupSparseDSIF(
int newnode);
270 void getGraph(std::vector<float> &graph);
CSparse2d csp
sparse matrix object
Eigen::Matrix< double, 2, 3 > w2n
Resultant transform from world to node coordinates;.
void getGraph(std::vector< float > &graph)
Eigen::Matrix< double, 3, 1 > err
error
double calcErrDist(const Node2d &nd0, const Node2d &nd1)
calculate error in distance only, no weighting
bool addConstraint(int nd0, int nd1, const Vector3d &mean, const Matrix3d &prec)
Eigen::Matrix< double, 3, 3 > J1t
double sqMinDelta
Convergence bound (square of minimum acceptable delta change)
void setJacobians(std::vector< Node2d, Eigen::aligned_allocator< Node2d > > &nodes)
Eigen::Matrix< double, 3, 3 > J0t
int nd1
Node2d index for the second node.
Eigen::Matrix< double, 3, 1 > trans
6DOF pose as a unit quaternion and translation vector
void normArot()
Normalize to [-pi,+pi].
double calcErr(const Node2d &nd0, const Node2d &nd1)
calculates projection error and stores it in <err>
std::vector< std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > > scans
set of point scans, corresponding to nodes
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SysSPA2d()
constructor
Eigen::Matrix< double, 3, 3 > prec
void setupSparseSys(double sLambda, int iter, int sparseType)
Eigen::Matrix< double, 3, 3 > J0
jacobian with respect to frames; uses dR'/dq from Node2d calculation
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int ndr
Reference pose index.
Vector3< kt_double > Vector3d
bool removeConstraint(int ndi0, int ndi1)
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.
Eigen::Vector2d tmean
Mean vector, quaternion (inverse) and precision matrix for this constraint.
#define SBA_SPARSE_CHOLESKY
bool isFixed
For SPA, is this camera fixed or free?
void useCholmod(bool yes)
use CHOLMOD or CSparse
bool read2dP2File(char *fname, SysSPA2d spa)
constraint files
void printStats()
print some system stats
int nFixed
Number of fixed nodes.
Eigen::MatrixXd A
linear system matrix and vector
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int nodeId
node id - somewhat redundant, but can be useful, e.g., in KARTO links
void writeSparseA(char *fname, bool useCSparse=false)
Vector2< kt_double > Vector2d
Eigen::Matrix< double, 3, 3 > J1
int doSPAwindowed(int window, int niter, double sLambda, int useCSparse)
double calcCost(bool tcost=false)
void setupSys(double sLambda)
bool verbose
if we want statistics
int doSPA(int niter, double sLambda=1.0e-4, int useCSparse=SBA_SPARSE_CHOLESKY, double initTol=1.0e-8, int CGiters=50)
std::vector< Node2d, Eigen::aligned_allocator< Node2d > > getNodes()
bool isValid
valid or not (could be out of bounds)
SysSPA2d holds a set of nodes and constraints for sparse pose adjustment.
Eigen::Matrix< double, 3, 1 > oldtrans
int addNode(const Vector3d &pos, int id)
nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:22