|
gtsam 4.1.1
gtsam
|
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 ¶ms=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 ¶ms=LevenbergMarquardtParams()) | |
| Standard constructor, requires a nonlinear factor graph, initial variable assignments, and optimization parameters. More... | |
| ~LevenbergMarquardtOptimizer () override | |
| 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. More... | |
| const LevenbergMarquardtParams & | params () 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 Values & | optimize () |
| Optimize for the maximum-likelihood estimate, returning a the optimized variable assignments. More... | |
| const Values & | optimizeSafely () |
| Optimize, but return empty result if any uncaught exception is thrown Intended for MATLAB. More... | |
| double | error () const |
| return error in current optimizer state | |
| size_t | iterations () const |
| return number of iterations in current optimizer state | |
| const Values & | values () const |
| return values in current optimizer state | |
| const NonlinearFactorGraph & | graph () const |
| return the graph with nonlinear factors | |
| virtual | ~NonlinearOptimizer () |
| Virtual destructor. | |
| virtual VectorValues | solve (const GaussianFactorGraph &gfg, const NonlinearOptimizerParams ¶ms) const |
| Default function to do linear solve, i.e. More... | |
Public Types | |
| typedef boost::shared_ptr< LevenbergMarquardtOptimizer > | shared_ptr |
Public Types inherited from gtsam::NonlinearOptimizer | |
| using | shared_ptr = boost::shared_ptr< const NonlinearOptimizer > |
| A shared pointer to this class. | |
Protected Member Functions | |
| void | initTime () |
| const NonlinearOptimizerParams & | _params () const override |
| Access the parameters (base class version) More... | |
Protected Member Functions inherited from gtsam::NonlinearOptimizer | |
| void | defaultOptimize () |
| A default implementation of the optimization loop, which calls iterate() until checkConvergence returns true. | |
| virtual const NonlinearOptimizerParams & | _params () const =0 |
| 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. | |
| 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.
| graph | The nonlinear factor graph to optimize |
| initialValues | The initial variable assignments |
| params | The optimization parameters |
| 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.
| graph | The nonlinear factor graph to optimize |
| initialValues | The initial variable assignments |
|
inlineoverrideprotectedvirtual |
Access the parameters (base class version)
Implements gtsam::NonlinearOptimizer.
|
overridevirtual |
Perform a single iteration, returning GaussianFactorGraph corresponding to the linearized factor graph.
Implements gtsam::NonlinearOptimizer.