Autoware.Auto
float_comparisons.hpp
Go to the documentation of this file.
1 // Copyright 2020 Mapless AI, Inc.
2 //
3 // Permission is hereby granted, free of charge, to any person obtaining a copy
4 // of this software and associated documentation files (the "Software"), to
5 // deal in the Software without restriction, including without limitation the
6 // rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
7 // sell copies of the Software, and to permit persons to whom the Software is
8 // furnished to do so, subject to the following conditions:
9 //
10 // The above copyright notice and this permission notice shall be included in
11 // all copies or substantial portions of the Software.
12 //
13 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
14 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
15 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
16 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
17 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
18 // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
19 // IN THE SOFTWARE.
20 
21 #ifndef HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_
22 #define HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_
23 
24 #include <algorithm>
25 #include <cmath>
26 #include <limits>
27 
28 namespace autoware
29 {
30 namespace common
31 {
32 namespace helper_functions
33 {
34 namespace comparisons
35 {
36 
42 template<typename T>
43 bool abs_eq(const T & a, const T & b, const T & eps)
44 {
45  static_assert(
46  std::is_floating_point<T>::value,
47  "Float comparisons only support floating point types.");
48 
49  return std::abs(a - b) <= eps;
50 }
51 
57 template<typename T>
58 bool abs_lt(const T & a, const T & b, const T & eps)
59 {
60  return !abs_eq(a, b, eps) && (a < b);
61 }
62 
68 template<typename T>
69 bool abs_lte(const T & a, const T & b, const T & eps)
70 {
71  return abs_eq(a, b, eps) || (a < b);
72 }
73 
79 template<typename T>
80 bool abs_gte(const T & a, const T & b, const T & eps)
81 {
82  return !abs_lt(a, b, eps);
83 }
84 
90 template<typename T>
91 bool abs_gt(const T & a, const T & b, const T & eps)
92 {
93  return !abs_lte(a, b, eps);
94 }
95 
101 template<typename T>
102 bool abs_eq_zero(const T & a, const T & eps)
103 {
104  return abs_eq(a, static_cast<T>(0), eps);
105 }
106 
113 template<typename T>
114 bool rel_eq(const T & a, const T & b, const T & rel_eps)
115 {
116  static_assert(
117  std::is_floating_point<T>::value,
118  "Float comparisons only support floating point types.");
119 
120  const auto delta = std::abs(a - b);
121  const auto larger = std::max(std::abs(a), std::abs(b));
122  const auto max_rel_delta = (larger * rel_eps);
123  return delta <= max_rel_delta;
124 }
125 
126 // TODO(jeff): As needed, add relative variants of <, <=, >, >=
127 
138 template<typename T>
139 bool approx_eq(const T & a, const T & b, const T & abs_eps, const T & rel_eps)
140 {
141  const auto are_absolute_eq = abs_eq(a, b, abs_eps);
142  const auto are_relative_eq = rel_eq(a, b, rel_eps);
143  return are_absolute_eq || are_relative_eq;
144 }
145 
146 } // namespace comparisons
147 } // namespace helper_functions
148 } // namespace common
149 } // namespace autoware
150 
151 #endif // HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_
autoware::common::helper_functions::comparisons::abs_gt
bool abs_gt(const T &a, const T &b, const T &eps)
Check for approximate greater than in absolute terms.
Definition: float_comparisons.hpp:91
autoware::common::helper_functions::comparisons::approx_eq
bool approx_eq(const T &a, const T &b, const T &abs_eps, const T &rel_eps)
Check for approximate equality in absolute and relative terms.
Definition: float_comparisons.hpp:139
autoware::common::helper_functions::comparisons::abs_lt
bool abs_lt(const T &a, const T &b, const T &eps)
Check for approximate less than in absolute terms.
Definition: float_comparisons.hpp:58
autoware::common::helper_functions::comparisons::abs_lte
bool abs_lte(const T &a, const T &b, const T &eps)
Check for approximate less than or equal in absolute terms.
Definition: float_comparisons.hpp:69
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::helper_functions::comparisons::abs_eq
bool abs_eq(const T &a, const T &b, const T &eps)
Check for approximate equality in absolute terms.
Definition: float_comparisons.hpp:43
autoware::common::helper_functions::comparisons::abs_eq_zero
bool abs_eq_zero(const T &a, const T &eps)
Check whether a value is within epsilon of zero.
Definition: float_comparisons.hpp:102
delta
Control delta
Definition: kinematic_bicycle.snippet.hpp:31
autoware::common::helper_functions::comparisons::abs_gte
bool abs_gte(const T &a, const T &b, const T &eps)
Check for approximate greater than or equal in absolute terms.
Definition: float_comparisons.hpp:80
autoware::common::helper_functions::comparisons::rel_eq
bool rel_eq(const T &a, const T &b, const T &rel_eps)
https://randomascii.wordpress.com/2012/02/25/comparing-floating-point-numbers-2012-edition/
Definition: float_comparisons.hpp:114