Go to the documentation of this file.
17 #ifndef MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
18 #define MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
29 namespace motion_model
41 template<
typename StateT>
62 const std::chrono::nanoseconds & dt)
const
64 return State{crtp_jacobian(state, dt) * state.vector()};
76 typename State::Matrix crtp_jacobian(
const State &,
const std::chrono::nanoseconds & dt)
const;
83 #endif // MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
autoware_auto_vehicle_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:40
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 crtp_predict(const State &state, const std::chrono::nanoseconds &dt) const
A crtp-called function that predicts the state forward.
Definition: linear_motion_model.hpp:60
StateT State
Definition: linear_motion_model.hpp:46
A generic linear motion model class.
Definition: linear_motion_model.hpp:42
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:39
This file holds a collection of states that are commonly used in this package.