g2o
Loading...
Searching...
No Matches
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]
Collaboration diagram for g2o::OptimizationAlgorithm:
Collaboration graph
[legend]

Public Member Functions

 OptimizationAlgorithm ()
 
virtual ~OptimizationAlgorithm ()
 
virtual bool init (bool online=false)=0
 
virtual SolverResult solve (int iteration, bool online=false)=0
 
virtual bool computeMarginals (SparseBlockMatrix< MatrixX > &spinv, const std::vector< std::pair< int, int > > &blockIndices)=0
 
virtual bool updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)=0
 
virtual void printVerbose (std::ostream &os) const
 
const SparseOptimizeroptimizer () const
 return the optimizer operating on
 
SparseOptimizeroptimizer ()
 
void setOptimizer (SparseOptimizer *optimizer)
 
const PropertyMapproperties () const
 return the properties of the solver
 
bool updatePropertiesFromString (const std::string &propString)
 
void printProperties (std::ostream &os) const
 

Protected Attributes

SparseOptimizer_optimizer
 the optimizer the solver is working on
 
PropertyMap _properties
 

Private Member Functions

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

Detailed Description

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

Definition at line 46 of file optimization_algorithm.h.

Constructor & Destructor Documentation

◆ OptimizationAlgorithm() [1/2]

g2o::OptimizationAlgorithm::OptimizationAlgorithm ( )

Definition at line 33 of file optimization_algorithm.cpp.

33: _optimizer(nullptr) {}
SparseOptimizer * _optimizer
the optimizer the solver is working on

◆ ~OptimizationAlgorithm()

g2o::OptimizationAlgorithm::~OptimizationAlgorithm ( )
virtual

Definition at line 35 of file optimization_algorithm.cpp.

35{}

◆ OptimizationAlgorithm() [2/2]

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

Definition at line 115 of file optimization_algorithm.h.

115{}

Member Function Documentation

◆ computeMarginals()

virtual bool g2o::OptimizationAlgorithm::computeMarginals ( SparseBlockMatrix< MatrixX > &  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::StructureOnlySolver< PointDoF >, and g2o::OptimizationAlgorithmWithHessian.

Referenced by g2o::SparseOptimizer::computeMarginals().

◆ init()

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

◆ operator=()

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

Definition at line 116 of file optimization_algorithm.h.

116 {
117 return *this;
118 }

◆ optimizer() [1/2]

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

Definition at line 88 of file optimization_algorithm.h.

88{ return _optimizer; }

◆ optimizer() [2/2]

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

return the optimizer operating on

Definition at line 87 of file optimization_algorithm.h.

87{ return _optimizer; }

Referenced by g2o::StructureOnlySolver< PointDoF >::init(), and setOptimizer().

◆ printProperties()

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

print the properties to a stream in a human readable fashion

Definition at line 37 of file optimization_algorithm.cpp.

37 {
38 os << "------------- Algorithm Properties -------------" << endl;
39 for (PropertyMap::const_iterator it = _properties.begin();
40 it != _properties.end(); ++it) {
41 BaseProperty* p = it->second;
42 os << it->first << "\t" << p->toString() << endl;
43 }
44 os << "------------------------------------------------" << endl;
45}

References _properties, and g2o::BaseProperty::toString().

Referenced by main().

◆ printVerbose()

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 83 of file optimization_algorithm.h.

83{ (void)os; };

Referenced by g2o::SparseOptimizer::optimize().

◆ properties()

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

return the properties of the solver

Definition at line 96 of file optimization_algorithm.h.

96{ return _properties; }

Referenced by MainWindow::on_btnOptimizerParameters_clicked().

◆ setOptimizer()

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

specify on which optimizer the solver should work on

Definition at line 52 of file optimization_algorithm.cpp.

52 {
54}
const SparseOptimizer * optimizer() const
return the optimizer operating on

References _optimizer, and optimizer().

Referenced by g2o::SparseOptimizer::setAlgorithm().

◆ solve()

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, g2o::OptimizationAlgorithmLevenberg, g2o::SolverSLAM2DLinear, and g2o::StructureOnlySolver< PointDoF >.

Referenced by g2o::SparseOptimizer::optimize().

◆ updatePropertiesFromString()

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

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

Definition at line 47 of file optimization_algorithm.cpp.

48 {
49 return _properties.updateMapFromString(propString);
50}
bool updateMapFromString(const std::string &values)
Definition property.cpp:83

References _properties, and g2o::PropertyMap::updateMapFromString().

Referenced by main().

◆ updateStructure()

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

Member Data Documentation

◆ _optimizer

SparseOptimizer* g2o::OptimizationAlgorithm::_optimizer
protected

◆ _properties

PropertyMap g2o::OptimizationAlgorithm::_properties
protected

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