Apollo  6.0
Open source self driving car software
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
apollo::control::MPCController Class Reference

MPCController, combined lateral and longitudinal controllers. More...

#include <mpc_controller.h>

Inheritance diagram for apollo::control::MPCController:
Inheritance graph
Collaboration diagram for apollo::control::MPCController:
Collaboration graph

Public Member Functions

 MPCController ()
 constructor More...
 
virtual ~MPCController ()
 destructor More...
 
common::Status Init (std::shared_ptr< DependencyInjector > injector, const ControlConf *control_conf) override
 initialize MPC Controller More...
 
common::Status ComputeControlCommand (const localization::LocalizationEstimate *localization, const canbus::Chassis *chassis, const planning::ADCTrajectory *trajectory, ControlCommand *cmd) override
 compute steering target and throttle/ brake based on current vehicle status and target trajectory More...
 
common::Status Reset () override
 reset MPC Controller More...
 
void Stop () override
 stop MPC controller More...
 
std::string Name () const override
 MPC controller name. More...
 
- Public Member Functions inherited from apollo::control::Controller
 Controller ()=default
 constructor More...
 
virtual ~Controller ()=default
 destructor More...
 
virtual common::Status ComputeControlCommand (const localization::LocalizationEstimate *localization, const canbus::Chassis *chassis, const planning::ADCTrajectory *trajectory, control::ControlCommand *cmd)=0
 compute control command based on current vehicle status and target trajectory More...
 

Protected Member Functions

void UpdateState (SimpleMPCDebug *debug)
 
void UpdateMatrix (SimpleMPCDebug *debug)
 
void FeedforwardUpdate (SimpleMPCDebug *debug)
 
void ComputeLateralErrors (const double x, const double y, const double theta, const double linear_v, const double angular_v, const double linear_a, const TrajectoryAnalyzer &trajectory_analyzer, SimpleMPCDebug *debug)
 
void ComputeLongitudinalErrors (const TrajectoryAnalyzer *trajectory, SimpleMPCDebug *debug)
 
bool LoadControlConf (const ControlConf *control_conf)
 
void InitializeFilters (const ControlConf *control_conf)
 
void LogInitParameters ()
 
void ProcessLogs (const SimpleMPCDebug *debug, const canbus::Chassis *chassis)
 
void CloseLogFile ()
 
double Wheel2SteerPct (const double wheel_angle)
 
void LoadControlCalibrationTable (const MPCControllerConf &mpc_controller_conf)
 
void LoadMPCGainScheduler (const MPCControllerConf &mpc_controller_conf)
 

Protected Attributes

common::VehicleParam vehicle_param_
 
TrajectoryAnalyzer trajectory_analyzer_
 
std::unique_ptr< Interpolation2Dcontrol_interpolation_
 
double ts_ = 0.0
 
double cf_ = 0.0
 
double cr_ = 0.0
 
double wheelbase_ = 0.0
 
double mass_ = 0.0
 
double lf_ = 0.0
 
double lr_ = 0.0
 
double iz_ = 0.0
 
double steer_ratio_ = 0.0
 
double steer_single_direction_max_degree_ = 0.0
 
double wheel_single_direction_max_degree_ = 0.0
 
double max_lat_acc_ = 0.0
 
const int basic_state_size_ = 6
 
const int controls_ = 2
 
const int horizon_ = 10
 
Eigen::MatrixXd matrix_a_
 
Eigen::MatrixXd matrix_ad_
 
Eigen::MatrixXd matrix_b_
 
Eigen::MatrixXd matrix_bd_
 
Eigen::MatrixXd matrix_c_
 
Eigen::MatrixXd matrix_cd_
 
Eigen::MatrixXd matrix_k_
 
Eigen::MatrixXd matrix_r_
 
Eigen::MatrixXd matrix_r_updated_
 
Eigen::MatrixXd matrix_q_
 
Eigen::MatrixXd matrix_q_updated_
 
Eigen::MatrixXd matrix_a_coeff_
 
Eigen::MatrixXd matrix_state_
 
double previous_heading_error_ = 0.0
 
double previous_lateral_error_ = 0.0
 
double previous_lateral_acceleration_ = 0.0
 
