Go to the documentation of this file.
21 #ifndef HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_
22 #define HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_
32 namespace helper_functions
46 std::is_floating_point<T>::value,
47 "Float comparisons only support floating point types.");
49 return std::abs(
a - b) <= eps;
60 return !
abs_eq(
a, b, eps) && (
a < b);
104 return abs_eq(
a,
static_cast<T>(0), eps);
117 std::is_floating_point<T>::value,
118 "Float comparisons only support floating point types.");
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;
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;
151 #endif // HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_
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
T
Definition: catr_diff.py:22
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
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
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
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
a
Definition: catr_diff.py:22
bool abs_eq(const T &a, const T &b, const T &eps)
Check for approximate equality in absolute terms.
Definition: float_comparisons.hpp:43
bool abs_eq_zero(const T &a, const T &eps)
Check whether a value is within epsilon of zero.
Definition: float_comparisons.hpp:102
Control delta
Definition: kinematic_bicycle.snippet.hpp:31
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
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