#include <DoglegOptimizerImpl.h>
Classes | |
struct | IterationResult |
Public Types | |
enum | TrustRegionAdaptationMode { SEARCH_EACH_ITERATION, SEARCH_REDUCE_ONLY, ONE_STEP_PER_ITERATION } |
Static Public Member Functions | |
static VectorValues | ComputeBlend (double delta, const VectorValues &x_u, const VectorValues &x_n, const bool verbose=false) |
static VectorValues | ComputeDoglegPoint (double delta, const VectorValues &dx_u, const VectorValues &dx_n, const bool verbose=false) |
template<class M , class F , class VALUES > | |
static IterationResult | Iterate (double delta, TrustRegionAdaptationMode mode, const VectorValues &dx_u, const VectorValues &dx_n, const M &Rd, const F &f, const VALUES &x0, const double f_error, const bool verbose=false) |
This class contains the implementation of the Dogleg algorithm. It is used by DoglegOptimizer and can be used to easily put together custom versions of Dogleg. Each function is well-documented and unit-tested. The notation here matches that in "trustregion.pdf" in doc, see this file for further explanation of the computations performed by this class.
Definition at line 32 of file DoglegOptimizerImpl.h.
Specifies how the trust region is adapted at each Dogleg iteration. If this is SEARCH_EACH_ITERATION, then the trust region radius will be increased potentially multiple times during one iteration until increasing it further no longer decreases the error. If this is ONE_STEP_PER_ITERATION, then the step in one iteration will not exceed the current trust region radius, but the radius will be increased for the next iteration if the error decrease is good. The former will generally result in slower iterations, but sometimes larger steps in early iterations. The latter generally results in faster iterations but it may take several iterations before the trust region radius is increased to the optimal value. Generally ONE_STEP_PER_ITERATION should be used, corresponding to most published descriptions of the algorithm.
Enumerator | |
---|---|
SEARCH_EACH_ITERATION | |
SEARCH_REDUCE_ONLY | |
ONE_STEP_PER_ITERATION |
Definition at line 53 of file DoglegOptimizerImpl.h.
|
static |
Compute the point on the line between the steepest descent point and the Newton's method point intersecting the trust region boundary. Mathematically, computes such that and , where is the trust region radius.
delta | Trust region radius |
x_u | Steepest descent minimizer |
x_n | Newton's method minimizer |
Definition at line 51 of file DoglegOptimizerImpl.cpp.
|
static |
Compute the dogleg point given a trust region radius . The dogleg point is the intersection between the dogleg path and the trust region boundary, see doc/trustregion.pdf for more details.
The update is computed using a quadratic approximation of an original nonlinear error function (a NonlinearFactorGraph) . The quadratic approximation is represented as a GaussianBayesNet , which is obtained by eliminating a GaussianFactorGraph resulting from linearizing the nonlinear factor graph . Thus, is
where and together are a Bayes' net. is upper-triangular and is a vector, in GTSAM represented as a GaussianBayesNet, containing GaussianConditional s.
delta | The trust region radius |
dx_u | The steepest descent point, i.e. the Cauchy point |
dx_n | The Gauss-Newton point |
Definition at line 25 of file DoglegOptimizerImpl.cpp.
|
static |
Compute the update point for one iteration of the Dogleg algorithm, given an initial trust region radius . The trust region radius is adapted based on the error of a NonlinearFactorGraph , and depending on the update mode mode
.
The update is computed using a quadratic approximation of an original nonlinear error function (a NonlinearFactorGraph) . The quadratic approximation is represented as a GaussianBayesNet , which is obtained by eliminating a GaussianFactorGraph resulting from linearizing the nonlinear factor graph . Thus, is
where and together are a Bayes' net or Bayes' tree. is upper-triangular and is a vector, in GTSAM represented as a BayesNet<GaussianConditional> (GaussianBayesNet) or BayesTree<GaussianConditional>, containing GaussianConditional s.
M | The type of the Bayes' net or tree, currently either BayesNet<GaussianConditional> (or GaussianBayesNet) or BayesTree<GaussianConditional>. |
F | For normal usage this will be NonlinearFactorGraph<VALUES>. |
VALUES | The Values or TupleValues to pass to F::error() to evaluate the error function. |
delta | The initial trust region radius. |
mode | See DoglegOptimizerImpl::TrustRegionAdaptationMode |
Rd | The Bayes' net or tree as described above. |
f | The original nonlinear factor graph with which to evaluate the accuracy of to adjust . |
x0 | The linearization point about which was created |
ordering | The variable ordering used to create |
f_error | The result of f.error(x0) . |
delta
, the linear update dx_d
, and the resulting nonlinear error f_error
. Definition at line 138 of file DoglegOptimizerImpl.h.