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 KALMAN_FILTER__COMMON_VARIABLES_HPP_
23 #define KALMAN_FILTER__COMMON_VARIABLES_HPP_
24 
26 
27 #include <type_traits>
28 
29 namespace autoware
30 {
31 namespace prediction
32 {
33 
34 namespace variable
35 {
36 struct X : Variable {};
37 struct Y : Variable {};
38 struct Z : Variable {};
39 struct ROLL : AngleVariable {};
40 struct PITCH : AngleVariable {};
41 struct YAW : AngleVariable {};
42 
43 struct X_VELOCITY : Variable {};
44 struct Y_VELOCITY : Variable {};
45 struct Z_VELOCITY : Variable {};
49 
56 
58 struct XY_VELOCITY : Variable {};
61 
62 } // namespace variable
63 
64 } // namespace prediction
65 } // namespace autoware
66 
67 #endif // KALMAN_FILTER__COMMON_VARIABLES_HPP_
autoware::prediction::variable::Y
Definition: common_variables.hpp:37
autoware::prediction::variable::YAW_CHANGE_ACCELERATION
Definition: common_variables.hpp:55
autoware::prediction::variable::ROLL_CHANGE_ACCELERATION
Definition: common_variables.hpp:53
autoware::prediction::variable::Z
Definition: common_variables.hpp:38
autoware::prediction::AngleVariable
A tag struct used to disambiguate variables that store angles from other types.
Definition: variable.hpp:45
variable.hpp
Contains base tag structs that define variables and traits to check if a type is one.
autoware::prediction::variable::YAW
Definition: common_variables.hpp:41
autoware::prediction::variable::PITCH
Definition: common_variables.hpp:40
autoware::prediction::variable::Y_VELOCITY
Definition: common_variables.hpp:44
autoware::prediction::variable::Y_ACCELERATION
Definition: common_variables.hpp:51
autoware::prediction::variable::Z_ACCELERATION
Definition: common_variables.hpp:52
autoware::prediction::variable::X_VELOCITY
Definition: common_variables.hpp:43
autoware::prediction::variable::X_ACCELERATION
Definition: common_variables.hpp:50
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::prediction::variable::PITCH_CHANGE_RATE
Definition: common_variables.hpp:47
autoware::prediction::variable::PITCH_CHANGE_ACCELERATION
Definition: common_variables.hpp:54
autoware::prediction::variable::ROLL_CHANGE_RATE
Definition: common_variables.hpp:46
autoware::prediction::variable::X
Definition: common_variables.hpp:36
autoware::prediction::variable::XY_VELOCITY
Velocity in xy plane. Used in differential drive models.
Definition: common_variables.hpp:58
autoware::prediction::Variable
A tag struct used to disambiguate variables from other types.
Definition: variable.hpp:38
autoware::prediction::variable::YAW_CHANGE_RATE
Definition: common_variables.hpp:48
autoware::prediction::variable::ROLL
Definition: common_variables.hpp:39
autoware::prediction::variable::XY_ACCELERATION
Acceleration in xy plane. Used in differential drive models.
Definition: common_variables.hpp:60
autoware::prediction::variable::Z_VELOCITY
Definition: common_variables.hpp:45