Autoware.Auto
common_states.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_STATES_HPP_
23 #define KALMAN_FILTER__COMMON_STATES_HPP_
24 
27 
28 namespace autoware
29 {
30 namespace prediction
31 {
32 namespace state
33 {
34 
40 using ConstAccelerationXY =
41  FloatState<
44 
51  FloatState<
55 
63  FloatState<
67 
75  FloatState<
78 
79 } // namespace state
80 } // namespace prediction
81 } // namespace autoware
82 
83 #endif // KALMAN_FILTER__COMMON_STATES_HPP_
common_variables.hpp
This file defines the common variables used within the filter implementations.
autoware::prediction::variable::Y
Definition: common_variables.hpp:37
autoware::prediction::variable::YAW_CHANGE_ACCELERATION
Definition: common_variables.hpp:55
autoware::prediction::variable::YAW
Definition: common_variables.hpp:41
autoware::prediction::variable::Y_VELOCITY
Definition: common_variables.hpp:44
autoware::prediction::variable::Y_ACCELERATION
Definition: common_variables.hpp:51
autoware::prediction::variable::X_VELOCITY
Definition: common_variables.hpp:43
autoware::prediction::variable::X_ACCELERATION
Definition: common_variables.hpp:50
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::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::YAW_CHANGE_RATE
Definition: common_variables.hpp:48
autoware::prediction::GenericState
A representation of a generic state vectors with specified variables.
Definition: generic_state.hpp:50
autoware::prediction::variable::XY_ACCELERATION
Acceleration in xy plane. Used in differential drive models.
Definition: common_variables.hpp:60