A CRTP interface for any motion model.
More...
#include <motion_model_interface.hpp>
|
| template<typename StateT > |
| auto | predict (const StateT &state, const std::chrono::nanoseconds &dt) |
| | Get the next predicted state. More...
|
| |
| template<typename StateT > |
| auto | jacobian (const StateT &state, const std::chrono::nanoseconds &dt) const |
| | Get the Jacobian of this motion model. More...
|
| |
|
| const Derived & | impl () const |
| |
| Derived & | impl () |
| |
template<typename Derived>
class autoware::prediction::MotionModelInterface< Derived >
A CRTP interface for any motion model.
- Template Parameters
-
| Derived | Motion model implementation class. |
◆ jacobian()
template<typename Derived>
template<typename StateT >
Get the Jacobian of this motion model.
- Parameters
-
| [in] | state | The current state. |
| [in] | dt | Time span. |
- Template Parameters
-
- Returns
- A Jacobian of the motion model. In the linear case - a transition matrix.
◆ predict()
template<typename Derived>
template<typename StateT >
Get the next predicted state.
- Parameters
-
| [in] | state | The initial state |
| [in] | dt | Length of prediction into the future |
- Template Parameters
-
- Returns
- Predicted state after the time has passed.
The documentation for this class was generated from the following file: