Go to the documentation of this file.
19 #ifndef COMMON__TYPES_HPP_
20 #define COMMON__TYPES_HPP_
27 #include "common/visibility_control.hpp"
44 static_assert(
sizeof(
float) == 4,
"float is assumed to be 32-bit");
46 static_assert(
sizeof(
double) == 8,
"double is assumed to be 64-bit");
63 static constexpr uint16_t END_OF_SCAN_ID = 65535
u;
72 static constexpr uint16_t END_OF_SCAN_ID = 65535
u;
79 :
x(
x),
y(
y), z(z), intensity(intensity) {}
90 p1.x, p2.x, std::numeric_limits<float32_t>::epsilon()) &&
93 p1.y, p2.y, std::numeric_limits<float32_t>::epsilon()) &&
96 p1.z, p2.z, std::numeric_limits<float32_t>::epsilon()) &&
99 p1.intensity, p2.intensity, std::numeric_limits<float32_t>::epsilon());
110 template<
typename ... Ts>
116 #endif // COMMON__TYPES_HPP_
friend bool operator==(const PointXYZI &p1, const PointXYZI &p2) noexcept
Definition: types.hpp:84
void void_t
`stdvoid_t<> implementation
Definition: types.hpp:111
constexpr float32_t PI_2
pi/2
Definition: types.hpp:52
std::vector< const PointXYZIF * > PointPtrBlock
Definition: types.hpp:104
constexpr float32_t TAU
tau = 2 pi
Definition: types.hpp:54
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
DifferentialState u
Definition: kinematic_bicycle.snippet.hpp:29
static constexpr uint16_t POINT_BLOCK_CAPACITY
Stores basic configuration information, does some simple validity checking.
Definition: types.hpp:106
char char8_t
Definition: types.hpp:40
bool bool8_t
Definition: types.hpp:39
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
unsigned char uchar8_t
Definition: types.hpp:41
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
std::vector< PointXYZIF > PointBlock
Definition: types.hpp:103
float float32_t
Definition: types.hpp:45
double float64_t
Definition: types.hpp:47
PointXYZI(float32_t x, float32_t y, float32_t z, float32_t intensity)
Definition: types.hpp:78
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
constexpr float32_t PI
pi = tau / 2
Definition: types.hpp:50