Public Types | Protected Member Functions | Protected Attributes | List of all members
gtsam::LevenbergMarquardtOptimizer Class Reference

#include <LevenbergMarquardtOptimizer.h>

Inheritance diagram for gtsam::LevenbergMarquardtOptimizer:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< LevenbergMarquardtOptimizershared_ptr
 
- Public Types inherited from gtsam::NonlinearOptimizer
using shared_ptr = std::shared_ptr< const NonlinearOptimizer >
 

Public Member Functions

Constructors/Destructor
 LevenbergMarquardtOptimizer (const NonlinearFactorGraph &graph, const Values &initialValues, const LevenbergMarquardtParams &params=LevenbergMarquardtParams())
 
 LevenbergMarquardtOptimizer (const NonlinearFactorGraph &graph, const Values &initialValues, const Ordering &ordering, const LevenbergMarquardtParams &params=LevenbergMarquardtParams())
 
 ~LevenbergMarquardtOptimizer () override
 
Standard interface
double lambda () const
 Access the current damping value. More...
 
int getInnerIterations () const
 Access the current number of inner iterations. More...
 
void print (const std::string &str="") const
 print More...
 
Advanced interface
GaussianFactorGraph::shared_ptr iterate () override
 
const LevenbergMarquardtParamsparams () const
 
void writeLogFile (double currentError)
 
virtual GaussianFactorGraph::shared_ptr linearize () const
 
GaussianFactorGraph buildDampedSystem (const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal) const
 
bool tryLambda (const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal)
 
- Public Member Functions inherited from gtsam::NonlinearOptimizer
virtual const Valuesoptimize ()
 
const ValuesoptimizeSafely ()
 
double error () const
 return error in current optimizer state More...
 
size_t iterations () const
 return number of iterations in current optimizer state More...
 
const Valuesvalues () const
 return values in current optimizer state More...
 
const NonlinearFactorGraphgraph () const
 return the graph with nonlinear factors More...
 
virtual ~NonlinearOptimizer ()
 
virtual VectorValues solve (const GaussianFactorGraph &gfg, const NonlinearOptimizerParams &params) const
 

Protected Member Functions

const NonlinearOptimizerParams_params () const override
 
void initTime ()
 
- Protected Member Functions inherited from gtsam::NonlinearOptimizer
void defaultOptimize ()
 
 NonlinearOptimizer (const NonlinearFactorGraph &graph, std::unique_ptr< internal::NonlinearOptimizerState > state)
 

Protected Attributes

const LevenbergMarquardtParams params_
 LM parameters. More...
 
std::chrono::time_point< std::chrono::high_resolution_clock > startTime_
 time when optimization started More...
 
- Protected Attributes inherited from gtsam::NonlinearOptimizer
NonlinearFactorGraph graph_
 The graph with nonlinear factors. More...
 
std::unique_ptr< internal::NonlinearOptimizerStatestate_
 PIMPL'd state. More...
 

Detailed Description

This class performs Levenberg-Marquardt nonlinear optimization

Definition at line 35 of file LevenbergMarquardtOptimizer.h.

Member Typedef Documentation

◆ shared_ptr

Definition at line 46 of file LevenbergMarquardtOptimizer.h.

Constructor & Destructor Documentation

◆ LevenbergMarquardtOptimizer() [1/2]

gtsam::LevenbergMarquardtOptimizer::LevenbergMarquardtOptimizer ( const NonlinearFactorGraph graph,
const Values initialValues,
const LevenbergMarquardtParams params = LevenbergMarquardtParams() 
)

Standard constructor, requires a nonlinear factor graph, initial variable assignments, and optimization parameters. For convenience this version takes plain objects instead of shared pointers, but internally copies the objects.

Parameters
graphThe nonlinear factor graph to optimize
initialValuesThe initial variable assignments
paramsThe optimization parameters

Definition at line 47 of file LevenbergMarquardtOptimizer.cpp.

◆ LevenbergMarquardtOptimizer() [2/2]

gtsam::LevenbergMarquardtOptimizer::LevenbergMarquardtOptimizer ( const NonlinearFactorGraph graph,
const Values initialValues,
const Ordering ordering,
const LevenbergMarquardtParams params = LevenbergMarquardtParams() 
)

