Autoware.Auto
constant_velocity.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.
16 
21 #ifndef MOTION_MODEL__CONSTANT_VELOCITY_HPP_
22 #define MOTION_MODEL__CONSTANT_VELOCITY_HPP_
23 
24 #include <common/types.hpp>
25 #include <chrono>
28 
30 
31 namespace autoware
32 {
33 namespace motion
34 {
35 namespace motion_model
36 {
38 class MOTION_MODEL_PUBLIC ConstantVelocity : public MotionModel<4U>
39 {
40 public:
44  ConstantVelocity & operator=(const ConstantVelocity & rhs);
46  struct States
47  {
48  static const index_t POSE_X = 0U;
49  static const index_t POSE_Y = 1U;
50  static const index_t VELOCITY_X = 2U;
51  static const index_t VELOCITY_Y = 3U;
52  }; // struct States
53 
62  void predict(
63  Eigen::Matrix<float32_t, 4U, 1U> & x,
64  const std::chrono::nanoseconds & dt) const override;
65 
72  void predict(const std::chrono::nanoseconds & dt) override;
73 
77  void compute_jacobian(
78  Eigen::Matrix<float32_t, 4U, 4U> & F,
79  const std::chrono::nanoseconds & dt) override;
80 
87  void compute_jacobian_and_predict(
88  Eigen::Matrix<float32_t, 4U, 4U> & F,
89  const std::chrono::nanoseconds & dt) override;
90 
94  float32_t operator[](const index_t idx) const override;
95 
98  void reset(const Eigen::Matrix<float32_t, 4U, 1U> & x) override;
99 
102  const Eigen::Matrix<float32_t, 4U, 1U> & get_state() const override;
103 
104 private:
105  Eigen::Matrix<float32_t, 4U, 1U> m_state;
106 }; // class ConstantVelocity
107 } // namespace motion_model
108 } // namespace motion
109 } // namespace autoware
110 
111 #endif // MOTION_MODEL__CONSTANT_VELOCITY_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::ConstantVelocity::States
This state gives named handles for state indexing.
Definition: constant_velocity.hpp:46
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::motion::motion_model::ConstantVelocity
This is a simple constant velocity motion model.
Definition: constant_velocity.hpp:38
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:36
motion
Definition: controller_base.hpp:30
visibility_control.hpp