Autoware.Auto
catr_model.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__CATR_MODEL_HPP_
22 #define MOTION_MODEL__CATR_MODEL_HPP_
23 
24 #include <common/types.hpp>
25 #include <chrono>
29 
31 
32 namespace autoware
33 {
34 namespace motion
35 {
36 namespace motion_model
37 {
41 class MOTION_MODEL_PUBLIC CatrModel : public MotionModel<6U>
42 {
43 public:
47  CatrModel & operator=(const CatrModel & rhs);
56  void predict(
57  Eigen::Matrix<float32_t, 6U, 1U> & x,
58  const std::chrono::nanoseconds & dt) const override;
59 
66  void predict(const std::chrono::nanoseconds & dt) override;
67 
71  void compute_jacobian(
72  Eigen::Matrix<float32_t, 6U, 6U> & F,
73  const std::chrono::nanoseconds & dt) override;
74 
81  void compute_jacobian_and_predict(
82  Eigen::Matrix<float32_t, 6U, 6U> & F,
83  const std::chrono::nanoseconds & dt) override;
84 
88  float32_t operator[](const index_t idx) const override;
89 
92  void reset(const Eigen::Matrix<float32_t, 6U, 1U> & x) override;
93 
96  const Eigen::Matrix<float32_t, 6U, 1U> & get_state() const override;
97 
98 private:
99  Eigen::Matrix<float32_t, 6U, 1U> m_state;
100  CatrInvariantWorkspace m_invariants;
101  mutable CatrVariantWorkspace m_variants;
102 }; // class ConstantVelocity
103 } // namespace motion_model
104 } // namespace motion
105 } // namespace autoware
106 
107 #endif // MOTION_MODEL__CATR_MODEL_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
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::motion::motion_model::CatrVariantWorkspace
This struct holds some common worker variables for CATR model's jacobian and prediction computation,...
Definition: catr_core.hpp:54
autoware::motion::motion_model::CatrModel
This is a constant acceleration, constant turn-rate motion model. This model produces clothoidal traj...
Definition: catr_model.hpp:41
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
catr_core.hpp
This file defines the constant velocity motion model.
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
motion
Definition: controller_base.hpp:30
visibility_control.hpp
autoware::motion::motion_model::CatrInvariantWorkspace
This struct holds some common worker variables for CATR model's jacobian and prediction computation,...
Definition: catr_core.hpp:40