Autoware.Auto
autoware::common::optimization::MoreThuenteLineSearch Class Reference

This class describes a More-Thuente line search as presented in the paper "Line Search Algorithms with Guaranteed Sufficient Decrease" by Jorge J. More and David J. Thuente. More...

#include <more_thuente_line_search.hpp>

Inheritance diagram for autoware::common::optimization::MoreThuenteLineSearch:
Collaboration diagram for autoware::common::optimization::MoreThuenteLineSearch:

Public Types

enum  OptimizationDirection { OptimizationDirection::kMinimization, OptimizationDirection::kMaximization }
 An enum that defines the direction of optimization. More...
 

Public Member Functions

 MoreThuenteLineSearch (const StepT max_step, const StepT min_step, const OptimizationDirection optimization_direction=OptimizationDirection::kMinimization, const StepT mu=1.e-4F, const StepT eta=0.1F, const std::int32_t max_iterations=10)
 Constructs a new instance. More...
 
template<typename DomainValueT , typename OptimizationProblemT >
DomainValueT compute_next_step_ (const DomainValueT &x0, const DomainValueT &initial_step, OptimizationProblemT &optimization_problem)
 Calculates the next step. More...
 

Additional Inherited Members

- Protected Member Functions inherited from autoware::common::helper_functions::crtp< MoreThuenteLineSearch >
const MoreThuenteLineSearch & impl () const
 
MoreThuenteLineSearch & impl ()
 

Detailed Description

This class describes a More-Thuente line search as presented in the paper "Line Search Algorithms with Guaranteed Sufficient Decrease" by Jorge J. More and David J. Thuente.

One notable change here is that this class will automatically detect if we are trying to solve a minimization or the maximization problem by evaluating \(\phi^\prime(0)\). If \(\phi^\prime(0) < 0\) then we follow the suggestions in the paper exactle. Otherwise, we assume we are dealing with a dual maximization problem and will flip the objective function \(\phi\), thus making it again a minimization problem.

Member Enumeration Documentation

◆ OptimizationDirection

An enum that defines the direction of optimization.

Enumerator
kMinimization 
kMaximization 

Constructor & Destructor Documentation

◆ MoreThuenteLineSearch()

autoware::common::optimization::MoreThuenteLineSearch::MoreThuenteLineSearch ( const StepT  max_step,
const StepT  min_step,
const OptimizationDirection  optimization_direction = OptimizationDirection::kMinimization,
const StepT  mu = 1.e-4F,
const StepT  eta = 0.1F,
const std::int32_t  max_iterations = 10 
)
inlineexplicit

Constructs a new instance.

Parameters
[in]max_stepThe maximum step that the process is allowed to make
[in]min_stepThe minimum step that the process is allowed to make
[in]optimization_directionThe optimization direction
[in]muConstant \(\mu\) (eq. 1.1), that forces a sufficient decrease of the function.
[in]etaConstant \(\eta\) (eq. 1.2), that forces the curvature condition.
[in]max_iterationsMaximum allowed iterations.

Member Function Documentation

◆ compute_next_step_()

template<typename DomainValueT , typename OptimizationProblemT >
DomainValueT autoware::common::optimization::MoreThuenteLineSearch::compute_next_step_ ( const DomainValueT &  x0,
const DomainValueT &  initial_step,
OptimizationProblemT &  optimization_problem 
)

Calculates the next step.

Parameters
[in]x0Starting argument.
[in]initial_stepInitial step to initiate the search.
optimization_problemThe optimization problem for generating values of function denoted as f in the paper.
Template Parameters
DomainValueTType of values of the domain of the function f.
OptimizationProblemTThe type of the optimization problem that provides values of function f evaluated on a domain point.
Returns
The new step to make in order to optimize the function.
Note
If the length of initial_step is smaller than the m_step_min then an unmodified initial_step will be returned.

The documentation for this class was generated from the following file: