Autoware.Auto
common_states.hpp
Go to the documentation of this file.
1 // Copyright 2021 Apex.AI, Inc.
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_STATES_HPP_
23 #define STATE_VECTOR__COMMON_STATES_HPP_
24 
25 #include <common/types.hpp>
28 
29 namespace autoware
30 {
31 namespace common
32 {
33 namespace state_vector
34 {
35 
41 template<typename ScalarT>
42 using ConstAccelerationXY =
43  GenericState<ScalarT,
48 
54 template<typename ScalarT>
56  GenericState<ScalarT,
62 
68 template<typename ScalarT>
70  GenericState<ScalarT,
76 
82 template<typename ScalarT>
84  GenericState<ScalarT,
91 
106 template<typename ScalarT>
108  GenericState<ScalarT,
117 
124 template<typename ScalarT>
126  GenericState<ScalarT,
132 
139 template<typename ScalarT>
141  GenericState<ScalarT,
146 
147 } // namespace state_vector
148 } // namespace common
149 } // namespace autoware
150 
151 #endif // STATE_VECTOR__COMMON_STATES_HPP_
autoware::common::state_vector::variable::YAW_CHANGE_ACCELERATION
Definition: common_variables.hpp:83
common_variables.hpp
This file defines the common variables used within the filter implementations.
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
types.hpp
This file includes common type definition.
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::GenericState
A representation of a generic state vectors with specified variables.
Definition: generic_state.hpp:60
autoware::common::state_vector::variable::YAW
A variable that represents the roll angle of an object.
Definition: common_variables.hpp:67
generic_state.hpp
This file defines a class for a generic state vector representation.
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::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