Go to the documentation of this file.
17 #ifndef OPTIMIZATION__LINE_SEARCH__LINE_SEARCH_HPP_
18 #define OPTIMIZATION__LINE_SEARCH__LINE_SEARCH_HPP_
30 namespace optimization
33 template<
typename Derived>
44 m_step_max = step_max;
55 template<
typename DomainValueT,
typename OptimizationProblemT>
57 const DomainValueT & x0,
const DomainValueT & initial_step,
58 OptimizationProblemT & optimization_problem)
60 return this->impl().compute_next_step_(x0, initial_step, optimization_problem);
74 m_step_max = step_max;
85 #endif // OPTIMIZATION__LINE_SEARCH__LINE_SEARCH_HPP_
DomainValueT compute_next_step(const DomainValueT &x0, const DomainValueT &initial_step, OptimizationProblemT &optimization_problem)
Definition: line_search.hpp:56
Base class (CRTP) to mange the step length during optimization.
Definition: line_search.hpp:34
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
StepT get_step_max() const noexcept
Definition: line_search.hpp:65
LineSearch(const StepT step_max=std::numeric_limits< StepT >::min())
Definition: line_search.hpp:42
This file includes common helper functions.
float_t StepT
Definition: line_search.hpp:38
void set_step_max(const StepT step_max) noexcept
Definition: line_search.hpp:72