gtsam 4.1.1
gtsam
gtsam::GaussNewtonOptimizer Class Reference

Detailed Description

This class performs Gauss-Newton nonlinear optimization.

+ Inheritance diagram for gtsam::GaussNewtonOptimizer:

Public Member Functions

Standard interface
 GaussNewtonOptimizer (const NonlinearFactorGraph &graph, const Values &initialValues, const GaussNewtonParams &params=GaussNewtonParams())
 Standard constructor, requires a nonlinear factor graph, initial variable assignments, and optimization parameters. More...
 
 GaussNewtonOptimizer (const NonlinearFactorGraph &graph, const Values &initialValues, const Ordering &ordering)
 Standard constructor, requires a nonlinear factor graph, initial variable assignments, and optimization parameters. More...
 
Advanced interface
 ~GaussNewtonOptimizer () override
 Virtual destructor.
 
GaussianFactorGraph::shared_ptr iterate () override
 Perform a single iteration, returning GaussianFactorGraph corresponding to the linearized factor graph. More...
 
const GaussNewtonParamsparams () const
 Read-only access the parameters.
 
- 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 in current optimizer state
 
size_t iterations () const
 return number of iterations in current optimizer state
 
const Valuesvalues () const
 return values in current optimizer state
 
const NonlinearFactorGraphgraph () const
 return the graph with nonlinear factors
 
virtual ~NonlinearOptimizer ()
 Virtual destructor.
 
virtual VectorValues solve (const GaussianFactorGraph &gfg, const NonlinearOptimizerParams &params) const
 Default function to do linear solve, i.e. More...
 

Protected Member Functions

const NonlinearOptimizerParams_params () const override
 Access the parameters (base class version) More...
 
GaussNewtonParams ensureHasOrdering (GaussNewtonParams params, const NonlinearFactorGraph &graph) const
 Internal function for computing a COLAMD ordering if no ordering is specified.
 
- 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

GaussNewtonParams params_
 
- Protected Attributes inherited from gtsam::NonlinearOptimizer
NonlinearFactorGraph graph_
 The graph with nonlinear factors.
 
std::unique_ptr< internal::NonlinearOptimizerState > state_
 PIMPL'd state.
 

Additional Inherited Members

- Public Types inherited from gtsam::NonlinearOptimizer
using shared_ptr = boost::shared_ptr< const NonlinearOptimizer >
 A shared pointer to this class.
 

Constructor & Destructor Documentation

◆ GaussNewtonOptimizer() [1/2]

gtsam::GaussNewtonOptimizer::GaussNewtonOptimizer ( const NonlinearFactorGraph graph,
const Values initialValues,
const GaussNewtonParams params = GaussNewtonParams() 
)

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

◆ GaussNewtonOptimizer() [2/2]

gtsam::GaussNewtonOptimizer::GaussNewtonOptimizer ( const NonlinearFactorGraph graph,
const Values initialValues,
const Ordering ordering 
)

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

Member Function Documentation

◆ _params()

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

Access the parameters (base class version)

Implements gtsam::NonlinearOptimizer.

◆ iterate()

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

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

Implements gtsam::NonlinearOptimizer.


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