Public Member Functions | List of all members
g2o::OptimizationAlgorithmGaussNewton Class Reference

Implementation of the Gauss Newton Algorithm. More...

#include <optimization_algorithm_gauss_newton.h>

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

Public Member Functions

 OptimizationAlgorithmGaussNewton (Solver *solver)
 
virtual void printVerbose (std::ostream &os) const
 
virtual SolverResult solve (int iteration, bool online=false)
 
virtual ~OptimizationAlgorithmGaussNewton ()
 
- Public Member Functions inherited from g2o::OptimizationAlgorithmWithHessian
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
 
const PropertyMapproperties () const
 return the properties of the solver More...
 
void setOptimizer (SparseOptimizer *optimizer)
 
bool updatePropertiesFromString (const std::string &propString)
 
virtual ~OptimizationAlgorithm ()
 

Additional Inherited Members

- Public Types inherited from g2o::OptimizationAlgorithm
enum  SolverResult { Terminate =2, OK =1, Fail =-1 }
 
- Protected Attributes inherited from g2o::OptimizationAlgorithmWithHessian
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...
 

Detailed Description

Implementation of the Gauss Newton Algorithm.

Definition at line 37 of file optimization_algorithm_gauss_newton.h.

Constructor & Destructor Documentation

g2o::OptimizationAlgorithmGaussNewton::OptimizationAlgorithmGaussNewton ( Solver solver)
explicit

construct the Gauss Newton algorithm, which use the given Solver for solving the linearized system.

Definition at line 41 of file optimization_algorithm_gauss_newton.cpp.

g2o::OptimizationAlgorithmGaussNewton::~OptimizationAlgorithmGaussNewton ( )
virtual

Definition at line 46 of file optimization_algorithm_gauss_newton.cpp.

Member Function Documentation

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

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

Reimplemented from g2o::OptimizationAlgorithm.

Definition at line 95 of file optimization_algorithm_gauss_newton.cpp.

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

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

Parameters
iterationindicates the current iteration

Implements g2o::OptimizationAlgorithm.

Definition at line 50 of file optimization_algorithm_gauss_newton.cpp.


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