24 #include "modules/control/proto/pid_conf.pb.h" 44 void Init(
const PidConf &pid_conf);
51 void SetPID(
const PidConf &pid_conf);
65 virtual double Control(
const double error,
const double dt);
double previous_error_
Definition: pid_controller.h:92
void SetPID(const PidConf &pid_conf)
set pid controller coefficients for the proportional, integral, and derivative
bool first_hit_
Definition: pid_controller.h:97
void Reset()
reset variables for pid controller
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool integrator_enabled_
Definition: pid_controller.h:98
double integrator_saturation_low_
Definition: pid_controller.h:96
int IntegratorSaturationStatus() const
get saturation status
virtual double Control(const double error, const double dt)
compute control value based on the error
double previous_output_
Definition: pid_controller.h:93
double integrator_saturation_high_
Definition: pid_controller.h:95
double ki_
Definition: pid_controller.h:89
virtual ~PIDController()=default
double kp_
Definition: pid_controller.h:88
bool integrator_hold_
Definition: pid_controller.h:99
double kaw_
Definition: pid_controller.h:91
void Init(const PidConf &pid_conf)
initialize pid controller
int integrator_saturation_status_
Definition: pid_controller.h:100
double integral_
Definition: pid_controller.h:94
void SetIntegratorHold(bool hold)
set whether to hold integrator component at its current value.
double output_saturation_low_
Definition: pid_controller.h:103
int output_saturation_status_
Definition: pid_controller.h:104
double kd_
Definition: pid_controller.h:90
bool IntegratorHold() const
get status that if integrator is hold
double output_saturation_high_
Definition: pid_controller.h:102
A proportional-integral-derivative controller for speed and steering using defualt integral hold...
Definition: pid_controller.h:38