#include <DoglegOptimizer.h>
Public Types | |
enum | VerbosityDL { SILENT, VERBOSE } |
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 } |
Public Member Functions | |
DoglegParams () | |
double | getDeltaInitial () const |
std::string | getVerbosityDL () const |
void | print (const std::string &str="") const override |
void | setDeltaInitial (double deltaInitial) |
void | setVerbosityDL (const std::string &verbosityDL) |
~DoglegParams () override | |
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 | |
void | setAbsoluteErrorTol (double value) |
void | setErrorTol (double value) |
void | setIterativeParams (const boost::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 () |
Public Attributes | |
double | deltaInitial |
The initial trust region radius (default: 10.0) More... | |
VerbosityDL | verbosityDL |
The verbosity level for Dogleg (default: SILENT), see also NonlinearOptimizerParams::verbosity. More... | |
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... | |
boost::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... | |
Private Member Functions | |
VerbosityDL | verbosityDLTranslator (const std::string &verbosityDL) const |
std::string | verbosityDLTranslator (VerbosityDL verbosityDL) const |
Additional Inherited Members | |
Static Public Member Functions inherited from gtsam::NonlinearOptimizerParams | |
static Verbosity | verbosityTranslator (const std::string &s) |
static std::string | verbosityTranslator (Verbosity value) |
Parameters for Levenberg-Marquardt optimization. Note that this parameters class inherits from NonlinearOptimizerParams, which specifies the parameters common to all nonlinear optimization algorithms. This class also contains all of those parameters.
Definition at line 32 of file DoglegOptimizer.h.
See DoglegParams::dlVerbosity
Enumerator | |
---|---|
SILENT | |
VERBOSE |
Definition at line 35 of file DoglegOptimizer.h.
|
inline |
Definition at line 43 of file DoglegOptimizer.h.
|
inlineoverride |
Definition at line 46 of file DoglegOptimizer.h.
|
inline |
Definition at line 54 of file DoglegOptimizer.h.
|
inline |
Definition at line 55 of file DoglegOptimizer.h.
|
inlineoverridevirtual |
Reimplemented from gtsam::NonlinearOptimizerParams.
Definition at line 48 of file DoglegOptimizer.h.
|
inline |
Definition at line 57 of file DoglegOptimizer.h.
|
inline |
Definition at line 58 of file DoglegOptimizer.h.
|
private |
Definition at line 32 of file DoglegOptimizer.cpp.
|
private |
Definition at line 42 of file DoglegOptimizer.cpp.
double gtsam::DoglegParams::deltaInitial |
The initial trust region radius (default: 10.0)
Definition at line 40 of file DoglegOptimizer.h.
VerbosityDL gtsam::DoglegParams::verbosityDL |
The verbosity level for Dogleg (default: SILENT), see also NonlinearOptimizerParams::verbosity.
Definition at line 41 of file DoglegOptimizer.h.