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 
25 #include "common/visibility_control.hpp"
26 
27 namespace autoware
28 {
29 namespace common
30 {
31 namespace types
32 {
33 using bool8_t = bool;
34 using char8_t = char;
35 using uchar8_t = unsigned char;
36 using float32_t = float;
37 using float64_t = double;
38 
40 constexpr float32_t PI = 3.14159265359F;
42 constexpr float32_t PI_2 = 1.5707963267948966F;
44 constexpr float32_t TAU = 6.283185307179586476925286766559F;
46 constexpr float32_t FEPS = 0.000001F;
47 
48 struct COMMON_PUBLIC PointXYZIF
49 {
52  float32_t z{0};
53  float32_t intensity{0};
54  uint16_t id{0};
55  static constexpr uint16_t END_OF_SCAN_ID = 65535u;
56 };
57 
58 struct COMMON_PUBLIC PointXYZF
59 {
62  float32_t z{0};
63  uint16_t id{0};
64  static constexpr uint16_t END_OF_SCAN_ID = 65535u;
65 };
66 
67 using PointBlock = std::vector<PointXYZIF>;
68 using PointPtrBlock = std::vector<const PointXYZIF *>;
70 static constexpr uint16_t POINT_BLOCK_CAPACITY = 512U;
71 
72 } // namespace types
73 } // namespace common
74 } // namespace autoware
75 
76 #endif // COMMON__TYPES_HPP_
autoware::common::types::PI_2
constexpr float32_t PI_2
pi/2
Definition: types.hpp:42
autoware::common::types::PointPtrBlock
std::vector< const PointXYZIF * > PointPtrBlock
Definition: types.hpp:68
autoware::common::types::TAU
constexpr float32_t TAU
tau = 2 pi
Definition: types.hpp:44
y
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
autoware::common::types::PointXYZF
Definition: types.hpp:58
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:70
autoware::common::types::PointXYZIF
Definition: types.hpp:48
autoware::common::types::char8_t
char char8_t
Definition: types.hpp:34
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::types::uchar8_t
unsigned char uchar8_t
Definition: types.hpp:35
autoware::common::types::FEPS
constexpr float32_t FEPS
arbitrary small constant: 1.0E-6F
Definition: types.hpp:46
x
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
autoware::common::types::PointBlock
std::vector< PointXYZIF > PointBlock
Definition: types.hpp:67
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:37
autoware::common::types::PI
constexpr float32_t PI
pi = tau / 2
Definition: types.hpp:40