Autoware.Auto
types.hpp
Go to the documentation of this file.
1 // Copyright 2017-2020 the Autoware Foundation, Arm Limited
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.
18 
19 #ifndef COMMON__TYPES_HPP_
20 #define COMMON__TYPES_HPP_
21 
22 #include <cstdint>
23 #include <vector>
24 #include <limits>
25 
27 #include "common/visibility_control.hpp"
28 
29 namespace autoware
30 {
31 namespace common
32 {
33 namespace types
34 {
35 // Aliases to conform to MISRA C++ Rule 3-9-2 (Directive 4.6 in MISRA C).
36 // Similarly, the stdint typedefs should be used instead of plain int, long etc. types.
37 // We don't currently require code to comply to MISRA, but we should try to where it is
38 // easily possible.
39 using bool8_t = bool;
40 using char8_t = char;
41 using uchar8_t = unsigned char;
42 // If we ever compile on a platform where this is not true, float32_t and float64_t definitions
43 // need to be adjusted.
44 static_assert(sizeof(float) == 4, "float is assumed to be 32-bit");
45 using float32_t = float;
46 static_assert(sizeof(double) == 8, "double is assumed to be 64-bit");
47 using float64_t = double;
48 
50 constexpr float32_t PI = 3.14159265359F;
52 constexpr float32_t PI_2 = 1.5707963267948966F;
54 constexpr float32_t TAU = 6.283185307179586476925286766559F;
55 
56 struct COMMON_PUBLIC PointXYZIF
57 {
60  float32_t z{0};
61  float32_t intensity{0};
62  uint16_t id{0};
63  static constexpr uint16_t END_OF_SCAN_ID = 65535u;
64  friend bool operator==(
65  const PointXYZIF & p1,
66  const PointXYZIF & p2) noexcept
67  {
69  const auto epsilon = std::numeric_limits<float32_t>::epsilon();
70  return rel_eq(p1.x, p2.x, epsilon) &&
71  rel_eq(p1.y, p2.y, epsilon) &&
72  rel_eq(p1.z, p2.z, epsilon) &&
73  rel_eq(p1.intensity, p2.intensity, epsilon) &&
74  (p1.id == p2.id);
75  }
76 };
77 
78 struct COMMON_PUBLIC PointXYZF
79 {
82  float32_t z{0};
83  uint16_t id{0};
84  static constexpr uint16_t END_OF_SCAN_ID = 65535u;
85  friend bool operator==(
86  const PointXYZF & p1,
87  const PointXYZF & p2) noexcept
88  {
90  const auto epsilon = std::numeric_limits<float32_t>::epsilon();
91  return rel_eq(p1.x, p2.x, epsilon) &&
92  rel_eq(p1.y, p2.y, epsilon) &&
93  rel_eq(p1.z, p2.z, epsilon) &&
94  (p1.id == p2.id);
95  }
96 };
97 
98 struct COMMON_PUBLIC PointXYZI
99 {
100  float32_t x{0.0F};
101  float32_t y{0.0F};
102  float32_t z{0.0F};
103  float32_t intensity{0.0F};
104  friend bool operator==(
105  const PointXYZI & p1,
106  const PointXYZI & p2) noexcept
107  {
108  return
110  p1.x, p2.x, std::numeric_limits<float32_t>::epsilon()) &&
111 
113  p1.y, p2.y, std::numeric_limits<float32_t>::epsilon()) &&
114 
116  p1.z, p2.z, std::numeric_limits<float32_t>::epsilon()) &&
117 
119  p1.intensity, p2.intensity, std::numeric_limits<float32_t>::epsilon());
120  }
121 };
122 
123 using PointBlock = std::vector<PointXYZIF>;
124 using PointPtrBlock = std::vector<const PointXYZIF *>;
126 static constexpr uint16_t POINT_BLOCK_CAPACITY = 512U;
127 
128 // TODO(yunus.caliskan): switch to std::void_t when C++17 is available
130 template<typename ... Ts>
131 using void_t = void;
132 } // namespace types
133 } // namespace common
134 } // namespace autoware
135 
136 #endif // COMMON__TYPES_HPP_
autoware::common::types::PointXYZI::operator==
friend bool operator==(const PointXYZI &p1, const PointXYZI &p2) noexcept
Definition: types.hpp:104
autoware::common::types::void_t
void void_t
`stdvoid_t<> implementation
Definition: types.hpp:131
autoware::common::types::PI_2
constexpr float32_t PI_2
pi/2
Definition: types.hpp:52
autoware::common::types::PointPtrBlock
std::vector< const PointXYZIF * > PointPtrBlock
Definition: types.hpp:124
autoware::common::types::TAU
constexpr float32_t TAU
tau = 2 pi
Definition: types.hpp:54
autoware::common::types::PointXYZIF::operator==
friend bool operator==(const PointXYZIF &p1, const PointXYZIF &p2) noexcept
Definition: types.hpp:64
y
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
autoware::common::types::PointXYZF
Definition: types.hpp:78
u
DifferentialState u
Definition: kinematic_bicycle.snippet.hpp:29
autoware::common::types::POINT_BLOCK_CAPACITY
static constexpr uint16_t POINT_BLOCK_CAPACITY
Stores basic configuration information, does some simple validity checking.
Definition: types.hpp:126
autoware::common::types::PointXYZIF
Definition: types.hpp:56
autoware::common::types::char8_t
char char8_t
Definition: types.hpp:40
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
float_comparisons.hpp
autoware::common::types::uchar8_t
unsigned char uchar8_t
Definition: types.hpp:41
autoware::common::types::PointXYZF::operator==
friend bool operator==(const PointXYZF &p1, const PointXYZF &p2) noexcept
Definition: types.hpp:85
x
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
autoware::common::types::PointBlock
std::vector< PointXYZIF > PointBlock
Definition: types.hpp:123
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::common::types::PointXYZI
Definition: types.hpp:98
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
autoware::common::types::PI
constexpr float32_t PI
pi = tau / 2
Definition: types.hpp:50