double previous_heading_rate_ = 0.0
 
double previous_ref_heading_rate_ = 0.0
 
double previous_heading_acceleration_ = 0.0
 
double previous_ref_heading_acceleration_ = 0.0
 
double previous_acceleration_ = 0.0
 
double previous_acceleration_reference_ = 0.0
 
int mpc_max_iteration_ = 0
 
double mpc_eps_ = 0.0
 
common::DigitalFilter digital_filter_
 
std::unique_ptr< Interpolation1Dlat_err_interpolation_
 
std::unique_ptr< Interpolation1Dheading_err_interpolation_
 
std::unique_ptr< Interpolation1Dfeedforwardterm_interpolation_
 
std::unique_ptr< Interpolation1Dsteer_weight_interpolation_
 
std::ofstream mpc_log_file_
 
const std::string name_
 
double max_acceleration_when_stopped_ = 0.0
 
double max_abs_speed_when_stopped_ = 0.0
 
double standstill_acceleration_ = 0.0
 
double throttle_lowerbound_ = 0.0
 
double brake_lowerbound_ = 0.0
 
double steer_angle_feedforwardterm_ = 0.0
 
double steer_angle_feedforwardterm_updated_ = 0.0
 
double max_acceleration_ = 0.0
 
double max_deceleration_ = 0.0
 
common::MeanFilter lateral_error_filter_
 
common::MeanFilter heading_error_filter_
 
double minimum_speed_protection_ = 0.1
 
bool enable_mpc_feedforward_compensation_ = false
 
double unconstrained_control_diff_limit_ = 5.0
 
std::shared_ptr< DependencyInjectorinjector_
 

Detailed Description

MPCController, combined lateral and longitudinal controllers.

Constructor & Destructor Documentation

◆ MPCController()

apollo::control::MPCController::MPCController ( )

constructor

◆ ~MPCController()

virtual apollo::control::MPCController::~MPCController ( )
virtual

destructor

Member Function Documentation

◆ CloseLogFile()

void apollo::control::MPCController::CloseLogFile ( )
protected

◆ ComputeControlCommand()

common::Status apollo::control::MPCController::ComputeControlCommand ( const localization::LocalizationEstimate *  localization,
const canbus::Chassis *  chassis,
const planning::ADCTrajectory *  trajectory,
ControlCommand *  cmd 
)
override

compute steering target and throttle/ brake based on current vehicle status and target trajectory

Parameters
localizationvehicle location
chassisvehicle status e.g., speed, acceleration
trajectorytrajectory generated by planning
cmdcontrol command
Returns
Status computation status

◆ ComputeLateralErrors()

void apollo::control::MPCController::ComputeLateralErrors ( const double  x,
const double  y,
const double  theta,
const double  linear_v,
const double  angular_v,
const double  linear_a,
const TrajectoryAnalyzer trajectory_analyzer,
SimpleMPCDebug *  debug 
)
protected

◆ ComputeLongitudinalErrors()

void apollo::control::MPCController::ComputeLongitudinalErrors ( const TrajectoryAnalyzer trajectory,
SimpleMPCDebug *  debug 
)
protected

◆ FeedforwardUpdate()

void apollo::control::MPCController::FeedforwardUpdate ( SimpleMPCDebug *  debug)
protected

◆ Init()

common::Status apollo::control::MPCController::Init ( std::shared_ptr< DependencyInjector injector,
const ControlConf *  control_conf 
)
overridevirtual

initialize MPC Controller

Parameters
control_confcontrol configurations
Returns
Status initialization status

Implements apollo::control::Controller.

◆ InitializeFilters()

void apollo::control::MPCController::InitializeFilters ( const ControlConf *  control_conf)
protected

◆ LoadControlCalibrationTable()

void apollo::control::MPCController::LoadControlCalibrationTable ( const MPCControllerConf &  mpc_controller_conf)
protected

◆ LoadControlConf()

bool apollo::control::MPCController::LoadControlConf ( const ControlConf *  control_conf)
protected

◆ LoadMPCGainScheduler()

void apollo::control::MPCController::LoadMPCGainScheduler ( const MPCControllerConf &  mpc_controller_conf)
protected

