Autoware.Auto
line_search.hpp
Go to the documentation of this file.
1 // Copyright 2019 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__LINE_SEARCH_HPP_
18 #define OPTIMIZATION__LINE_SEARCH__LINE_SEARCH_HPP_
19 
22 #include <limits>
23 #include <cmath>
24 #include <algorithm>
25 
26 namespace autoware
27 {
28 namespace common
29 {
30 namespace optimization
31 {
33 template<typename Derived>
34 class OPTIMIZATION_PUBLIC LineSearch : public common::helper_functions::crtp<Derived>
35 {
36 public:
37  // TODO(igor): should we force this to float? We mostly use 64 bit types in optimization.
38  using StepT = float_t;
39 
42  explicit LineSearch(const StepT step_max = std::numeric_limits<StepT>::min())
43  {
44  m_step_max = step_max;
45  }
46 
55  template<typename DomainValueT, typename OptimizationProblemT>
56  inline DomainValueT compute_next_step(
57  const DomainValueT & x0, const DomainValueT & initial_step,
58  OptimizationProblemT & optimization_problem)
59  {
60  return this->impl().compute_next_step_(x0, initial_step, optimization_problem);
61  }
62 
65  inline StepT get_step_max() const noexcept
66  {
67  return m_step_max;
68  }
69 
72  inline void set_step_max(const StepT step_max) noexcept
73  {
74  m_step_max = step_max;
75  }
76 
77 private:
78  StepT m_step_max;
79 };
80 
81 } // namespace optimization
82 } // namespace common
83 } // namespace autoware
84 
85 #endif // OPTIMIZATION__LINE_SEARCH__LINE_SEARCH_HPP_
Base class (CRTP) to mange the step length during optimization.
Definition: line_search.hpp:34
DomainValueT compute_next_step(const DomainValueT &x0, const DomainValueT &initial_step, OptimizationProblemT &optimization_problem)
Definition: line_search.hpp:56
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.
void set_step_max(const StepT step_max) noexcept
Definition: line_search.hpp:72
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24