Go to the documentation of this file.
17 #ifndef OPTIMIZATION__LINE_SEARCH__FIXED_LINE_SEARCH_HPP_
18 #define OPTIMIZATION__LINE_SEARCH__FIXED_LINE_SEARCH_HPP_
28 namespace optimization
42 template<
typename DomainValueT,
typename OptimizationProblemT>
44 const DomainValueT &, DomainValueT & step_direction,
45 OptimizationProblemT &)
const noexcept
47 return get_step_max() * step_direction.normalized();
54 #endif // OPTIMIZATION__LINE_SEARCH__FIXED_LINE_SEARCH_HPP_
Class to use a fixed step length during optimization.
Definition: fixed_line_search.hpp:32
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
float_t StepT
Definition: line_search.hpp:38
DomainValueT compute_next_step(const DomainValueT &, DomainValueT &step_direction, OptimizationProblemT &) const noexcept
Definition: fixed_line_search.hpp:43
FixedLineSearch(const StepT step=std::numeric_limits< StepT >::min())
Definition: fixed_line_search.hpp:37