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

A proportional-integral-derivative controller for speed and steering using defualt integral hold. More...

#include <pid_controller.h>

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

Public Member Functions

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 double Control (const double error, const double dt)
 compute control value based on the error 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...
 

Protected Attributes

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 using defualt integral hold.

Constructor & Destructor Documentation

◆ ~PIDController()

virtual apollo::control::PIDController::~PIDController ( )
virtualdefault

Member Function Documentation

◆ Control()

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

compute control value based on the error

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

Reimplemented in apollo::control::PIDBCController, and apollo::control::PIDICController.

◆ Init()

void apollo::control::PIDController::Init ( const PidConf &  pid_conf)

initialize pid controller

Parameters
pid_confconfiguration for pid controller

◆ IntegratorHold()

bool apollo::control::PIDController::IntegratorHold ( ) const

get status that if integrator is hold

Returns
if integrator is hold return true

◆ IntegratorSaturationStatus()

int apollo::control::PIDController::IntegratorSaturationStatus ( ) const

get saturation status

Returns
saturation status

◆ Reset()

void apollo::control::PIDController::Reset ( )

reset variables for pid controller

◆ SetIntegratorHold()

void apollo::control::PIDController::SetIntegratorHold ( bool  hold)

set whether to hold integrator component at its current value.

Parameters
hold

◆ SetPID()

void apollo::control::PIDController::SetPID ( const PidConf &  pid_conf)

set pid controller coefficients for the proportional, integral, and derivative

Parameters
pid_confconfiguration for pid controller

Member Data Documentation

◆ first_hit_

bool apollo::control::PIDController::first_hit_ = false
protected

◆ integral_

double apollo::control::PIDController::integral_ = 0.0
protected

◆ integrator_enabled_

bool apollo::control::PIDController::integrator_enabled_ = false
protected

◆ integrator_hold_

bool apollo::control::PIDController::integrator_hold_ = false
protected

◆ integrator_saturation_high_

double apollo::control::PIDController::integrator_saturation_high_ = 0.0
protected

◆ integrator_saturation_low_

double apollo::control::PIDController::integrator_saturation_low_ = 0.0
protected

◆ integrator_saturation_status_

int apollo::control::PIDController::integrator_saturation_status_ = 0
protected

◆ kaw_

double apollo::control::PIDController::kaw_ = 0.0
protected

◆ kd_

double apollo::control::PIDController::kd_ = 0.0
protected

◆ ki_

double apollo::control::PIDController::ki_ = 0.0
protected

◆ kp_

double apollo::control::PIDController::kp_ = 0.0
protected

◆ output_saturation_high_

double apollo::control::PIDController::output_saturation_high_ = 0.0
protected

◆ output_saturation_low_

double apollo::control::PIDController::output_saturation_low_ = 0.0
protected

◆ output_saturation_status_

int apollo::control::PIDController::output_saturation_status_ = 0
protected

◆ previous_error_

double apollo::control::PIDController::previous_error_ = 0.0
protected

◆ previous_output_

double apollo::control::PIDController::previous_output_ = 0.0
protected

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