Go to the documentation of this file.
22 #ifndef MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
23 #define MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
40 template<
typename Derived>
54 template<
typename StateT>
55 inline auto predict(
const StateT & state,
const std::chrono::nanoseconds & dt)
const
58 return this->impl().crtp_predict(state, dt);
70 template<
typename StateT>
71 inline auto jacobian(
const StateT & state,
const std::chrono::nanoseconds & dt)
const
73 return this->impl().crtp_jacobian(state, dt);
80 #endif // MOTION_MODEL__MOTION_MODEL_INTERFACE_HPP_
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
Forward-declare is_state trait.
Definition: generic_state.hpp:42
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
This file includes common helper functions.
auto predict(const StateT &state, const std::chrono::nanoseconds &dt) const
Get the next predicted state.
Definition: motion_model_interface.hpp:55