|
Autoware.Auto
|
|
Base class (CRTP) to mange the step length during optimization. More...
#include <line_search.hpp>


Public Types | |
| using | StepT = float_t |
Public Member Functions | |
| LineSearch (const StepT step_max=std::numeric_limits< StepT >::min()) | |
| template<typename DomainValueT , typename OptimizationProblemT > | |
| 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< Derived > | |
| const Derived & | impl () const |
| Derived & | impl () |
Base class (CRTP) to mange the step length during optimization.
| using autoware::common::optimization::LineSearch< Derived >::StepT = float_t |
|
inlineexplicit |
Constructor.
| step_max | Maximum step length. By default initialized to the minimum value. |
|
inline |
Computes the optimal step for the optimization optimization_problem
| DomainValueT | Parameter type. |
| OptimizationProblemT | Optimization optimization_problem type. Must be an implementation of common::optimization::OptimizationProblem. |
| x0 | Initial x value to do the line searching for. |
| initial_step | Initial step to start the search for the optimal step. |
| optimization_problem | optimization problem. |
|
inlinenoexcept |
Getter for the maximum step length
|
inlinenoexcept |
Setter for the maximum step length
| step_max | the new maximal step length |