gtsam  4.0.0
gtsam
gtsam::LevenbergMarquardtOptimizer Class Reference

Detailed Description

This class performs Levenberg-Marquardt nonlinear optimization.

+ Inheritance diagram for gtsam::LevenbergMarquardtOptimizer:

Public Member Functions

Constructors/Destructor
 LevenbergMarquardtOptimizer (const NonlinearFactorGraph &graph, const Values &initialValues, const LevenbergMarquardtParams &params=LevenbergMarquardtParams())
 Standard constructor, requires a nonlinear factor graph, initial variable assignments, and optimization parameters. More...
 
 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. More...
 
virtual ~LevenbergMarquardtOptimizer ()
 Virtual destructor.
 
Standard interface
double lambda () const
 Access the current damping value.
 
int getInnerIterations () const
 Access the current number of inner iterations.
 
void print (const std::string &str="") const
 print
 
Advanced interface
GaussianFactorGraph::shared_ptr iterate () override
 Perform a single iteration, returning GaussianFactorGraph corresponding to the linearized factor graph.
 
const LevenbergMarquardtParamsparams () const
 Read-only access the parameters.
 
void writeLogFile (double currentError)
 
virtual GaussianFactorGraph::shared_ptr linearize () const
 linearize, can be overwritten
 
GaussianFactorGraph buildDampedSystem (const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal) const
 Build a damped system for a specific lambda – for testing only.
 
bool tryLambda (const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal)
 Inner loop, changes state, returns true if successful or giving up.
 
- Public Member Functions inherited from gtsam::NonlinearOptimizer
virtual const Valuesoptimize ()
 Optimize for the maximum-likelihood estimate, returning a the optimized variable assignments. More...
 
const ValuesoptimizeSafely ()
 Optimize, but return empty result if any uncaught exception is thrown Intended for MATLAB. More...
 
double error () const
 return error
 
size_t iterations () const
 return number of iterations
 
const Valuesvalues () const
 return values
 
virtual ~NonlinearOptimizer ()
 Virtual destructor.
 
virtual VectorValues solve (const GaussianFactorGraph &gfg, const NonlinearOptimizerParams &params) const
 Default function to do linear solve, i.e. More...
 

Public Types

typedef boost::shared_ptr< LevenbergMarquardtOptimizershared_ptr
 
- Public Types inherited from gtsam::NonlinearOptimizer
typedef boost::shared_ptr< const NonlinearOptimizershared_ptr
 A shared pointer to this class.
 

Protected Member Functions

void initTime ()
 
const NonlinearOptimizerParams_params () const override
 Access the parameters (base class version)
 
- Protected Member Functions inherited from gtsam::NonlinearOptimizer
void defaultOptimize ()
 A default implementation of the optimization loop, which calls iterate() until checkConvergence returns true.
 
 NonlinearOptimizer (const NonlinearFactorGraph &graph, std::unique_ptr< internal::NonlinearOptimizerState > state)
 Constructor for initial construction of base classes. More...
 

Protected Attributes

const LevenbergMarquardtParams params_
 LM parameters.
 
boost::posix_time::ptime startTime_
 
- Protected Attributes inherited from gtsam::NonlinearOptimizer
NonlinearFactorGraph graph_
 The graph with nonlinear factors.
 
std::unique_ptr< internal::NonlinearOptimizerState > state_
 PIMPL'd state.
 

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

◆ 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

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