Autoware.Auto
autoware::motion::control::trajectory_follower::KinematicsBicycleModelNoDelay Class Reference

calculate model-related values More...

#include <vehicle_model_bicycle_kinematics_no_delay.hpp>

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

Public Member Functions

 KinematicsBicycleModelNoDelay (const float64_t wheelbase, const float64_t steer_lim)
 constructor with parameter initialization More...
 
 ~KinematicsBicycleModelNoDelay ()=default
 destructor More...
 
void calculateDiscreteMatrix (Eigen::MatrixXd &a_d, Eigen::MatrixXd &b_d, Eigen::MatrixXd &c_d, Eigen::MatrixXd &w_d, const float64_t dt) override
 calculate discrete model matrix of x_k+1 = a_d * xk + b_d * uk + w_d, yk = c_d * xk More...
 
void calculateReferenceInput (Eigen::MatrixXd &u_ref) override
 calculate reference input More...
 
- Public Member Functions inherited from autoware::motion::control::trajectory_follower::VehicleModelInterface
 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...
 

Additional Inherited Members

- Protected Attributes inherited from autoware::motion::control::trajectory_follower::VehicleModelInterface
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 of bicycle kinematics without steering delay

Constructor & Destructor Documentation

◆ KinematicsBicycleModelNoDelay()

autoware::motion::control::trajectory_follower::KinematicsBicycleModelNoDelay::KinematicsBicycleModelNoDelay ( const float64_t  wheelbase,
const float64_t  steer_lim 
)

constructor with parameter initialization

Parameters
[in]wheelbasewheelbase length [m]
[in]steer_limsteering angle limit [rad]

◆ ~KinematicsBicycleModelNoDelay()

autoware::motion::control::trajectory_follower::KinematicsBicycleModelNoDelay::~KinematicsBicycleModelNoDelay ( )
default

destructor

Member Function Documentation

◆ calculateDiscreteMatrix()

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

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]

Implements autoware::motion::control::trajectory_follower::VehicleModelInterface.

◆ calculateReferenceInput()

void autoware::motion::control::trajectory_follower::KinematicsBicycleModelNoDelay::calculateReferenceInput ( Eigen::MatrixXd &  u_ref)
overridevirtual

calculate reference input

Parameters
[out]u_refinput

Implements autoware::motion::control::trajectory_follower::VehicleModelInterface.


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