Apollo 10.0
自动驾驶开放平台
|
A proportional-integral-derivative controller for speed and steering with integral-clamping-anti-windup 更多...
#include <pid_IC_controller.h>
Public 成员函数 | |
virtual double | Control (const double error, const double dt) |
compute control value based on the error, with integral-clamping-anti-windup | |
virtual int | OutputSaturationStatus () |
![]() | |
void | Init (const PidConf &pid_conf) |
initialize pid controller | |
void | SetPID (const PidConf &pid_conf) |
set pid controller coefficients for the proportional, integral, and derivative | |
void | Reset () |
reset variables for pid controller | |
void | Reset_integral () |
reset integral for pid controller | |
virtual | ~PIDController ()=default |
int | IntegratorSaturationStatus () const |
get saturation status | |
bool | IntegratorHold () const |
get status that if integrator is hold | |
void | SetIntegratorHold (bool hold) |
set whether to hold integrator component at its current value. | |
额外继承的成员函数 | |
![]() | |
double | kp_ = 0.0 |
double | ki_ = 0.0 |
double | kd_ = 0.0 |
double | kaw_ = 0.0 |
double | previous_error_ = 0.0 |
double | previous_output_ = 0.0 |
double | integral_ = 0.0 |
double | integrator_saturation_high_ = 0.0 |
double | integrator_saturation_low_ = 0.0 |
bool | first_hit_ = false |
bool | integrator_enabled_ = false |
bool | integrator_hold_ = false |
int | integrator_saturation_status_ = 0 |
double | output_saturation_high_ = 0.0 |
double | output_saturation_low_ = 0.0 |
int | output_saturation_status_ = 0 |
A proportional-integral-derivative controller for speed and steering with integral-clamping-anti-windup
在文件 pid_IC_controller.h 第 40 行定义.
|
virtual |
compute control value based on the error, with integral-clamping-anti-windup
error | error value, the difference between a desired value and a measured value |
dt | sampling time interval |
重载 apollo::control::PIDController .
在文件 pid_IC_controller.cc 第 28 行定义.
|
virtual |
在文件 pid_IC_controller.cc 第 72 行定义.