|
Autoware.Auto
|
|
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>


Public Types | |
| enum | OptimizationDirection { OptimizationDirection::kMinimization, OptimizationDirection::kMaximization } |
| An enum that defines the direction of optimization. More... | |
Public Types inherited from autoware::common::optimization::LineSearch< MoreThuenteLineSearch > | |
| using | StepT = float_t |
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... | |
Public Member Functions inherited from autoware::common::optimization::LineSearch< MoreThuenteLineSearch > | |
| LineSearch (const StepT step_max=std::numeric_limits< StepT >::min()) | |
| DomainValueT | compute_next_step (const DomainValueT &x0, const DomainValueT &initial_step, OptimizationProblemT &optimization_problem) |
| StepT | get_step_max () const noexcept |
| void | set_step_max (const StepT step_max) noexcept |
Additional Inherited Members | |
Protected Member Functions inherited from autoware::common::helper_functions::crtp< MoreThuenteLineSearch > | |
| const MoreThuenteLineSearch & | impl () const |
| MoreThuenteLineSearch & | impl () |
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.
|
inlineexplicit |
Constructs a new instance.
| [in] | max_step | The maximum step that the process is allowed to make |
| [in] | min_step | The minimum step that the process is allowed to make |
| [in] | optimization_direction | The optimization direction |
| [in] | mu | Constant \(\mu\) (eq. 1.1), that forces a sufficient decrease of the function. |
| [in] | eta | Constant \(\eta\) (eq. 1.2), that forces the curvature condition. |
| [in] | max_iterations | Maximum allowed iterations. |
| DomainValueT autoware::common::optimization::MoreThuenteLineSearch::compute_next_step_ | ( | const DomainValueT & | x0, |
| const DomainValueT & | initial_step, | ||
| OptimizationProblemT & | optimization_problem | ||
| ) |
Calculates the next step.
| [in] | x0 | Starting argument. |
| [in] | initial_step | Initial step to initiate the search. |
| optimization_problem | The optimization problem for generating values of function denoted as f in the paper. |
| DomainValueT | Type of values of the domain of the function f. |
| OptimizationProblemT | The type of the optimization problem that provides values of function f evaluated on a domain point. |