Autoware.Auto
lookup_table.hpp
Go to the documentation of this file.
1 // Copyright 2017-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 
19 
20 #ifndef GEOMETRY__LOOKUP_TABLE_HPP_
21 #define GEOMETRY__LOOKUP_TABLE_HPP_
22 
23 #include <cmath>
24 #include <stdexcept>
25 #include <vector>
26 
27 #include "common/types.hpp"
28 #include "geometry/interval.hpp"
29 
30 namespace autoware
31 {
32 namespace common
33 {
34 namespace helper_functions
35 {
36 
37 namespace
38 {
39 
44 template<typename T, typename U>
45 T interpolate(const T & a, const T & b, U scaling)
46 {
47  static const geometry::Interval<U> UNIT_INTERVAL(static_cast<U>(0), static_cast<U>(1));
48  scaling = geometry::Interval<U>::clamp_to(UNIT_INTERVAL, scaling);
49 
50  const auto m = (b - a);
51  const auto offset = static_cast<U>(m) * scaling;
52  return a + static_cast<T>(offset);
53 }
54 
55 // TODO(c.ho) support more forms of interpolation as template functor
56 // Actual lookup logic, assuming all invariants hold:
57 // Throw if value is not finite
58 template<typename T>
59 T lookup_impl_1d(const std::vector<T> & domain, const std::vector<T> & range, const T value)
60 {
61  if (!std::isfinite(value)) {
62  throw std::domain_error{"Query value is not finite (NAN or INF)"};
63  }
64  if (value <= domain.front()) {
65  return range.front();
66  } else if (value >= domain.back()) {
67  return range.back();
68  } else {
69  // Fall through to normal case
70  }
71 
72  auto second_idx{0U};
73  for (auto idx = 1U; idx < domain.size(); ++idx) {
74  if (value < domain[idx]) {
75  second_idx = idx;
76  break;
77  }
78  }
79  // T must be a floating point between 0 and 1
80  const auto num = static_cast<double>(value - domain[second_idx - 1U]);
81  const auto den = static_cast<double>(domain[second_idx] - domain[second_idx - 1U]);
82  const auto t = num / den;
83  const auto val = interpolate(range[second_idx - 1U], range[second_idx], t);
84  return static_cast<T>(val);
85 }
86 
87 // Check invariants for table lookup:
88 template<typename T>
89 void check_table_lookup_invariants(const std::vector<T> & domain, const std::vector<T> & range)
90 {
91  if (domain.size() != range.size()) {
92  throw std::domain_error{"Domain's size does not match range's"};
93  }
94  if (domain.empty()) {
95  throw std::domain_error{"Empty domain or range"};
96  }
97  // Check if sorted: Can start at 1 because not empty
98  for (auto idx = 1U; idx < domain.size(); ++idx) {
99  if (domain[idx] <= domain[idx - 1U]) { // This is safe because indexing starts at 1
100  throw std::domain_error{"Domain is not sorted"};
101  }
102  }
103 }
104 } // namespace
105 
118 template<typename T>
119 T lookup_1d(const std::vector<T> & domain, const std::vector<T> & range, const T value)
120 {
121  check_table_lookup_invariants(domain, range);
122 
123  return lookup_impl_1d(domain, range, value);
124 }
125 
129 template<typename T>
131 {
132 public:
139  LookupTable1D(const std::vector<T> & domain, const std::vector<T> & range)
140  : m_domain{domain},
141  m_range{range}
142  {
143  check_table_lookup_invariants(m_domain, m_range);
144  }
145 
152  LookupTable1D(std::vector<T> && domain, std::vector<T> && range)
153  : m_domain{domain},
154  m_range{range}
155  {
156  check_table_lookup_invariants(m_domain, m_range);
157  }
158 
165  T lookup(const T value) const
166  {
167  return lookup_impl_1d(m_domain, m_range, value);
168  }
170  const std::vector<T> & domain() const noexcept {return m_domain;}
172  const std::vector<T> & range() const noexcept {return m_range;}
173 
174 private:
175  std::vector<T> m_domain;
176  std::vector<T> m_range;
177 }; // class LookupTable1D
178 
179 } // namespace helper_functions
180 } // namespace common
181 } // namespace autoware
182 
183 
184 #endif // GEOMETRY__LOOKUP_TABLE_HPP_
catr_diff.T
T
Definition: catr_diff.py:22
types.hpp
This file includes common type definition.
catr_diff.t
t
Definition: catr_diff.py:22
autoware::common::geometry::Interval::clamp_to
static T clamp_to(const Interval &i, T val)
Clamp a scalar 'val' onto 'interval'.
Definition: interval.hpp:345
autoware::common::helper_functions::LookupTable1D::LookupTable1D
LookupTable1D(std::vector< T > &&domain, std::vector< T > &&range)
Definition: lookup_table.hpp:152
autoware::common::helper_functions::LookupTable1D::LookupTable1D
LookupTable1D(const std::vector< T > &domain, const std::vector< T > &range)
Definition: lookup_table.hpp:139
autoware::common::helper_functions::LookupTable1D::range
const std::vector< T > & range() const noexcept
Get the range table.
Definition: lookup_table.hpp:172
time_utils::interpolate
TIME_UTILS_PUBLIC std::chrono::nanoseconds interpolate(std::chrono::nanoseconds a, std::chrono::nanoseconds b, float t) noexcept
Standard interpolation.
Definition: time_utils.cpp:101
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
m
OnlineData m
Definition: linear_tire.snippet.hpp:36
autoware::common::helper_functions::LookupTable1D
Definition: lookup_table.hpp:130
autoware::common::helper_functions::LookupTable1D::domain
const std::vector< T > & domain() const noexcept
Get the domain table.
Definition: lookup_table.hpp:170
autoware::common::helper_functions::lookup_1d
T lookup_1d(const std::vector< T > &domain, const std::vector< T > &range, const T value)
Definition: lookup_table.hpp:119
catr_diff.a
a
Definition: catr_diff.py:22
interval.hpp
autoware::common::helper_functions::LookupTable1D::lookup
T lookup(const T value) const
Definition: lookup_table.hpp:165