Public Member Functions | Protected Attributes | List of all members
g2o::OptimizationAlgorithmWithHessian Class Reference

Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg. More...

#include <optimization_algorithm_with_hessian.h>

Inheritance diagram for g2o::OptimizationAlgorithmWithHessian:
Inheritance graph
[legend]

Public Member Functions

virtual bool buildLinearStructure ()
 
virtual bool computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices)
 
virtual bool init (bool online=false)
 
 OptimizationAlgorithmWithHessian (Solver *solver)
 
virtual void setWriteDebug (bool writeDebug)
 
Solversolver ()
 return the underlying solver used to solve the linear system More...
 
virtual void updateLinearSystem ()
 
virtual bool updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)
 
virtual bool writeDebug () const
 
virtual ~OptimizationAlgorithmWithHessian ()
 
- Public Member Functions inherited from g2o::OptimizationAlgorithm
 OptimizationAlgorithm ()
 
const SparseOptimizeroptimizer () const
 return the optimizer operating on More...
 
SparseOptimizeroptimizer ()
 
void printProperties (std::ostream &os) const
 
virtual void printVerbose (std::ostream &os) const
 
const PropertyMapproperties () const
 return the properties of the solver More...
 
void setOptimizer (SparseOptimizer *optimizer)
 
virtual SolverResult solve (int iteration, bool online=false)=0
 
bool updatePropertiesFromString (const std::string &propString)
 
virtual ~OptimizationAlgorithm ()
 

Protected Attributes

Solver_solver
 
Property< bool > * _writeDebug
 
- Protected Attributes inherited from g2o::OptimizationAlgorithm
SparseOptimizer_optimizer
 the optimizer the solver is working on More...
 
PropertyMap _properties
 the properties of your solver, use this to store the parameters of your solver More...
 

Additional Inherited Members

- Public Types inherited from g2o::OptimizationAlgorithm
enum  SolverResult { Terminate =2, OK =1, Fail =-1 }
 

Detailed Description

Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg.

Definition at line 39 of file optimization_algorithm_with_hessian.h.

Constructor & Destructor Documentation

g2o::OptimizationAlgorithmWithHessian::OptimizationAlgorithmWithHessian ( Solver solver)
explicit

Definition at line 38 of file optimization_algorithm_with_hessian.cpp.

g2o::OptimizationAlgorithmWithHessian::~OptimizationAlgorithmWithHessian ( )
virtual

Definition at line 45 of file optimization_algorithm_with_hessian.cpp.

Member Function Documentation

bool g2o::OptimizationAlgorithmWithHessian::buildLinearStructure ( )
virtual

Definition at line 80 of file optimization_algorithm_with_hessian.cpp.

bool g2o::OptimizationAlgorithmWithHessian::computeMarginals ( SparseBlockMatrix< MatrixXd > &  spinv,
const std::vector< std::pair< int, int > > &  blockIndices 
)
virtual

computes the block diagonal elements of the pattern specified in the input and stores them in given SparseBlockMatrix. If your solver does not support computing the marginals, return false.

Implements g2o::OptimizationAlgorithm.

Definition at line 75 of file optimization_algorithm_with_hessian.cpp.

bool g2o::OptimizationAlgorithmWithHessian::init ( bool  online = false)
virtual

initialize the solver, called once before the first call to solve()

Implements g2o::OptimizationAlgorithm.

Definition at line 50 of file optimization_algorithm_with_hessian.cpp.

void g2o::OptimizationAlgorithmWithHessian::setWriteDebug ( bool  writeDebug)
virtual

write debug output of the Hessian if system is not positive definite

Definition at line 96 of file optimization_algorithm_with_hessian.cpp.

Solver* g2o::OptimizationAlgorithmWithHessian::solver ( )
inline

return the underlying solver used to solve the linear system

Definition at line 56 of file optimization_algorithm_with_hessian.h.

void g2o::OptimizationAlgorithmWithHessian::updateLinearSystem ( )
virtual

Definition at line 85 of file optimization_algorithm_with_hessian.cpp.

bool g2o::OptimizationAlgorithmWithHessian::updateStructure ( const std::vector< HyperGraph::Vertex * > &  vset,
const HyperGraph::EdgeSet edges 
)
virtual

update the structures for online processing

Implements g2o::OptimizationAlgorithm.

Definition at line 91 of file optimization_algorithm_with_hessian.cpp.

virtual bool g2o::OptimizationAlgorithmWithHessian::writeDebug ( ) const
inlinevirtual

Definition at line 62 of file optimization_algorithm_with_hessian.h.

Member Data Documentation

Solver* g2o::OptimizationAlgorithmWithHessian::_solver
protected

Definition at line 65 of file optimization_algorithm_with_hessian.h.

Property<bool>* g2o::OptimizationAlgorithmWithHessian::_writeDebug
protected

Definition at line 66 of file optimization_algorithm_with_hessian.h.


The documentation for this class was generated from the following files:


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:06