Standard constructor, requires a nonlinear factor graph, initial variable assignments, and optimization parameters. For convenience this version takes plain objects instead of shared pointers, but internally copies the objects.

Parameters
graphThe nonlinear factor graph to optimize
initialValuesThe initial variable assignments

Definition at line 55 of file LevenbergMarquardtOptimizer.cpp.

◆ ~LevenbergMarquardtOptimizer()

gtsam::LevenbergMarquardtOptimizer::~LevenbergMarquardtOptimizer ( )
inlineoverride

Virtual destructor

Definition at line 74 of file LevenbergMarquardtOptimizer.h.

Member Function Documentation

◆ _params()

const NonlinearOptimizerParams& gtsam::LevenbergMarquardtOptimizer::_params ( ) const
inlineoverrideprotectedvirtual

Access the parameters (base class version)

Implements gtsam::NonlinearOptimizer.

Definition at line 127 of file LevenbergMarquardtOptimizer.h.

◆ buildDampedSystem()

GaussianFactorGraph gtsam::LevenbergMarquardtOptimizer::buildDampedSystem ( const GaussianFactorGraph linear,
const VectorValues sqrtHessianDiagonal 
) const

Build a damped system for a specific lambda – for testing only

Definition at line 88 of file LevenbergMarquardtOptimizer.cpp.

◆ getInnerIterations()

int gtsam::LevenbergMarquardtOptimizer::getInnerIterations ( ) const

Access the current number of inner iterations.

Definition at line 77 of file LevenbergMarquardtOptimizer.cpp.

◆ initTime()

void gtsam::LevenbergMarquardtOptimizer::initTime ( )
protected

Definition at line 65 of file LevenbergMarquardtOptimizer.cpp.

◆ iterate()

GaussianFactorGraph::shared_ptr gtsam::LevenbergMarquardtOptimizer::iterate ( void  )
overridevirtual

Perform a single iteration, returning GaussianFactorGraph corresponding to the linearized factor graph.

Implements gtsam::NonlinearOptimizer.

Definition at line 273 of file LevenbergMarquardtOptimizer.cpp.

◆ lambda()

double gtsam::LevenbergMarquardtOptimizer::lambda ( ) const

Access the current damping value.

Definition at line 71 of file LevenbergMarquardtOptimizer.cpp.

◆ linearize()

GaussianFactorGraph::shared_ptr gtsam::LevenbergMarquardtOptimizer::linearize ( ) const
virtual

linearize, can be overwritten

Definition at line 83 of file LevenbergMarquardtOptimizer.cpp.

◆ params()

const LevenbergMarquardtParams& gtsam::LevenbergMarquardtOptimizer::params ( ) const
inline

Read-only access the parameters

Definition at line 106 of file LevenbergMarquardtOptimizer.h.

◆ print()

void gtsam::LevenbergMarquardtOptimizer::print ( const std::string &  str = "") const
inline

print

Definition at line 89 of file LevenbergMarquardtOptimizer.h.

◆ tryLambda()

bool gtsam::LevenbergMarquardtOptimizer::tryLambda ( const GaussianFactorGraph linear,
const VectorValues sqrtHessianDiagonal 
)

Inner loop, changes state, returns true if successful or giving up

Definition at line 121 of file LevenbergMarquardtOptimizer.cpp.

◆ writeLogFile()

void gtsam::LevenbergMarquardtOptimizer::writeLogFile ( double  currentError)
inline

Definition at line 104 of file LevenbergMarquardtOptimizer.cpp.

Member Data Documentation

◆ params_

const LevenbergMarquardtParams gtsam::LevenbergMarquardtOptimizer::params_
protected

LM parameters.

Definition at line 38 of file LevenbergMarquardtOptimizer.h.

◆ startTime_

std::chrono::time_point<std::chrono::high_resolution_clock> gtsam::LevenbergMarquardtOptimizer::startTime_
protected

time when optimization started

Definition at line 41 of file LevenbergMarquardtOptimizer.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:22