Autoware.Auto
fixed_line_search.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef OPTIMIZATION__LINE_SEARCH__FIXED_LINE_SEARCH_HPP_
18 #define OPTIMIZATION__LINE_SEARCH__FIXED_LINE_SEARCH_HPP_
19 
21 
22 #include <limits>
23 
24 namespace autoware
25 {
26 namespace common
27 {
28 namespace optimization
29 {
30 
32 class OPTIMIZATION_PUBLIC FixedLineSearch : public LineSearch<FixedLineSearch>
33 {
34 public:
37  explicit FixedLineSearch(const StepT step = std::numeric_limits<StepT>::min())
38  : LineSearch{step} {}
39 
42  template<typename DomainValueT, typename OptimizationProblemT>
43  DomainValueT compute_next_step(
44  const DomainValueT &, DomainValueT & step_direction,
45  OptimizationProblemT &) const noexcept
46  {
47  return get_step_max() * step_direction.normalized();
48  }
49 };
50 } // namespace optimization
51 } // namespace common
52 } // namespace autoware
53 
54 #endif // OPTIMIZATION__LINE_SEARCH__FIXED_LINE_SEARCH_HPP_
autoware::common::optimization::FixedLineSearch
Class to use a fixed step length during optimization.
Definition: fixed_line_search.hpp:32
autoware::common::optimization::LineSearch
Base class (CRTP) to mange the step length during optimization.
Definition: line_search.hpp:34
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
line_search.hpp
autoware::common::optimization::LineSearch< FixedLineSearch >::StepT
float_t StepT
Definition: line_search.hpp:38
autoware::common::optimization::FixedLineSearch::compute_next_step
DomainValueT compute_next_step(const DomainValueT &, DomainValueT &step_direction, OptimizationProblemT &) const noexcept
Definition: fixed_line_search.hpp:43
autoware::common::optimization::FixedLineSearch::FixedLineSearch
FixedLineSearch(const StepT step=std::numeric_limits< StepT >::min())
Definition: fixed_line_search.hpp:37