Autoware.Auto
|
|
calculate model-related values More...
#include <vehicle_model_bicycle_dynamics.hpp>
Public Member Functions | |
DynamicsBicycleModel (const float64_t wheelbase, const float64_t mass_fl, const float64_t mass_fr, const float64_t mass_rl, const float64_t mass_rr, const float64_t cf, const float64_t cr) | |
constructor with parameter initialization More... | |
~DynamicsBicycleModel ()=default | |
destructor More... | |
void | calculateDiscreteMatrix (Eigen::MatrixXd &a_d, Eigen::MatrixXd &b_d, Eigen::MatrixXd &w_d, Eigen::MatrixXd &c_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... | |
calculate model-related values
Vehicle model class of bicycle dynamics
autoware::motion::control::trajectory_follower::DynamicsBicycleModel::DynamicsBicycleModel | ( | const float64_t | wheelbase, |
const float64_t | mass_fl, | ||
const float64_t | mass_fr, | ||
const float64_t | mass_rl, | ||
const float64_t | mass_rr, | ||
const float64_t | cf, | ||
const float64_t | cr | ||
) |
constructor with parameter initialization
[in] | wheelbase | wheelbase length [m] |
[in] | mass_fl | mass applied to front left tire [kg] |
[in] | mass_fr | mass applied to front right tire [kg] |
[in] | mass_rl | mass applied to rear left tire [kg] |
[in] | mass_rr | mass applied to rear right tire [kg] |
[in] | cf | front cornering power [N/rad] |
[in] | cr | rear cornering power [N/rad] |
|
default |
destructor
|
overridevirtual |
calculate discrete model matrix of x_k+1 = a_d * xk + b_d * uk + w_d, yk = c_d * xk
[in] | a_d | coefficient matrix |
[in] | b_d | coefficient matrix |
[in] | c_d | coefficient matrix |
[in] | w_d | coefficient matrix |
[in] | dt | Discretization time [s] |
Implements autoware::motion::control::trajectory_follower::VehicleModelInterface.
|
overridevirtual |
calculate reference input
[out] | u_ref | input |
Implements autoware::motion::control::trajectory_follower::VehicleModelInterface.