Autoware.Auto
common_variables.hpp
Go to the documentation of this file.
1 // Copyright 2021 the Autoware Foundation
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 // Developed by Apex.AI, Inc.
16 
21 
22 #ifndef STATE_VECTOR__COMMON_VARIABLES_HPP_
23 #define STATE_VECTOR__COMMON_VARIABLES_HPP_
24 
26 
27 #include <type_traits>
28 
29 namespace autoware
30 {
31 namespace common
32 {
33 namespace state_vector
34 {
35 
36 namespace variable
37 {
38 struct X : Variable {};
39 struct Y : Variable {};
40 struct Z : Variable {};
41 
49 struct ROLL : AngleVariable {};
50 
58 struct PITCH : AngleVariable {};
59 
67 struct YAW : AngleVariable {};
68 
69 struct X_VELOCITY : Variable {};
70 struct Y_VELOCITY : Variable {};
71 struct Z_VELOCITY : Variable {};
72 
76 
80 
84 
86 struct XY_VELOCITY : Variable {};
89 
90 } // namespace variable
91 
92 } // namespace state_vector
93 } // namespace common
94 } // namespace autoware
95 
96 #endif // STATE_VECTOR__COMMON_VARIABLES_HPP_
autoware::common::state_vector::variable::YAW_CHANGE_ACCELERATION
Definition: common_variables.hpp:83
autoware::common::state_vector::AngleVariable
A tag struct used to disambiguate variables that store angles from other types.
Definition: variable.hpp:47
autoware::common::state_vector::variable::X_VELOCITY
Definition: common_variables.hpp:69
autoware::common::state_vector::variable::XY_ACCELERATION
Acceleration in xy plane. Used in differential drive models.
Definition: common_variables.hpp:88
autoware::common::state_vector::variable::PITCH_CHANGE_ACCELERATION
Definition: common_variables.hpp:82
autoware::common::state_vector::variable::Z
Definition: common_variables.hpp:40
autoware::common::state_vector::variable::YAW
A variable that represents the roll angle of an object.
Definition: common_variables.hpp:67
variable.hpp
Contains base tag structs that define variables and traits to check if a type is one.
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::state_vector::variable::Z_VELOCITY
Definition: common_variables.hpp:71
autoware::common::state_vector::variable::Y
Definition: common_variables.hpp:39
autoware::common::state_vector::Variable
A tag struct used to disambiguate variables from other types.
Definition: variable.hpp:40
autoware::common::state_vector::variable::PITCH
A variable that represents the pitch angle of an object.
Definition: common_variables.hpp:58
autoware::common::state_vector::variable::Z_ACCELERATION
Definition: common_variables.hpp:79
autoware::common::state_vector::variable::PITCH_CHANGE_RATE
Definition: common_variables.hpp:74
autoware::common::state_vector::variable::X
Definition: common_variables.hpp:38
autoware::common::state_vector::variable::X_ACCELERATION
Definition: common_variables.hpp:77
autoware::common::state_vector::variable::ROLL_CHANGE_ACCELERATION
Definition: common_variables.hpp:81
autoware::common::state_vector::variable::Y_ACCELERATION
Definition: common_variables.hpp:78
autoware::common::state_vector::variable::ROLL
A variable that represents the roll angle of an object.
Definition: common_variables.hpp:49
autoware::common::state_vector::variable::ROLL_CHANGE_RATE
Definition: common_variables.hpp:73
autoware::common::state_vector::variable::Y_VELOCITY
Definition: common_variables.hpp:70
autoware::common::state_vector::variable::XY_VELOCITY
Velocity in xy plane. Used in differential drive models.
Definition: common_variables.hpp:86
autoware::common::state_vector::variable::YAW_CHANGE_RATE
Definition: common_variables.hpp:75