A lead/lag controller for speed and steering using defualt integral hold.
More...
#include <leadlag_controller.h>
|
void | Init (const LeadlagConf &leadlag_conf, const double dt) |
| initialize lead/lag controller More...
|
|
void | SetLeadlag (const LeadlagConf &leadlag_conf) |
|
void | TransformC2d (const double dt) |
| transfer lead/lag controller coefficients to the discrete-time form, with the bilinear transform (trapezoidal integration) method More...
|
|
void | Reset () |
| reset variables for lead/leg controller More...
|
|
virtual double | Control (const double error, const double dt) |
| compute control value based on the error More...
|
|
int | InnerstateSaturationStatus () const |
| get saturation status More...
|
|
A lead/lag controller for speed and steering using defualt integral hold.
◆ Control()
virtual double apollo::control::LeadlagController::Control |
( |
const double |
error, |
|
|
const double |
dt |
|
) |
| |
|
virtual |
compute control value based on the error
- Parameters
-
error | error value, the difference between a desired value and a measured value |
dt | sampling time interval |
- Returns
- control value based on Lead/Lag terms
◆ Init()
void apollo::control::LeadlagController::Init |
( |
const LeadlagConf & |
leadlag_conf, |
|
|
const double |
dt |
|
) |
| |
initialize lead/lag controller
- Parameters
-
leadlag_conf | configuration for leadlag controller |
dt | sampling time interval |
◆ InnerstateSaturationStatus()
int apollo::control::LeadlagController::InnerstateSaturationStatus |
( |
| ) |
const |
get saturation status
- Returns
- saturation status
◆ Reset()
void apollo::control::LeadlagController::Reset |
( |
| ) |
|
reset variables for lead/leg controller
◆ SetLeadlag()
void apollo::control::LeadlagController::SetLeadlag |
( |
const LeadlagConf & |
leadlag_conf | ) |
|
alpha, beta and tau
- Parameters
-
leadlag_conf | configuration for leadlag controller |
◆ TransformC2d()
void apollo::control::LeadlagController::TransformC2d |
( |
const double |
dt | ) |
|
transfer lead/lag controller coefficients to the discrete-time form, with the bilinear transform (trapezoidal integration) method
- Parameters
-
◆ alpha_
double apollo::control::LeadlagController::alpha_ = 0.0 |
|
protected |
◆ beta_
double apollo::control::LeadlagController::beta_ = 0.0 |
|
protected |
◆ innerstate_
double apollo::control::LeadlagController::innerstate_ = 0.0 |
|
protected |
◆ innerstate_saturation_high_
double apollo::control::LeadlagController::innerstate_saturation_high_ = 0.0 |
|
protected |
◆ innerstate_saturation_low_
double apollo::control::LeadlagController::innerstate_saturation_low_ = 0.0 |
|
protected |
◆ innerstate_saturation_status_
int apollo::control::LeadlagController::innerstate_saturation_status_ = 0 |
|
protected |
◆ kd0_
double apollo::control::LeadlagController::kd0_ = 0.0 |
|
protected |
◆ kd1_
double apollo::control::LeadlagController::kd1_ = 0.0 |
|
protected |
◆ kn0_
double apollo::control::LeadlagController::kn0_ = 0.0 |
|
protected |
◆ kn1_
double apollo::control::LeadlagController::kn1_ = 0.0 |
|
protected |
◆ previous_innerstate_
double apollo::control::LeadlagController::previous_innerstate_ = 0.0 |
|
protected |
◆ previous_output_
double apollo::control::LeadlagController::previous_output_ = 0.0 |
|
protected |
◆ tau_
double apollo::control::LeadlagController::tau_ = 0.0 |
|
protected |
◆ transfromc2d_enabled_
bool apollo::control::LeadlagController::transfromc2d_enabled_ = false |
|
protected |
◆ Ts_
double apollo::control::LeadlagController::Ts_ = 0.01 |
|
protected |
The documentation for this class was generated from the following file: