Autoware.Auto
linear_motion_model.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 MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
23 #define MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
24 
29 
30 namespace autoware
31 {
32 namespace prediction
33 {
34 
44 template<typename StateT>
45 class KALMAN_FILTER_PUBLIC LinearMotionModel
46  : public MotionModelInterface<LinearMotionModel<StateT>>
47 {
48 public:
49  using State = StateT;
50 
51 protected:
52  // Allow the CRTP interface to call private functions.
54 
64  const State & state,
65  const std::chrono::nanoseconds & dt) const
66  {
67  return State{crtp_jacobian(state, dt) * state.vector()};
68  }
69 
71  typename State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
72  {
73  static_assert(
74  sizeof(StateT) == 0U,
75  "\n\nThis function must be specialized for specific states.\n\n");
76  }
77 };
78 
79 
88 template<>
89 KALMAN_FILTER_PUBLIC state::ConstAccelerationXYYaw::Matrix
91  const State & state, const std::chrono::nanoseconds & dt) const;
92 
101 template<>
102 KALMAN_FILTER_PUBLIC state::ConstAccelerationXY::Matrix
104  const State & state, const std::chrono::nanoseconds & dt) const;
105 
106 } // namespace prediction
107 } // namespace autoware
108 
109 #endif // MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
This file defines an interface for the motion model.
StateT State
Definition: linear_motion_model.hpp:49
This file holds a collection of states that are commonly used in this package.
A generic linear motion model class.
Definition: linear_motion_model.hpp:45
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:41
State crtp_predict(const State &state, const std::chrono::nanoseconds &dt) const
A crtp-called function that predicts the state forward.
Definition: linear_motion_model.hpp:63
Eigen::Matrix< ScalarT, kSize, kSize > Matrix
Definition: generic_state.hpp:65
State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
A crtp-called function that computes a Jacobian.
Definition: linear_motion_model.hpp:71
This file defines a class for a generic state vector representation.
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24