Autoware.Auto
motion_model_interface.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__MOTION_MODEL_INTERFACE_HPP_
23 #define MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
24 
27 
28 #include <chrono>
29 
30 namespace autoware
31 {
32 namespace prediction
33 {
34 
40 template<typename Derived>
41 class KALMAN_FILTER_PUBLIC MotionModelInterface : public common::helper_functions::crtp<Derived>
42 {
43 public:
54  template<typename StateT>
55  inline auto predict(const StateT & state, const std::chrono::nanoseconds & dt)
56  {
57  static_assert(is_state<StateT>::value, "\n\nStateT must be a GenericState\n\n");
58  return this->impl().crtp_predict(state, dt);
59  }
70  template<typename StateT>
71  inline auto jacobian(const StateT & state, const std::chrono::nanoseconds & dt) const
72  {
73  return this->impl().crtp_jacobian(state, dt);
74  }
75 };
76 
77 } // namespace prediction
78 } // namespace autoware
79 
80 #endif // MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
auto predict(const StateT &state, const std::chrono::nanoseconds &dt)
Get the next predicted state.
Definition: motion_model_interface.hpp:55
This file includes common helper functions.
auto jacobian(const StateT &state, const std::chrono::nanoseconds &dt) const
Get the Jacobian of this motion model.
Definition: motion_model_interface.hpp:71
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:41
This file defines a class for a generic state vector representation.
Forward-declare is_state trait.
Definition: generic_state.hpp:42
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24