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

LQR-Based lateral controller, to compute steering target. For more details, please refer to "Vehicle dynamics and control." Rajamani, Rajesh. Springer Science & Business Media, 2011. More...

#include <lat_controller.h>

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

Public Member Functions

 LatController ()
 constructor More...
 
virtual ~LatController ()
 destructor More...
 
common::Status Init (std::shared_ptr< DependencyInjector > injector, const ControlConf *control_conf) override
 initialize Lateral Controller More...
 
common::Status ComputeControlCommand (const localization::LocalizationEstimate *localization, const canbus::Chassis *chassis, const planning::ADCTrajectory *trajectory, ControlCommand *cmd) override
 compute steering target based on current vehicle status and target trajectory More...
 
common::Status Reset () override
 reset Lateral Controller More...
 
void Stop () override
 stop Lateral controller More...
 
std::string Name () const override
 Lateral 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 (SimpleLateralDebug *debug)
 
void UpdateDrivingOrientation ()
 
void UpdateMatrix ()
 
void UpdateMatrixCompound ()
 
double ComputeFeedForward (double ref_curvature) const
 
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, SimpleLateralDebug *debug)
 
bool LoadControlConf (const ControlConf *control_conf)
 
void InitializeFilters (const ControlConf *control_conf)
 
void LoadLatGainScheduler (const LatControllerConf &lat_controller_conf)
 
void LogInitParameters ()
 
void ProcessLogs (const SimpleLateralDebug *debug, const canbus::Chassis *chassis)
 
void CloseLogFile ()
 

Protected Attributes

const ControlConf * control_conf_ = nullptr
 
common::VehicleParam vehicle_param_
 
TrajectoryAnalyzer trajectory_analyzer_
 
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 max_lat_acc_ = 0.0
 
int preview_window_ = 0
 
double lookahead_station_low_speed_ = 0.0
 
double lookback_station_low_speed_ = 0.0
 
double lookahead_station_high_speed_ = 0.0
 
double lookback_station_high_speed_ = 0.0
 
const int basic_state_size_ = 4
 
Eigen::MatrixXd matrix_a_
 
Eigen::MatrixXd matrix_ad_
 
Eigen::MatrixXd matrix_adc_
 
Eigen::MatrixXd matrix_b_
 
Eigen::MatrixXd matrix_bd_
 
Eigen::MatrixXd matrix_bdc_
 
Eigen::MatrixXd matrix_k_
 
Eigen::MatrixXd matrix_r_
 
Eigen::MatrixXd matrix_q_
 
Eigen::MatrixXd matrix_q_updated_
 
Eigen::MatrixXd matrix_a_coeff_
 
Eigen::MatrixXd matrix_state_
 
int lqr_max_iteration_ = 0
 
double lqr_eps_ = 0.0
 
common::DigitalFilter digital_filter_
 
std::unique_ptr< Interpolation1Dlat_err_interpolation_
 
std::unique_ptr< Interpolation1Dheading_err_interpolation_
 
common::MeanFilter lateral_error_filter_
 
common::MeanFilter heading_error_filter_
 
bool enable_leadlag_ = false
 
LeadlagController leadlag_controller_
 
bool enable_mrac_ = false
 
MracController mrac_controller_
 
bool enable_look_ahead_back_control_ = false
 
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
 
std::ofstream steer_log_file_
 
const std::string name_
 
double query_relative_time_
 
double pre_steer_angle_ = 0.0
 
double pre_steering_position_ = 0.0
 
double minimum_speed_protection_ = 0.1
 
double current_trajectory_timestamp_ = -1.0
 
double init_vehicle_x_ = 0.0
 
double init_vehicle_y_ = 0.0
 
double init_vehicle_heading_ = 0.0
 
double low_speed_bound_ = 0.0
 
double low_speed_window_ = 0.0
 
double driving_orientation_ = 0.0
 
std::shared_ptr< DependencyInjectorinjector_
 

Detailed Description

LQR-Based lateral controller, to compute steering target. For more details, please refer to "Vehicle dynamics and control." Rajamani, Rajesh. Springer Science & Business Media, 2011.

Constructor & Destructor Documentation

◆ LatController()

apollo::control::LatController::LatController ( )

constructor

◆ ~LatController()

virtual apollo::control::LatController::~LatController ( )
virtual

destructor

Member Function Documentation

◆ CloseLogFile()

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

◆ ComputeControlCommand()

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

compute steering target 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

◆ ComputeFeedForward()

double apollo::control::LatController::ComputeFeedForward ( double  ref_curvature) const
protected

◆ ComputeLateralErrors()

void apollo::control::LatController::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,
SimpleLateralDebug *  debug 
)
protected

◆ Init()

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

initialize Lateral Controller

Parameters
control_confcontrol configurations
Returns
Status initialization status

Implements apollo::control::Controller.

◆ InitializeFilters()

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

◆ LoadControlConf()

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

◆ LoadLatGainScheduler()

void apollo::control::LatController::LoadLatGainScheduler ( const LatControllerConf &  lat_controller_conf)
protected

◆ LogInitParameters()

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

◆ Name()

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

Lateral controller name.

Returns
string controller name in string

Implements apollo::control::Controller.

◆ ProcessLogs()

void apollo::control::LatController::ProcessLogs ( const SimpleLateralDebug *  debug,
const canbus::Chassis *  chassis 
)
protected

◆ Reset()

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

reset Lateral Controller

Returns
Status reset status

Implements apollo::control::Controller.

◆ Stop()

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

stop Lateral controller

Implements apollo::control::Controller.

◆ UpdateDrivingOrientation()

