Autoware.Auto
autoware::motion::control::trajectory_follower::VehicleModelInterface Class Referenceabstract

calculate model-related values More...

#include <vehicle_model_interface.hpp>

Inheritance diagram for autoware::motion::control::trajectory_follower::VehicleModelInterface:
Collaboration diagram for autoware::motion::control::trajectory_follower::VehicleModelInterface:

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...
 

Detailed Description

calculate model-related values

Vehicle model class

Constructor & Destructor Documentation

◆ VehicleModelInterface()

autoware::motion::control::trajectory_follower::VehicleModelInterface::VehicleModelInterface ( int64_t  dim_x,
int64_t  dim_u,
int64_t  dim_y,
float64_t  wheelbase 
)

constructor

Parameters
[in]dim_xdimension of state x
[in]dim_udimension of input u
[in]dim_ydimension of output y
[in]wheelbasewheelbase of the vehicle [m]

◆ ~VehicleModelInterface()

virtual autoware::motion::control::trajectory_follower::VehicleModelInterface::~VehicleModelInterface ( )
virtualdefault

destructor

Member Function Documentation

◆ calculateDiscreteMatrix()

virtual void autoware::motion::control::trajectory_follower::VehicleModelInterface::calculateDiscreteMatrix ( Eigen::MatrixXd &  a_d,
Eigen::MatrixXd &  b_d,
Eigen::MatrixXd &  c_d,
Eigen::MatrixXd &  w_d,
const float64_t  dt 
)
pure virtual

calculate discrete model matrix of x_k+1 = a_d * xk + b_d * uk + w_d, yk = c_d * xk

Parameters
[out]a_dcoefficient matrix
[out]b_dcoefficient matrix
[out]c_dcoefficient matrix
[out]w_dcoefficient matrix
[in]dtDiscretization time [s]

Implemented in autoware::motion::control::trajectory_follower::DynamicsBicycleModel, autoware::motion::control::trajectory_follower::KinematicsBicycleModel, and autoware::motion::control::trajectory_follower::KinematicsBicycleModelNoDelay.

◆ calculateReferenceInput()

virtual void autoware::motion::control::trajectory_follower::VehicleModelInterface::calculateReferenceInput ( Eigen::MatrixXd &  u_ref)
pure virtual

◆ getDimU()

int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getDimU ( )

get input u dimension

Returns
input dimension

◆ getDimX()

int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getDimX ( )

get state x dimension

Returns
state dimension

◆ getDimY()

int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getDimY ( )

get output y dimension

Returns
output dimension

◆ getWheelbase()

float64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::getWheelbase ( )

get wheelbase of the vehicle

Returns
wheelbase value [m]

◆ setCurvature()

void autoware::motion::control::trajectory_follower::VehicleModelInterface::setCurvature ( const float64_t  curvature)

set curvature

Parameters
[in]curvaturecurvature on the linearized point on path

◆ setVelocity()

void autoware::motion::control::trajectory_follower::VehicleModelInterface::setVelocity ( const float64_t  velocity)

set velocity

Parameters
[in]velocityvehicle velocity

Member Data Documentation

◆ m_curvature

float64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::m_curvature
protected

curvature on the linearized point on path

◆ m_dim_u

const int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::m_dim_u
protected

dimension of input u

◆ m_dim_x

const int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::m_dim_x
protected

dimension of state x

◆ m_dim_y

const int64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::m_dim_y
protected

dimension of output y

◆ m_velocity

float64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::m_velocity
protected

vehicle velocity [m/s]

◆ m_wheelbase

float64_t autoware::motion::control::trajectory_follower::VehicleModelInterface::m_wheelbase
protected

wheelbase of the vehicle [m]


The documentation for this class was generated from the following files: