#include <GaussNewtonOptimizer.h>
Public Types | |
using | OptimizerType = GaussNewtonOptimizer |
Public Types inherited from gtsam::NonlinearOptimizerParams | |
using | IterationHook = std::function< void(size_t, double, double)> |
enum | LinearSolverType { MULTIFRONTAL_CHOLESKY, MULTIFRONTAL_QR, SEQUENTIAL_CHOLESKY, SEQUENTIAL_QR, Iterative, CHOLMOD } |
enum | Verbosity { SILENT, TERMINATION, ERROR, VALUES, DELTA, LINEAR } |
Additional Inherited Members | |
Public Member Functions inherited from gtsam::NonlinearOptimizerParams | |
bool | equals (const NonlinearOptimizerParams &other, double tol=1e-9) const |
double | getAbsoluteErrorTol () const |
GaussianFactorGraph::Eliminate | getEliminationFunction () const |
double | getErrorTol () const |
std::string | getLinearSolverType () const |
size_t | getMaxIterations () const |
std::string | getOrderingType () const |
double | getRelativeErrorTol () const |
std::string | getVerbosity () const |
bool | isCholmod () const |
bool | isIterative () const |
bool | isMultifrontal () const |
bool | isSequential () const |
NonlinearOptimizerParams ()=default | |
virtual void | print (const std::string &str="") const |
void | setAbsoluteErrorTol (double value) |
void | setErrorTol (double value) |
void | setIterativeParams (const std::shared_ptr< IterativeOptimizationParameters > params) |
void | setLinearSolverType (const std::string &solver) |
void | setMaxIterations (int value) |
void | setOrdering (const Ordering &ordering) |
void | setOrderingType (const std::string &ordering) |
void | setRelativeErrorTol (double value) |
void | setVerbosity (const std::string &src) |
virtual | ~NonlinearOptimizerParams () |
Static Public Member Functions inherited from gtsam::NonlinearOptimizerParams | |
static Verbosity | verbosityTranslator (const std::string &s) |
static std::string | verbosityTranslator (Verbosity value) |
Public Attributes inherited from gtsam::NonlinearOptimizerParams | |
double | absoluteErrorTol = 1e-5 |
The maximum absolute error decrease to stop iterating (default 1e-5) More... | |
double | errorTol = 0.0 |
The maximum total error to stop iterating (default 0.0) More... | |
IterationHook | iterationHook |
IterativeOptimizationParameters::shared_ptr | iterativeParams |
The container for iterativeOptimization parameters. used in CG Solvers. More... | |
LinearSolverType | linearSolverType = MULTIFRONTAL_CHOLESKY |
The type of linear solver to use in the nonlinear optimizer. More... | |
size_t | maxIterations = 100 |
The maximum iterations to stop iterating (default 100) More... | |
std::optional< Ordering > | ordering |
The optional variable elimination ordering, or empty to use COLAMD (default: empty) More... | |
Ordering::OrderingType | orderingType = Ordering::COLAMD |
The method of ordering use during variable elimination (default COLAMD) More... | |
double | relativeErrorTol = 1e-5 |
The maximum relative error decrease to stop iterating (default 1e-5) More... | |
Verbosity | verbosity = SILENT |
The printing verbosity during optimization (default SILENT) More... | |
Parameters for Gauss-Newton optimization, inherits from NonlinearOptimizationParams.
Definition at line 30 of file GaussNewtonOptimizer.h.
Definition at line 32 of file GaussNewtonOptimizer.h.