Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
g2o::OptimizationAlgorithmDogleg Class Reference

Implementation of Powell's Dogleg Algorithm. More...

#include <optimization_algorithm_dogleg.h>

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

Public Types

enum  { STEP_UNDEFINED, STEP_SD, STEP_GN, STEP_DL }
 type of the step to take More...
 
- Public Types inherited from g2o::OptimizationAlgorithm
enum  SolverResult { Terminate =2, OK =1, Fail =-1 }
 

Public Member Functions

int lastStep () const
 return the type of the last step taken by the algorithm More...
 
 OptimizationAlgorithmDogleg (BlockSolverBase *solver)
 
virtual void printVerbose (std::ostream &os) const
 
virtual SolverResult solve (int iteration, bool online=false)
 
double trustRegion () const
 return the diameter of the trust region More...
 
virtual ~OptimizationAlgorithmDogleg ()
 
- 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 ()
 

Static Public Member Functions

static const char * stepType2Str (int stepType)
 convert the type into an integer More...
 

Protected Attributes

Eigen::VectorXd _auxVector
 auxilary vector used to perform multiplications or other stuff More...
 
double _currentLambda
 the damping factor to force positive definite matrix More...
 
double _delta
 trust region More...
 
Eigen::VectorXd _hdl
 final dogleg step More...
 
Eigen::VectorXd _hsd
 steepest decent step More...
 
Property< double > * _initialLambda
 
Property< double > * _lamdbaFactor
 
int _lastNumTries
 
int _lastStep
 type of the step taken by the algorithm More...
 
Property< int > * _maxTrialsAfterFailure
 
Property< double > * _userDeltaInit
 
bool _wasPDInAllIterations
 the matrix we solve was positive definite in all iterations -> if not apply damping More...
 
- 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 Powell's Dogleg Algorithm.

Definition at line 39 of file optimization_algorithm_dogleg.h.

Member Enumeration Documentation

anonymous enum

type of the step to take

Enumerator
STEP_UNDEFINED 
STEP_SD 
STEP_GN 
STEP_DL 

Definition at line 43 of file optimization_algorithm_dogleg.h.

Constructor & Destructor Documentation

g2o::OptimizationAlgorithmDogleg::OptimizationAlgorithmDogleg ( BlockSolverBase solver)
explicit

construct the Dogleg algorithm, which will use the given Solver for solving the linearized system.

Definition at line 41 of file optimization_algorithm_dogleg.cpp.

g2o::OptimizationAlgorithmDogleg::~OptimizationAlgorithmDogleg ( )
virtual

Definition at line 53 of file optimization_algorithm_dogleg.cpp.

Member Function Documentation

int g2o::OptimizationAlgorithmDogleg::lastStep ( ) const
inline

return the type of the last step taken by the algorithm

Definition at line 61 of file optimization_algorithm_dogleg.h.

void g2o::OptimizationAlgorithmDogleg::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 209 of file optimization_algorithm_dogleg.cpp.

OptimizationAlgorithm::SolverResult g2o::OptimizationAlgorithmDogleg::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 57 of file optimization_algorithm_dogleg.cpp.

const char * g2o::OptimizationAlgorithmDogleg::stepType2Str ( int  stepType)
static

convert the type into an integer

Definition at line 219 of file optimization_algorithm_dogleg.cpp.

double g2o::OptimizationAlgorithmDogleg::trustRegion ( ) const
inline

return the diameter of the trust region

Definition at line 63 of file optimization_algorithm_dogleg.h.

Member Data Documentation

Eigen::VectorXd g2o::OptimizationAlgorithmDogleg::_auxVector
protected

auxilary vector used to perform multiplications or other stuff

Definition at line 78 of file optimization_algorithm_dogleg.h.

double g2o::OptimizationAlgorithmDogleg::_currentLambda
protected

the damping factor to force positive definite matrix

Definition at line 80 of file optimization_algorithm_dogleg.h.

double g2o::OptimizationAlgorithmDogleg::_delta
protected

trust region

Definition at line 81 of file optimization_algorithm_dogleg.h.

Eigen::VectorXd g2o::OptimizationAlgorithmDogleg::_hdl
protected

final dogleg step

Definition at line 77 of file optimization_algorithm_dogleg.h.

Eigen::VectorXd g2o::OptimizationAlgorithmDogleg::_hsd
protected

steepest decent step

Definition at line 76 of file optimization_algorithm_dogleg.h.

Property<double>* g2o::OptimizationAlgorithmDogleg::_initialLambda
protected

Definition at line 73 of file optimization_algorithm_dogleg.h.

Property<double>* g2o::OptimizationAlgorithmDogleg::_lamdbaFactor
protected

Definition at line 74 of file optimization_algorithm_dogleg.h.

int g2o::OptimizationAlgorithmDogleg::_lastNumTries
protected

Definition at line 84 of file optimization_algorithm_dogleg.h.

int g2o::OptimizationAlgorithmDogleg::_lastStep
protected

type of the step taken by the algorithm

Definition at line 82 of file optimization_algorithm_dogleg.h.

Property<int>* g2o::OptimizationAlgorithmDogleg::_maxTrialsAfterFailure
protected

Definition at line 70 of file optimization_algorithm_dogleg.h.

Property<double>* g2o::OptimizationAlgorithmDogleg::_userDeltaInit
protected

Definition at line 71 of file optimization_algorithm_dogleg.h.

bool g2o::OptimizationAlgorithmDogleg::_wasPDInAllIterations
protected

the matrix we solve was positive definite in all iterations -> if not apply damping

Definition at line 83 of file optimization_algorithm_dogleg.h.


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


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47