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>
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.
◆ LatController()
apollo::control::LatController::LatController |
( |
| ) |
|
◆ ~LatController()
virtual apollo::control::LatController::~LatController |
( |
| ) |
|
|
virtual |
◆ 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
-
localization | vehicle location |
chassis | vehicle status e.g., speed, acceleration |
trajectory | trajectory generated by planning |
cmd | control 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()
◆ 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 |
◆ ProcessLogs()
void apollo::control::LatController::ProcessLogs |
( |
const SimpleLateralDebug * |
debug, |
|
|
const canbus::Chassis * |
chassis |
|
) |
| |
|
protected |
◆ Reset()
◆ Stop()
void apollo::control::LatController::Stop |
( |
| ) |
|
|
overridevirtual |
◆ 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 |
◆ 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_
◆ 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_
◆ 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_
◆ 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_
◆ leadlag_controller_
◆ 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_
◆ 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_
◆ 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: