Go to the documentation of this file.
17 #ifndef MOTION_MODEL__STATIONARY_MOTION_MODEL_HPP_
18 #define MOTION_MODEL__STATIONARY_MOTION_MODEL_HPP_
29 namespace motion_model
38 template<
typename StateT>
58 const std::chrono::nanoseconds &)
const
70 return Eigen::Matrix<
typename State::Scalar, State::size(), State::size()>::Identity();
78 #endif // MOTION_MODEL__STATIONARY_MOTION_MODEL_HPP_
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
State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
A crtp-called function that computes a Jacobian for the stationary motion model.
Definition: stationary_motion_model.hpp:68
This class describes a stationary motion model, i.e., the model that does not change the state.
Definition: stationary_motion_model.hpp:39
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:39
StateT State
Definition: stationary_motion_model.hpp:43
const State & crtp_predict(const State &state, const std::chrono::nanoseconds &) const
A crtp-called function that predicts the state forward.
Definition: stationary_motion_model.hpp:56
This file holds a collection of states that are commonly used in this package.