gtsam 4.1.1
gtsam
|
An implementation of the nonlinear CG method using the template below.
Public Member Functions | |
NonlinearConjugateGradientOptimizer (const NonlinearFactorGraph &graph, const Values &initialValues, const Parameters ¶ms=Parameters()) | |
Constructor. | |
~NonlinearConjugateGradientOptimizer () override | |
Destructor. | |
GaussianFactorGraph::shared_ptr | iterate () override |
Perform a single iteration, returning GaussianFactorGraph corresponding to the linearized factor graph. More... | |
const Values & | optimize () override |
Optimize for the maximum-likelihood estimate, returning a the optimized variable assignments. More... | |
Public Member Functions inherited from gtsam::NonlinearOptimizer | |
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 NonlinearOptimizer | Base |
typedef NonlinearOptimizerParams | Parameters |
typedef boost::shared_ptr< NonlinearConjugateGradientOptimizer > | 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 | |
const NonlinearOptimizerParams & | _params () const override |
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 | |
Parameters | params_ |
Protected Attributes inherited from gtsam::NonlinearOptimizer | |
NonlinearFactorGraph | graph_ |
The graph with nonlinear factors. | |
std::unique_ptr< internal::NonlinearOptimizerState > | state_ |
PIMPL'd state. | |
|
inlineoverrideprotectedvirtual |
Implements gtsam::NonlinearOptimizer.
|
overridevirtual |
Perform a single iteration, returning GaussianFactorGraph corresponding to the linearized factor graph.
Implements gtsam::NonlinearOptimizer.
|
overridevirtual |
Optimize for the maximum-likelihood estimate, returning a the optimized variable assignments.
Reimplemented from gtsam::NonlinearOptimizer.