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

A proportional-integral-derivative controller for speed and steering with backward-calculation-anti-windup. More...

#include <pid_BC_controller.h>

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

Public Member Functions

virtual double Control (const double error, const double dt)
 compute control value based on the error, with backward-calculation-anti-windup More...
 
virtual int OutputSaturationStatus ()
 
- Public Member Functions inherited from apollo::control::PIDController
void Init (const PidConf &pid_conf)
 initialize pid controller More...
 
void SetPID (const PidConf &pid_conf)
 set pid controller coefficients for the proportional, integral, and derivative More...
 
void Reset ()
 reset variables for pid controller More...
 
virtual ~PIDController ()=default
 
int IntegratorSaturationStatus () const
 get saturation status More...
 
bool IntegratorHold () const
 get status that if integrator is hold More...
 
void SetIntegratorHold (bool hold)
 set whether to hold integrator component at its current value. More...
 

Additional Inherited Members

- Protected Attributes inherited from apollo::control::PIDController
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
 

Detailed Description

A proportional-integral-derivative controller for speed and steering with backward-calculation-anti-windup.

Member Function Documentation

◆ Control()

virtual double apollo::control::PIDBCController::Control ( const double  error,
const double  dt 
)
virtual

compute control value based on the error, with backward-calculation-anti-windup

Parameters
errorerror value, the difference between a desired value and a measured value
dtsampling time interval
Returns
control value based on PID terms

Reimplemented from apollo::control::PIDController.

◆ OutputSaturationStatus()

virtual int apollo::control::PIDBCController::OutputSaturationStatus ( )
virtual

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