◆ LogInitParameters()

void apollo::control::MPCController::LogInitParameters ( )
protected

◆ Name()

std::string apollo::control::MPCController::Name ( ) const
overridevirtual

MPC controller name.

Returns
string controller name in string

Implements apollo::control::Controller.

◆ ProcessLogs()

void apollo::control::MPCController::ProcessLogs ( const SimpleMPCDebug *  debug,
const canbus::Chassis *  chassis 
)
protected

◆ Reset()

common::Status apollo::control::MPCController::Reset ( )
overridevirtual

reset MPC Controller

Returns
Status reset status

Implements apollo::control::Controller.

◆ Stop()

void apollo::control::MPCController::Stop ( )
overridevirtual

stop MPC controller

Implements apollo::control::Controller.

◆ UpdateMatrix()

void apollo::control::MPCController::UpdateMatrix ( SimpleMPCDebug *  debug)
protected

◆ UpdateState()

void apollo::control::MPCController::UpdateState ( SimpleMPCDebug *  debug)
protected

◆ Wheel2SteerPct()

double apollo::control::MPCController::Wheel2SteerPct ( const double  wheel_angle)
protected

Member Data Documentation

◆ basic_state_size_

const int apollo::control::MPCController::basic_state_size_ = 6
protected

◆ brake_lowerbound_

double apollo::control::MPCController::brake_lowerbound_ = 0.0
protected

◆ cf_

double apollo::control::MPCController::cf_ = 0.0
protected

◆ control_interpolation_

std::unique_ptr<Interpolation2D> apollo::control::MPCController::control_interpolation_
protected

◆ controls_

const int apollo::control::MPCController::controls_ = 2
protected

◆ cr_

double apollo::control::MPCController::cr_ = 0.0
protected

◆ digital_filter_

common::DigitalFilter apollo::control::MPCController::digital_filter_
protected

◆ enable_mpc_feedforward_compensation_

bool apollo::control::MPCController::enable_mpc_feedforward_compensation_ = false
protected

◆ feedforwardterm_interpolation_

std::unique_ptr<Interpolation1D> apollo::control::MPCController::feedforwardterm_interpolation_
protected

◆ heading_err_interpolation_

std::unique_ptr<Interpolation1D> apollo::control::MPCController::heading_err_interpolation_
protected

◆ heading_error_filter_

common::MeanFilter apollo::control::MPCController::heading_error_filter_
protected

◆ horizon_

const int apollo::control::MPCController::horizon_ = 10
protected

◆ injector_

std::shared_ptr<DependencyInjector> apollo::control::MPCController::injector_
protected

◆ iz_

double apollo::control::MPCController::iz_ = 0.0
protected

◆ lat_err_interpolation_

std::unique_ptr<Interpolation1D> apollo::control::MPCController::lat_err_interpolation_
protected

◆ lateral_error_filter_

common::MeanFilter apollo::control::MPCController::lateral_error_filter_
protected

◆ lf_

double apollo::control::MPCController::lf_ = 0.0
protected

◆ lr_

double apollo::control::MPCController::lr_ = 0.0
protected

◆ mass_

double apollo::control::MPCController::mass_ = 0.0
protected

◆ matrix_a_

Eigen::MatrixXd apollo::control::MPCController::matrix_a_
protected

◆ matrix_a_coeff_

Eigen::MatrixXd apollo::control::MPCController::matrix_a_coeff_
protected

◆ matrix_ad_

Eigen::MatrixXd apollo::control::MPCController::matrix_ad_
protected

◆ matrix_b_

Eigen::MatrixXd apollo::control::MPCController::matrix_b_
protected

◆ matrix_bd_

Eigen::MatrixXd apollo::control::MPCController::matrix_bd_
protected

◆ matrix_c_

Eigen::MatrixXd apollo::control::MPCController::matrix_c_
protected

◆ matrix_cd_

Eigen::MatrixXd apollo::control::MPCController::matrix_cd_
protected

◆ matrix_k_

Eigen::MatrixXd apollo::control::MPCController::matrix_k_
protected

◆ matrix_q_

Eigen::MatrixXd apollo::control::MPCController::matrix_q_
protected

