Autoware.Auto
autoware::common::optimization::LineSearch< Derived > Class Template Reference

Base class (CRTP) to mange the step length during optimization. More...

#include <line_search.hpp>

Inheritance diagram for autoware::common::optimization::LineSearch< Derived >:
Collaboration diagram for autoware::common::optimization::LineSearch< Derived >:

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 ()
 

Detailed Description

template<typename Derived>
class autoware::common::optimization::LineSearch< Derived >

Base class (CRTP) to mange the step length during optimization.

Member Typedef Documentation

◆ StepT

template<typename Derived>
using autoware::common::optimization::LineSearch< Derived >::StepT = float_t

Constructor & Destructor Documentation

◆ LineSearch()

template<typename Derived>
autoware::common::optimization::LineSearch< Derived >::LineSearch ( const StepT  step_max = std::numeric_limits<StepT>::min())
inlineexplicit

Constructor.

Parameters
step_maxMaximum step length. By default initialized to the minimum value.

Member Function Documentation

◆ compute_next_step()

template<typename Derived>
template<typename DomainValueT , typename OptimizationProblemT >
DomainValueT autoware::common::optimization::LineSearch< Derived >::compute_next_step ( const DomainValueT &  x0,
const DomainValueT &  initial_step,
OptimizationProblemT &  optimization_problem 
)
inline

Computes the optimal step for the optimization optimization_problem

Template Parameters
DomainValueTParameter type.
OptimizationProblemTOptimization optimization_problem type. Must be an implementation of common::optimization::OptimizationProblem.
Parameters
x0Initial x value to do the line searching for.
initial_stepInitial step to start the search for the optimal step.
optimization_problemoptimization problem.
Returns
Optimal step.

◆ get_step_max()

template<typename Derived>
StepT autoware::common::optimization::LineSearch< Derived >::get_step_max ( ) const
inlinenoexcept

Getter for the maximum step length

Returns
The maximum step length.

◆ set_step_max()

template<typename Derived>
void autoware::common::optimization::LineSearch< Derived >::set_step_max ( const StepT  step_max)
inlinenoexcept

Setter for the maximum step length

Parameters
step_maxthe new maximal step length

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