27 #ifndef G2O_BLOCK_SOLVER_H 28 #define G2O_BLOCK_SOLVER_H 35 #include "../../config.h" 38 using namespace Eigen;
43 template <
int _PoseDim,
int _LandmarkDim>
46 static const int PoseDim = _PoseDim;
47 static const int LandmarkDim = _LandmarkDim;
66 static const int PoseDim = Eigen::Dynamic;
67 static const int LandmarkDim = Eigen::Dynamic;
90 virtual void multiplyHessian(
double* dest,
const double* src)
const = 0;
96 template <
typename Traits>
100 static const int PoseDim = Traits::PoseDim;
101 static const int LandmarkDim = Traits::LandmarkDim;
124 virtual bool buildStructure(
bool zeroBlocks =
false);
125 virtual bool updateStructure(
const std::vector<HyperGraph::Vertex*>& vset,
const HyperGraph::EdgeSet& edges);
126 virtual bool buildSystem();
127 virtual bool solve();
129 virtual bool setLambda(
double lambda,
bool backup =
false);
130 virtual void restoreDiagonal();
132 virtual bool schur() {
return _doSchur;}
137 virtual void setWriteDebug(
bool writeDebug);
138 virtual bool writeDebug()
const {
return _linearSolver->writeDebug();}
140 virtual bool saveHessian(
const std::string& fileName)
const;
142 virtual void multiplyHessian(
double* dest,
const double* src)
const { _Hpp->multiplySymmetricUpperTriangle(dest, src);}
145 void resize(
int* blockPoseIndices,
int numPoseBlocks,
146 int* blockLandmarkIndices,
int numLandmarkBlocks,
int totalDim);
166 std::vector<OpenMPMutex> _coefficientsMutex;
VectorXd LandmarkVectorType
SparseBlockMatrix< PoseMatrixType > * _Hschur
Traits::PoseHessianType PoseHessianType
std::vector< LandmarkVectorType, Eigen::aligned_allocator< LandmarkVectorType > > _diagonalBackupLandmark
Traits::LandmarkMatrixType LandmarkMatrixType
BlockSolver< BlockSolverTraits< 6, 3 > > BlockSolver_6_3
Traits::PoseVectorType PoseVectorType
SparseBlockMatrix< PoseMatrixType > * _Hpp
virtual bool schur()
should the solver perform the schur complement or not
Traits::LandmarkHessianType LandmarkHessianType
virtual void setSchur(bool s)
SparseBlockMatrixDiagonal< LandmarkMatrixType > * _DInvSchur
MatrixXd PoseLandmarkMatrixType
SparseBlockMatrixCCS< PoseLandmarkMatrixType > * _HplCCS
traits to summarize the properties of the fixed size optimization problem
Matrix< double, PoseDim, LandmarkDim > PoseLandmarkMatrixType
SparseBlockMatrix< LandmarkMatrixType > * _Hll
Matrix< double, LandmarkDim, LandmarkDim > LandmarkMatrixType
SparseBlockMatrix< PoseLandmarkMatrixType > PoseLandmarkHessianType
Traits::PoseMatrixType PoseMatrixType
Traits::LinearSolverType LinearSolverType
SparseBlockMatrix< PoseMatrixType > PoseHessianType
std::set< Edge * > EdgeSet
BlockSolver< BlockSolverTraits< 3, 2 > > BlockSolver_3_2
SparseBlockMatrixCCS< PoseMatrixType > * _HschurTransposedCCS
Traits::PoseLandmarkHessianType PoseLandmarkHessianType
LinearSolver< PoseMatrixType > * linearSolver() const
MatrixXd LandmarkMatrixType
std::vector< PoseVectorType, Eigen::aligned_allocator< PoseVectorType > > _diagonalBackupPose
Traits::PoseLandmarkMatrixType PoseLandmarkMatrixType
Generic interface for a sparse solver operating on a graph which solves one iteration of the lineariz...
Traits::LandmarkVectorType LandmarkVectorType
LinearSolver< PoseMatrixType > LinearSolverType
SparseBlockMatrix< PoseLandmarkMatrixType > PoseLandmarkHessianType
virtual bool supportsSchur()
SparseBlockMatrix< PoseLandmarkMatrixType > * _Hpl
Matrix< double, LandmarkDim, 1 > LandmarkVectorType
SparseBlockMatrix< PoseMatrixType > PoseHessianType
virtual void multiplyHessian(double *dest, const double *src) const
SparseBlockMatrix< LandmarkMatrixType > LandmarkHessianType
BlockSolver< BlockSolverTraits< 7, 3 > > BlockSolver_7_3
LinearSolver< PoseMatrixType > * _linearSolver
Implementation of a solver operating on the blocks of the Hessian.
LinearSolver< PoseMatrixType > LinearSolverType
SparseBlockMatrix< LandmarkMatrixType > LandmarkHessianType
virtual ~BlockSolverBase()
virtual bool writeDebug() const
base for the block solvers with some basic function interfaces
BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > BlockSolverX
Matrix< double, PoseDim, 1 > PoseVectorType
Matrix< double, PoseDim, PoseDim > PoseMatrixType