Autoware.Auto
motion_model_interface.hpp
Go to the documentation of this file.
1 // Copyright 2021 Apex.AI, Inc.
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 
17 #ifndef MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
18 #define MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
19 
23 
24 #include <chrono>
25 
26 namespace autoware
27 {
28 namespace common
29 {
30 namespace motion_model
31 {
32 
38 template<typename Derived>
39 class MOTION_MODEL_PUBLIC MotionModelInterface : public common::helper_functions::crtp<Derived>
40 {
41 public:
52  template<typename StateT>
53  inline auto predict(const StateT & state, const std::chrono::nanoseconds & dt) const
54  {
55  static_assert(
57  "\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  static_assert(
75  "\n\nStateT must be a GenericState\n\n");
76  return this->impl().crtp_jacobian(state, dt);
77  }
78 };
79 
80 } // namespace motion_model
81 } // namespace common
82 } // namespace autoware
83 
84 #endif // MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
autoware::common::state_vector::is_state
Forward-declare is_state trait.
Definition: generic_state.hpp:51
generic_state.hpp
This file defines a class for a generic state vector representation.
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::motion_model::MotionModelInterface::jacobian
auto jacobian(const StateT &state, const std::chrono::nanoseconds &dt) const
Get the Jacobian of this motion model.
Definition: motion_model_interface.hpp:71
autoware::common::helper_functions::crtp
Definition: crtp.hpp:29
autoware::common::motion_model::MotionModelInterface::predict
auto predict(const StateT &state, const std::chrono::nanoseconds &dt) const
Get the next predicted state.
Definition: motion_model_interface.hpp:53
crtp.hpp
This file includes common helper functions.
autoware::common::motion_model::MotionModelInterface
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:39
visibility_control.hpp