void apollo::control::LatController::UpdateDrivingOrientation ( )
protected

◆ UpdateMatrix()

void apollo::control::LatController::UpdateMatrix ( )
protected

◆ UpdateMatrixCompound()

void apollo::control::LatController::UpdateMatrixCompound ( )
protected

◆ UpdateState()

void apollo::control::LatController::UpdateState ( SimpleLateralDebug *  debug)
protected

Member Data Documentation

◆ basic_state_size_

const int apollo::control::LatController::basic_state_size_ = 4
protected

◆ cf_

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

◆ control_conf_

const ControlConf* apollo::control::LatController::control_conf_ = nullptr
protected

◆ cr_

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

◆ current_trajectory_timestamp_

double apollo::control::LatController::current_trajectory_timestamp_ = -1.0
protected

◆ digital_filter_

common::DigitalFilter apollo::control::LatController::digital_filter_
protected

◆ driving_orientation_

double apollo::control::LatController::driving_orientation_ = 0.0
protected

◆ enable_leadlag_

bool apollo::control::LatController::enable_leadlag_ = false
protected

◆ enable_look_ahead_back_control_

bool apollo::control::LatController::enable_look_ahead_back_control_ = false
protected

◆ enable_mrac_

bool apollo::control::LatController::enable_mrac_ = false
protected

◆ heading_err_interpolation_

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

◆ heading_error_filter_

common::MeanFilter apollo::control::LatController::heading_error_filter_
protected

◆ init_vehicle_heading_

double apollo::control::LatController::init_vehicle_heading_ = 0.0
protected

◆ init_vehicle_x_

double apollo::control::LatController::init_vehicle_x_ = 0.0
protected

◆ init_vehicle_y_

double apollo::control::LatController::init_vehicle_y_ = 0.0
protected

◆ injector_

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

◆ iz_

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

◆ lat_err_interpolation_

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

◆ lateral_error_filter_

common::MeanFilter apollo::control::LatController::lateral_error_filter_
protected

◆ leadlag_controller_

LeadlagController apollo::control::LatController::leadlag_controller_
protected

◆ lf_

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

◆ lookahead_station_high_speed_

double apollo::control::LatController::lookahead_station_high_speed_ = 0.0
protected

◆ lookahead_station_low_speed_

double apollo::control::LatController::lookahead_station_low_speed_ = 0.0
protected

◆ lookback_station_high_speed_

double apollo::control::LatController::lookback_station_high_speed_ = 0.0
protected

◆ lookback_station_low_speed_

double apollo::control::LatController::lookback_station_low_speed_ = 0.0
protected

◆ low_speed_bound_

double apollo::control::LatController::low_speed_bound_ = 0.0
protected

◆ low_speed_window_

double apollo::control::LatController::low_speed_window_ = 0.0
protected

◆ lqr_eps_

double apollo::control::LatController::lqr_eps_ = 0.0
protected

◆ lqr_max_iteration_

int apollo::control::LatController::lqr_max_iteration_ = 0
protected

◆ lr_

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

◆ mass_

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

◆ matrix_a_

Eigen::MatrixXd apollo::control::LatController::matrix_a_
protected

◆ matrix_a_coeff_

Eigen::MatrixXd apollo::control::LatController::matrix_a_coeff_
protected

◆ matrix_ad_

Eigen::MatrixXd apollo::control::LatController::matrix_ad_
protected

◆ matrix_adc_

Eigen::MatrixXd apollo::control::LatController::matrix_adc_
protected

◆ matrix_b_

Eigen::MatrixXd apollo::control::LatController::matrix_b_
protected

◆ matrix_bd_

Eigen::MatrixXd apollo::control::LatController::matrix_bd_
protected

◆ matrix_bdc_

Eigen::MatrixXd apollo::control::LatController::matrix_bdc_
protected

◆ matrix_k_

Eigen::MatrixXd apollo::control::LatController::matrix_k_
protected

◆ matrix_q_

Eigen::MatrixXd apollo::control::LatController::matrix_q_
protected

◆ matrix_q_updated_

Eigen::MatrixXd apollo::control::LatController::matrix_q_updated_
protected

◆ matrix_r_

Eigen::MatrixXd apollo::control::LatController::matrix_r_
protected

◆ matrix_state_

Eigen::MatrixXd apollo::control::LatController::matrix_state_
protected

◆ max_lat_acc_

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

◆ minimum_speed_protection_

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

◆ mrac_controller_

MracController apollo::control::LatController::mrac_controller_
protected

◆ name_

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

◆ pre_steer_angle_

double apollo::control::LatController::pre_steer_angle_ = 0.0
protected

◆ pre_steering_position_

double apollo::control::LatController::pre_steering_position_ = 0.0
protected

◆ preview_window_

int apollo::control::LatController::preview_window_ = 0
protected

◆ previous_heading_acceleration_

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

◆ previous_heading_rate_

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

◆ previous_lateral_acceleration_

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

◆ previous_ref_heading_acceleration_

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

◆ previous_ref_heading_rate_

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

◆ query_relative_time_

double apollo::control::LatController::query_relative_time_
protected

◆ steer_log_file_

std::ofstream apollo::control::LatController::steer_log_file_
protected

◆ steer_ratio_

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

◆ steer_single_direction_max_degree_

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

◆ trajectory_analyzer_

TrajectoryAnalyzer apollo::control::LatController::trajectory_analyzer_
protected

◆ ts_

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

◆ vehicle_param_

common::VehicleParam apollo::control::LatController::vehicle_param_
protected

◆ wheelbase_

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

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