Functions | Variables
gtsam.utils.logging_optimizer Namespace Reference

Functions

def gtsam_optimize (optimizer, params, hook)
 
def optimize (optimizer, check_convergence, hook)
 
gtsam.Values optimize_using (OptimizerClass, hook, *args)
 

Variables

dictionary OPTIMIZER_PARAMS_MAP
 

Detailed Description

Optimization with logging via a hook.
Author: Jing Wu and Frank Dellaert

Function Documentation

◆ gtsam_optimize()

def gtsam.utils.logging_optimizer.gtsam_optimize (   optimizer,
  params,
  hook 
)
Given an optimizer and params, iterate until convergence.
    Recommend using optimize_using instead.
    After each iteration, hook(optimizer) is called.
    After the function, use values and errors to get the result.
    Arguments:
            optimizer {NonlinearOptimizer} -- Nonlinear optimizer
            params {NonlinearOptimizarParams} -- Nonlinear optimizer parameters
            hook -- hook function to record the error

Definition at line 83 of file logging_optimizer.py.

◆ optimize()

def gtsam.utils.logging_optimizer.optimize (   optimizer,
  check_convergence,
  hook 
)
Given an optimizer and a convergence check, iterate until convergence.
    After each iteration, hook(optimizer, error) is called.
    After the function, use values and errors to get the result.
    Arguments:
        optimizer (T): needs an iterate and an error function.
        check_convergence: T * float * float -> bool
        hook -- hook function to record the error

Definition at line 58 of file logging_optimizer.py.

◆ optimize_using()

gtsam.Values gtsam.utils.logging_optimizer.optimize_using (   OptimizerClass,
  hook,
args 
)
Wraps the constructor and "optimize()" call for an Optimizer together and adds an iteration
    hook.
    Example usage:
        ```python
        def hook(optimizer, error):
            print("iteration {:}, error = {:}".format(optimizer.iterations(), error))
        solution = optimize_using(gtsam.GaussNewtonOptimizer, hook, graph, init, params)
        ```
    Iteration hook's args are (optimizer, error) and return type should be None

Args:
    OptimizerClass (T): A NonlinearOptimizer class (e.g. GaussNewtonOptimizer,
        LevenbergMarquardtOptimizer)
    hook ([T, double] -> None): Function to callback after each iteration.  Args are (optimizer,
        error) and return should be None.
    *args: Arguments that would be passed into the OptimizerClass constructor, usually:
        graph, init, [params]
Returns:
    (gtsam.Values): A Values object representing the optimization solution.

Definition at line 20 of file logging_optimizer.py.

Variable Documentation

◆ OPTIMIZER_PARAMS_MAP

dictionary gtsam.utils.logging_optimizer.OPTIMIZER_PARAMS_MAP
gtsam::GaussNewtonOptimizer
Definition: GaussNewtonOptimizer.h:38
gtsam::DoglegOptimizer
Definition: DoglegOptimizer.h:68
gtsam::GaussNewtonParams
Definition: GaussNewtonOptimizer.h:30
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
gtsam::DoglegParams
Definition: DoglegOptimizer.h:32
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:16:45