Public Types | Public Member Functions | Protected Attributes | Private Member Functions | List of all members
g2o::OptimizationAlgorithm Class Referenceabstract

Generic interface for a non-linear solver operating on a graph. More...

#include <optimization_algorithm.h>

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

Public Types

enum  SolverResult { Terminate =2, OK =1, Fail =-1 }
 

Public Member Functions

virtual bool computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices)=0
 
virtual bool init (bool online=false)=0
 
 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 bool updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)=0
 
virtual ~OptimizationAlgorithm ()
 

Protected Attributes

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...
 

Private Member Functions

OptimizationAlgorithmoperator= (const OptimizationAlgorithm &)
 
 OptimizationAlgorithm (const OptimizationAlgorithm &)
 

Detailed Description

Generic interface for a non-linear solver operating on a graph.

Definition at line 46 of file optimization_algorithm.h.

Member Enumeration Documentation

Enumerator
Terminate 
OK 
Fail 

Definition at line 49 of file optimization_algorithm.h.

Constructor & Destructor Documentation

g2o::OptimizationAlgorithm::OptimizationAlgorithm ( )

Definition at line 33 of file optimization_algorithm.cpp.

g2o::OptimizationAlgorithm::~OptimizationAlgorithm ( )
virtual

Definition at line 38 of file optimization_algorithm.cpp.

g2o::OptimizationAlgorithm::OptimizationAlgorithm ( const OptimizationAlgorithm )
inlineprivate

Definition at line 111 of file optimization_algorithm.h.

Member Function Documentation

virtual bool g2o::OptimizationAlgorithm::computeMarginals ( SparseBlockMatrix< MatrixXd > &  spinv,
const std::vector< std::pair< int, int > > &  blockIndices 
)
pure 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.

Implemented in g2o::OptimizationAlgorithmWithHessian.

virtual bool g2o::OptimizationAlgorithm::init ( bool  online = false)
pure virtual

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

Implemented in g2o::OptimizationAlgorithmWithHessian.

OptimizationAlgorithm& g2o::OptimizationAlgorithm::operator= ( const OptimizationAlgorithm )
inlineprivate

Definition at line 112 of file optimization_algorithm.h.

const SparseOptimizer* g2o::OptimizationAlgorithm::optimizer ( ) const
inline

return the optimizer operating on

Definition at line 84 of file optimization_algorithm.h.

SparseOptimizer* g2o::OptimizationAlgorithm::optimizer ( )
inline

Definition at line 85 of file optimization_algorithm.h.

void g2o::OptimizationAlgorithm::printProperties ( std::ostream &  os) const

print the properties to a stream in a human readable fashion

Definition at line 42 of file optimization_algorithm.cpp.

virtual void g2o::OptimizationAlgorithm::printVerbose ( std::ostream &  os) const
inlinevirtual

called by the optimizer if verbose. re-implement, if you want to print something

Reimplemented in g2o::OptimizationAlgorithmDogleg, g2o::OptimizationAlgorithmGaussNewton, and g2o::OptimizationAlgorithmLevenberg.

Definition at line 80 of file optimization_algorithm.h.

const PropertyMap& g2o::OptimizationAlgorithm::properties ( ) const
inline

return the properties of the solver

Definition at line 93 of file optimization_algorithm.h.

void g2o::OptimizationAlgorithm::setOptimizer ( SparseOptimizer optimizer)

specify on which optimizer the solver should work on

Definition at line 57 of file optimization_algorithm.cpp.

virtual SolverResult g2o::OptimizationAlgorithm::solve ( int  iteration,
bool  online = false 
)
pure virtual

Solve one iteration. The SparseOptimizer running on-top will call this for the given number of iterations.

Parameters
iterationindicates the current iteration

Implemented in g2o::OptimizationAlgorithmDogleg, g2o::OptimizationAlgorithmGaussNewton, and g2o::OptimizationAlgorithmLevenberg.

bool g2o::OptimizationAlgorithm::updatePropertiesFromString ( const std::string &  propString)

update the properties from a string, see PropertyMap::updateMapFromString()

Definition at line 52 of file optimization_algorithm.cpp.

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

update the structures for online processing

Implemented in g2o::OptimizationAlgorithmWithHessian.

Member Data Documentation

SparseOptimizer* g2o::OptimizationAlgorithm::_optimizer
protected

the optimizer the solver is working on

Definition at line 106 of file optimization_algorithm.h.

PropertyMap g2o::OptimizationAlgorithm::_properties
protected

the properties of your solver, use this to store the parameters of your solver

Definition at line 107 of file optimization_algorithm.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