Go to the documentation of this file.
22 #ifndef MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
23 #define MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
44 template<
typename StateT>
65 const std::chrono::nanoseconds & dt)
const
67 return State{crtp_jacobian(state, dt) * state.vector()};
75 "\n\nThis function must be specialized for specific states.\n\n");
91 const State & state,
const std::chrono::nanoseconds & dt)
const;
104 const State & state,
const std::chrono::nanoseconds & dt)
const;
109 #endif // MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
Eigen::Matrix< ScalarT, kSize, kSize > Matrix
Definition: generic_state.hpp:65
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:63
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:41
This file defines an interface for the motion model.
This file defines a class for a generic state vector representation.
autoware_auto_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:36
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
A generic linear motion model class.
Definition: linear_motion_model.hpp:45
StateT State
Definition: linear_motion_model.hpp:49
State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
A crtp-called function that computes a Jacobian.
Definition: linear_motion_model.hpp:71
This file holds a collection of states that are commonly used in this package.