Autoware.Auto
|
|
calculate model-related values More...
#include <vehicle_model_interface.hpp>
Public Member Functions | |
VehicleModelInterface (int64_t dim_x, int64_t dim_u, int64_t dim_y, float64_t wheelbase) | |
constructor More... | |
virtual | ~VehicleModelInterface ()=default |
destructor More... | |
int64_t | getDimX () |
get state x dimension More... | |
int64_t | getDimU () |
get input u dimension More... | |
int64_t | getDimY () |
get output y dimension More... | |
float64_t | getWheelbase () |
get wheelbase of the vehicle More... | |
void | setVelocity (const float64_t velocity) |
set velocity More... | |
void | setCurvature (const float64_t curvature) |
set curvature More... | |
virtual void | calculateDiscreteMatrix (Eigen::MatrixXd &a_d, Eigen::MatrixXd &b_d, Eigen::MatrixXd &c_d, Eigen::MatrixXd &w_d, const float64_t dt)=0 |
calculate discrete model matrix of x_k+1 = a_d * xk + b_d * uk + w_d, yk = c_d * xk More... | |
virtual void | calculateReferenceInput (Eigen::MatrixXd &u_ref)=0 |
calculate reference input More... | |
Protected Attributes | |
const int64_t | m_dim_x |
dimension of state x More... | |
const int64_t | m_dim_u |
dimension of input u More... | |
const int64_t | m_dim_y |
dimension of output y More... | |
float64_t | m_velocity |
vehicle velocity [m/s] More... | |
float64_t | m_curvature |
curvature on the linearized point on path More... | |
float64_t | m_wheelbase |
wheelbase of the vehicle [m] More... | |
calculate model-related values
Vehicle model class
autoware::motion::control::trajectory_follower::VehicleModelInterface::VehicleModelInterface | ( | int64_t | dim_x, |
int64_t | dim_u, | ||
int64_t | dim_y, | ||
float64_t | wheelbase | ||
) |
constructor
[in] | dim_x | dimension of state x |
[in] | dim_u | dimension of input u |
[in] | dim_y | dimension of output y |
[in] | wheelbase | wheelbase of the vehicle [m] |
|
virtualdefault |
destructor
|
pure virtual |
calculate discrete model matrix of x_k+1 = a_d * xk + b_d * uk + w_d, yk = c_d * xk
[out] | a_d | coefficient matrix |
[out] | b_d | coefficient matrix |
[out] | c_d | coefficient matrix |
[out] | w_d | coefficient matrix |
[in] | dt | Discretization time [s] |
Implemented in autoware::motion::control::trajectory_follower::DynamicsBicycleModel, autoware::motion::control::trajectory_follower::KinematicsBicycleModel, and autoware::motion::control::trajectory_follower::KinematicsBicycleModelNoDelay.
|
pure virtual |
calculate reference input
[out] | u_ref | input |
Implemented in autoware::motion::control::trajectory_follower::DynamicsBicycleModel, autoware::motion::control::trajectory_follower::KinematicsBicycleModel, and autoware::motion::control::trajectory_follower::KinematicsBicycleModelNoDelay.
int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getDimU | ( | ) |
get input u dimension
int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getDimX | ( | ) |
get state x dimension
int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getDimY | ( | ) |
get output y dimension
float64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getWheelbase | ( | ) |
get wheelbase of the vehicle
void autoware::motion::control::trajectory_follower::VehicleModelInterface::setCurvature | ( | const float64_t | curvature | ) |
set curvature
[in] | curvature | curvature on the linearized point on path |
void autoware::motion::control::trajectory_follower::VehicleModelInterface::setVelocity | ( | const float64_t | velocity | ) |
set velocity
[in] | velocity | vehicle velocity |
|
protected |
curvature on the linearized point on path
|
protected |
dimension of input u
|
protected |
dimension of state x
|
protected |
dimension of output y
|
protected |
vehicle velocity [m/s]
|
protected |
wheelbase of the vehicle [m]