Autoware.Auto
common/optimization/include/optimization/utils.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__UTILS_HPP_
18 #define OPTIMIZATION__UTILS_HPP_
19 
20 #include <common/types.hpp>
22 #include <Eigen/Core>
23 #include <functional>
24 #include <limits>
25 
27 
28 namespace autoware
29 {
30 namespace common
31 {
32 namespace optimization
33 {
38 class OPTIMIZATION_PUBLIC ComputeMode
39 {
40 public:
42  ComputeMode() = default;
47  ComputeMode(bool8_t score, bool8_t jacobian, bool8_t hessian);
50  ComputeMode & set_score() noexcept;
53  ComputeMode & set_jacobian() noexcept;
56  ComputeMode & set_hessian() noexcept;
57 
60  bool8_t score() const noexcept;
63  bool8_t jacobian() const noexcept;
66  bool8_t hessian() const noexcept;
67 
68  bool8_t operator==(const ComputeMode & other) const noexcept;
69  bool8_t operator!=(const ComputeMode & other) const noexcept;
70 
71 private:
72  bool8_t m_score{false};
73  bool8_t m_jacobian{false};
74  bool8_t m_hessian{false};
75 };
76 
78 enum class ExpressionTerm
79 {
80  SCORE, // Evaluation of the expression
81  JACOBIAN, // Evaluation of the first derivative
82  HESSIAN // Evaluation of the second derivative
83 };
84 
86 class OPTIMIZATION_PUBLIC EigenComparator
87 {
88 public:
89  template<typename T, int H, int W>
90  typename std::enable_if_t<std::is_floating_point<T>::value, bool8_t>
91  operator()(const Eigen::Matrix<T, H, W> & lhs, const Eigen::Matrix<T, H, W> & rhs) const
92  {
93  return lhs.isApprox(rhs, std::numeric_limits<T>::epsilon());
94  }
95 
96  template<typename T, int H, int W>
97  typename std::enable_if_t<std::is_integral<T>::value, bool8_t>
98  operator()(const Eigen::Matrix<T, H, W> & lhs, const Eigen::Matrix<T, H, W> & rhs) const
99  {
100  return lhs == rhs;
101  }
102 };
103 
107 template<typename DomainValue, typename ComparatorT = decltype(std::equal_to<DomainValue>())>
108 class OPTIMIZATION_PUBLIC CacheStateMachine
109 {
110 public:
111  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
114  explicit CacheStateMachine(const ComparatorT & comparator = ComparatorT())
115  : m_comparator(comparator) {}
116 
122  const DomainValue & value, const ComputeMode & mode,
123  const ComparatorT & comparator = ComparatorT())
124  : m_comparator(comparator), m_last_mode(mode), m_last_value(value)
125  {
126  }
127 
131  void update(const DomainValue & value, const ComputeMode & mode) noexcept
132  {
133  m_last_mode = mode;
134  m_last_value = value;
135  }
136 
143  bool8_t is_cached(const DomainValue & x, const ExpressionTerm & term) const noexcept
144  {
145  bool8_t ret = false;
146  if (m_comparator(x, m_last_value)) {
147  switch (term) {
149  ret = m_last_mode.score();
150  break;
152  ret = m_last_mode.jacobian();
153  break;
155  ret = m_last_mode.hessian();
156  break;
157  default:
158  ret = false;
159  }
160  }
161  return ret;
162  }
163 
164 private:
165  const ComparatorT m_comparator;
166  DomainValue m_last_value;
167  ComputeMode m_last_mode;
168 };
169 
170 } // namespace optimization
171 } // namespace common
172 } // namespace autoware
173 
174 #endif // OPTIMIZATION__UTILS_HPP_
autoware::common::optimization::CacheStateMachine::is_cached
bool8_t is_cached(const DomainValue &x, const ExpressionTerm &term) const noexcept
Definition: common/optimization/include/optimization/utils.hpp:143
autoware::common::optimization::ExpressionTerm::JACOBIAN
@ JACOBIAN
autoware::common::optimization::CacheStateMachine::CacheStateMachine
CacheStateMachine(const DomainValue &value, const ComputeMode &mode, const ComparatorT &comparator=ComparatorT())
Definition: common/optimization/include/optimization/utils.hpp:121
types.hpp
This file includes common type definition.
autoware::common::optimization::ComputeMode
Definition: common/optimization/include/optimization/utils.hpp:38
autoware::common::optimization::ExpressionTerm::SCORE
@ SCORE
autoware::common::optimization::EigenComparator
Generic equality comparison functor for eigen matrices.
Definition: common/optimization/include/optimization/utils.hpp:86
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::optimization::EigenComparator::operator()
std::enable_if_t< std::is_floating_point< T >::value, bool8_t > operator()(const Eigen::Matrix< T, H, W > &lhs, const Eigen::Matrix< T, H, W > &rhs) const
Definition: common/optimization/include/optimization/utils.hpp:91
visibility_control.hpp
autoware::common::optimization::ExpressionTerm::HESSIAN
@ HESSIAN
x
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
autoware::common::optimization::CacheStateMachine::CacheStateMachine
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CacheStateMachine(const ComparatorT &comparator=ComparatorT())
Definition: common/optimization/include/optimization/utils.hpp:114
autoware::common::optimization::ExpressionTerm
ExpressionTerm
Enum class representing expression terms.
Definition: common/optimization/include/optimization/utils.hpp:78
autoware::common::optimization::CacheStateMachine
Definition: common/optimization/include/optimization/utils.hpp:108
autoware::common::optimization::CacheStateMachine::update
void update(const DomainValue &value, const ComputeMode &mode) noexcept
Definition: common/optimization/include/optimization/utils.hpp:131
autoware::common::optimization::EigenComparator::operator()
std::enable_if_t< std::is_integral< T >::value, bool8_t > operator()(const Eigen::Matrix< T, H, W > &lhs, const Eigen::Matrix< T, H, W > &rhs) const
Definition: common/optimization/include/optimization/utils.hpp:98