Autoware.Auto
constant_acceleration.hpp
Go to the documentation of this file.
1 // Copyright 2018 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 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
18 #ifndef MOTION_MODEL__CONSTANT_ACCELERATION_HPP_
19 #define MOTION_MODEL__CONSTANT_ACCELERATION_HPP_
20 
21 #include <common/types.hpp>
22 #include <chrono>
25 
27 
28 namespace autoware
29 {
30 namespace motion
31 {
32 namespace motion_model
33 {
35 class MOTION_MODEL_PUBLIC ConstantAcceleration : public MotionModel<6U>
36 {
37 public:
41  ConstantAcceleration & operator=(const ConstantAcceleration & rhs);
42  ConstantAcceleration & operator=(ConstantAcceleration && rhs) noexcept = default;
43  ConstantAcceleration(const ConstantAcceleration & rhs) = default;
44  ConstantAcceleration(ConstantAcceleration && rhs) noexcept = default;
45  ConstantAcceleration() = default;
47  struct States
48  {
49  static const index_t POSE_X = 0U;
50  static const index_t POSE_Y = 1U;
51  static const index_t VELOCITY_X = 2U;
52  static const index_t VELOCITY_Y = 3U;
53  static const index_t ACCELERATION_X = 4U;
54  static const index_t ACCELERATION_Y = 5U;
55  }; // struct States
56 
65  void predict(
66  Eigen::Matrix<float32_t, 6U, 1U> & x,
67  const std::chrono::nanoseconds & dt) const override;
68 
75  void predict(const std::chrono::nanoseconds & dt) override;
76 
80  void compute_jacobian(
81  Eigen::Matrix<float32_t, 6U, 6U> & F,
82  const std::chrono::nanoseconds & dt) override;
83 
90  void compute_jacobian_and_predict(
91  Eigen::Matrix<float32_t, 6U, 6U> & F,
92  const std::chrono::nanoseconds & dt) override;
93 
97  float32_t operator[](const index_t idx) const override;
98 
101  void reset(const Eigen::Matrix<float32_t, 6U, 1U> & x) override;
102 
105  const Eigen::Matrix<float32_t, 6U, 1U> & get_state() const override;
106 
107 private:
108  Eigen::Matrix<float32_t, 6U, 1U> m_state{Eigen::Matrix<float32_t, 6U, 1U>::Zero()};
109 }; // class ConstantAcceleration
110 } // namespace motion_model
111 } // namespace motion
112 } // namespace autoware
113 
114 #endif // MOTION_MODEL__CONSTANT_ACCELERATION_HPP_
motion_model.hpp
This file defines the motion model interface used by kalman filters.
types.hpp
This file includes common type definition.
autoware::motion::motion_model::index_t
Eigen::Index index_t
indexing matches what matrices use
Definition: motion_model.hpp:41
autoware::motion::motion_model::ConstantAcceleration::States
This state gives named handles for state indexing.
Definition: constant_acceleration.hpp:47
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::motion::motion_model::MotionModel
Virtual interface for all motion models for use with prediction.
Definition: motion_model.hpp:46
x
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
motion
Definition: controller_base.hpp:30
autoware::motion::motion_model::ConstantAcceleration
This is a simple constant acceleration motion model.
Definition: constant_acceleration.hpp:35
visibility_control.hpp