◆ matrix_q_updated_

Eigen::MatrixXd apollo::control::MPCController::matrix_q_updated_
protected

◆ matrix_r_

Eigen::MatrixXd apollo::control::MPCController::matrix_r_
protected

◆ matrix_r_updated_

Eigen::MatrixXd apollo::control::MPCController::matrix_r_updated_
protected

◆ matrix_state_

Eigen::MatrixXd apollo::control::MPCController::matrix_state_
protected

◆ max_abs_speed_when_stopped_

double apollo::control::MPCController::max_abs_speed_when_stopped_ = 0.0
protected

◆ max_acceleration_

double apollo::control::MPCController::max_acceleration_ = 0.0
protected

◆ max_acceleration_when_stopped_

double apollo::control::MPCController::max_acceleration_when_stopped_ = 0.0
protected

◆ max_deceleration_

double apollo::control::MPCController::max_deceleration_ = 0.0
protected

◆ max_lat_acc_

double apollo::control::MPCController::max_lat_acc_ = 0.0
protected

◆ minimum_speed_protection_

double apollo::control::MPCController::minimum_speed_protection_ = 0.1
protected

◆ mpc_eps_

double apollo::control::MPCController::mpc_eps_ = 0.0
protected

◆ mpc_log_file_

std::ofstream apollo::control::MPCController::mpc_log_file_
protected

◆ mpc_max_iteration_

int apollo::control::MPCController::mpc_max_iteration_ = 0
protected

◆ name_

const std::string apollo::control::MPCController::name_
protected

◆ previous_acceleration_

double apollo::control::MPCController::previous_acceleration_ = 0.0
protected

◆ previous_acceleration_reference_

double apollo::control::MPCController::previous_acceleration_reference_ = 0.0
protected

◆ previous_heading_acceleration_

double apollo::control::MPCController::previous_heading_acceleration_ = 0.0
protected

◆ previous_heading_error_

double apollo::control::MPCController::previous_heading_error_ = 0.0
protected

◆ previous_heading_rate_

double apollo::control::MPCController::previous_heading_rate_ = 0.0
protected

◆ previous_lateral_acceleration_

double apollo::control::MPCController::previous_lateral_acceleration_ = 0.0
protected

◆ previous_lateral_error_

double apollo::control::MPCController::previous_lateral_error_ = 0.0
protected

◆ previous_ref_heading_acceleration_

double apollo::control::MPCController::previous_ref_heading_acceleration_ = 0.0
protected

◆ previous_ref_heading_rate_

double apollo::control::MPCController::previous_ref_heading_rate_ = 0.0
protected

◆ standstill_acceleration_

double apollo::control::MPCController::standstill_acceleration_ = 0.0
protected

◆ steer_angle_feedforwardterm_

double apollo::control::MPCController::steer_angle_feedforwardterm_ = 0.0
protected

◆ steer_angle_feedforwardterm_updated_

double apollo::control::MPCController::steer_angle_feedforwardterm_updated_ = 0.0
protected

◆ steer_ratio_

double apollo::control::MPCController::steer_ratio_ = 0.0
protected

◆ steer_single_direction_max_degree_

double apollo::control::MPCController::steer_single_direction_max_degree_ = 0.0
protected

◆ steer_weight_interpolation_

std::unique_ptr<Interpolation1D> apollo::control::MPCController::steer_weight_interpolation_
protected

◆ throttle_lowerbound_

double apollo::control::MPCController::throttle_lowerbound_ = 0.0
protected

◆ trajectory_analyzer_

TrajectoryAnalyzer apollo::control::MPCController::trajectory_analyzer_
protected

◆ ts_

double apollo::control::MPCController::ts_ = 0.0
protected

◆ unconstrained_control_diff_limit_

double apollo::control::MPCController::unconstrained_control_diff_limit_ = 5.0
protected

◆ vehicle_param_

common::VehicleParam apollo::control::MPCController::vehicle_param_
protected

◆ wheel_single_direction_max_degree_

double apollo::control::MPCController::wheel_single_direction_max_degree_ = 0.0
protected

◆ wheelbase_

double apollo::control::MPCController::wheelbase_ = 0.0
protected

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