PID Controllers

Table of Contents

Reference(s):

  1.  AVR221: Discrete PID Controller on tinyAVR and megaAVR devices
  2. MIT Lab 4: Motor Control introduces the control of DC motors using the Arduino and Adafruit motor shield. A PID controller is demonstrated using the Mathworks SISO Design Tools GUI with accompanying Mathworks PID tutorial “Designing PID Controllers.”
  3. RepRap Extruder Nozzle Temperature Controller. RepRap provides a feed forward example (PIDSample3) and can be found in the PID_Beta6 project folder.

PID Theory

In Figure 1 a schematic of a system with a PID controller is shown. The PID controller compares the measured process value y with a reference setpoint value, y0. The difference or error, e, is then processed to calculate a new process input, u. This input will try to adjust the measured process value back to the desired setpoint.

The alternative to a closed-loop control scheme such as the PID controller is an open-loop controller. Open-loop control (no feedback) is in many cases not satisfactory and is often impossible due to the system properties. By adding feedback from the system output, performance can be improved.

Figure 1. Closed Loop System with PID Controller

Unlike a simple proportional control algorithm, the PID controller is capable of manipulating the process inputs based on the history and rate of change of the signal. This gives a more accurate and stable control method.

The basic idea is that the controller reads the system state by a sensor. Then it subtracts the measurement from the desired reference to generate the error value. The error will be managed in three ways, too…

  • handle the present, through the proportional term,
  • recover from the past, using the integral term,
  • anticipate the future, through the derivative term.

Click here to continue the reference article.

From Theory to Programming

The layout in Figure 2 reflects the “classic” PID architecture, naming conventions, and software implementation, versus the primary reference article. Figure 2 shows the PID design by, where Kp, Ki, and Kd denote the time constants of the proportional, integral, and derivative terms respectively. Within the literature, the variable, block, and even layouts may change, while the fundamentals stay the same.

Figure 2. PID controller schematic (cc Arturo Urquizo)

In this section, I am going to step through the blocks defined in Figure 2 “PID controller schematic” and look at how they have been translated into software.

  • Error value
  • Proportional term
  • Integral term
  • Differential term
  • Summing junction

The software examples are from these PID controllers.

  1. My Little PID Controller
  2. Bare Bones (PID) Coffee Controller
  3. AeroQuad

Error Value

The error value e(t) is defined as the difference between the desired setpoint r(t) and a measured process variable y(t). Here is the C++ statement used by the Bare Bones Coffee control software to implement this term.

  // determine how badly we are doing
  // error = setpoint - process value
  double error = sp - pv;

Proportional Term

The proportional term is only a function of the error. Here is the C++ statement used by the Bare Bones Coffee control software to implement this term.

  // the pTerm is the view from now, the pgain judges
  // how much we care about error we are at this instant.
   double pTerm = kp * error;

The proportional term (P) gives a system control input proportional to the error. Using only P control gives a stationary error in all cases except when the system control input is zero and the system process value y(t) equals the desired value.

In the figure below the stationary error e(t) in the system process value y(t) appears after a change in the desired value r(t). The response shown is that of a second-order transient system. Using a too large P term gives an unstable system.

Figure 3. Proportional Term (credit: AVR221: Discrete PID Controller)

Integral Term

You may remember the definition of integration, as shown in Figure 4, from your calculus class. If you have forgotten, the image below was originally presented in this review article.  To program the integral term we work backward from the definition by approximating the integral term by taking the area under the error(t) curve.

Figure 4. Integral as Limit of Area

Here is the C++ statement used by My Little PID control software to implement this term.

 static double iTerm = 0;
 iTerm += ki * error;     // ki unit time (ki = Ki*dT)

Here is the C++ statement used by the AeroQuad PID control software to implement this term. Where the arrow operator -> is used to access the integratedError member of the PIDparameters data structure by reference.

PIDparameters->integratedError += error * G_Dt;

Where global variable for delta time [1] is defined as.

float G_Dt = 0.02;

[1] Of all the PID code examples reviewed for this article, this was the only one that included delta time (Dt). All other code examples combine delta time with the integral term (Ki).  This latter approach is computationally more efficient at the cost of clarity (see Computational Simplification).

The figure below shows the step responses to an I and PI controller. As seen the PI controller response has no stationary error and the I controller response is very slow.

Figure 5. Step Response I and PI Controller (credit: AVR221: Discrete PID Controller)

Differential Term

Returning to your first course in calculus you hopefully also remember the definition of derivative as explained here. To program the differential term we again work backward from the definition by approximating the differential term by finding the slope of the error(t) curve at time t.

Figure 6. The Derivative

Here is a C++ statement for the My Simple PID control software to implement this term.

double dTerm = kd * (pv - last_value); // kd unit time (kd = Kd/dT)
last_value = pv;

Here is a C++ statement, written in the form of the AeroQuad PID control software to implement this term.

PIDparameters->differentialError = (currentPosition - PIDparameters->lastPosition) / G_Dt;

The figure below shows D and PD controller responses. The response of the PD controller gives a faster rising system process value.

Figure 7. Step Response D of PD Controller (credit: AVR221: Discrete PID Controller)

The differential term essentially behaves as a high pass filter on the system error signal and may therefore increase the effect of noise on the system leading to system instability. To see if a differential term is the best choice for your application, I would recommend reading “The PID’s Derivative Term Can Improve Control Loop Performance, But Often at a Cost.

Summing Junction

The summing junction u(t) adds the control inputs to be applied to the plant from the Proportional, Integral, and Differential blocks. Depending on the software implementation the gain factors  Kp, Ki, and Kd may be added here, or within each computational block. The summing junction is often included in the return statement.

The My Little PID controller takes the former approach as shown here.

  return pTerm + iTerm + dTerm; // process input

The Bare Bones Coffee controller takes the former approach as shown here.

  // the magic feedback bit
  return  pTerm + iTerm - dTerm;

The AeroQuad PID controller takes a hybrid approach with the gain factors P and I included at the summing junction, versus the differential block, where the term already includes gain factor D.

  return (PIDparameters->P * error) + (PIDparameters->I * (PIDparameters->integratedError)) + dTerm;

The figure below compares the P, PI, and PID controllers. PI improves the P by removing the stationary error, and the PID
improves the PI by the faster response and no overshoot.

Figure 8. Step Response P, PI, and PID Controller (credit: AVR221: Discrete PID Controller)

Computational Simplification

In moving from theory to program implementation, I intentionally used the AeroQuad as the example for computation of the integral term because it followed directly from the definition of integration and specifically included delta time.

PIDparameters->integratedError += error * G_Dt;

I then took some liberties by creating a differential term that also included time.

PIDparameters->differentialError = (currentPosition - PIDparameters->lastPosition) / G_Dt;

Here is the actual AeroQuad computation of the differential term.

dTerm = PIDparameters->D * (currentPosition - PIDparameters->lastPosition);

The inclusion of the differential gain term D, as mentioned in the discussion of the summing junction, is not unusual; but what happened to time? The better question would surprisingly be, why does the AeroQuad include time in the computation of the integral term in the first place? In almost every software PID controller, time is assumed to be a constant and therefore incorporated into the gain terms to minimize computational time. I was lucky to find one of the few exceptions.  To understand why this is true, let’s take a look at a hypothetical PID controller (based on the Bare Bones Coffee controller) where the PID terms include both the gain terms and delta time.

  // iState keeps changing over time; it's
  // overall "performance" over time, or accumulated error
  iTerm += igain * error * dT;
  // the dTerm, the difference between the temperature now
  // and our last reading, indicated the "speed,"
  // how quickly the temp is changing. (aka. Differential)
  dTerm = dgain * (curTemp - lastTemp) / dT;

By application of the associative (iTerm and dTerm) and distributive (dTerm)  laws, these two C++ statements could be rewritten as follows.

  iTerm += (igain * dT) * error;
  dTerm = (dgain / dT) * (curTemp - lastTemp);

The answer to our question is now more obvious. To compute the iTerm two multiplication operations are required. In the same way, the dTerm requires division, multiplication, and subtraction. By redefining the gain terms to include the time which we again assume is a constant, the iTerm only requires a single multiplication and the dTerm a single multiplication and subtraction. The Arduino PID library v1.2.1 and My Simple PID controller provides a nice example of this integration of gain terms and time in their tuning function. Here is a simplified version of the SetTunings function.

/* SetTunings(...)*************************************************************
* This function allows the controller's dynamic performance to be adjusted. 
* it's called automatically from the constructor, but tunings can also
* be adjusted on the fly during normal operation
* source: Arduino PID Library - Version 1
* by Brett Beauregard  brettbeauregard.com
******************************************************************************/ 
void setTunings(double Kp, double Ki, double Kd)
  {
    if (Kp<0 || Ki<0 || Kd<0) return;

    double dispKp = Kp;
    double dispKi = Ki; 
    double dispKd = Kd;

    double SampleTimeInSec = ((double)dT)/1000; 
    kp = Kp;
    ki = Ki * SampleTimeInSec;
    kd = Kd / SampleTimeInSec;
}

Discrete PID Controller – Sample Period

From the last section, we now know that a discrete PID controller will read the error, calculate and output the control input at a constant time interval (sample period dT).  So how do I choose a sample time? The sample time should be less than the shortest time constant (36% of normalized output) in the system. This represents the slowest acceptable sample time; hopefully, your system can sample/control the system at a much higher rate.

For PID controllers in which the measurement of the process value y(t) incorporates a gyro (including IMUs) setting the sample period to high will result in an increase in the integration error from the gyro (converting from angular velocity to an angle). Note: this is a different integration than the I in PID.

Read "Improving the Beginner’s PID – Sample Time" by Brett Beauregard, the author of the Arduino PID controller, to learn how time is handled by his PID controller.

Windup

Source: AVR221: Discrete PID controller

"I'm Givin' Her All She's Got, Captain!"

When the process input, u(t), reaches a high enough value, it is limited in some way. Either by the numeric range internally in the PID controller, the output range of the controller or constraints in amplifiers, or the process itself. This will happen if there is a large enough difference in the measured process value and the reference setpoint value, typically because the process has a larger disturbance/load than the system is capable of handling, for example, at startup and/or reset.

If the controller uses an integral term, this situation can be problematic. The integral term will sum up as long as the situation lasts, and when the larger disturbance/load disappears, the PID controller will overcompensate the process input until the integral sum is back to normal. This problem can be avoided in several ways. In this implementation, the maximum integral sum is limited by not allowing it to become larger than MAX_I_TERM. The correct size of the MAX_I_TERM will depend on the system and sample time used.

Here is how My Simple PID controller mitigates windup.

static double iTerm = 0;
iTerm += ki * error; // ki unit time (ki = Ki*dT)
iTerm = constrain(windupGuardMin, iTerm, windupGuardMax);

A standard C++ alternative to Arduino's unique constrain() function is provided here.

if(iTerm > outMax) iTerm= outMax; 
else if(iTerm < outMin) iTerm= outMin;

Here is how the Bare Bones Coffee controller mitigates windup.

  // iState keeps changing over time; it's
  // overall "performance" over time, or accumulated error
  iState += error;

  // to prevent the iTerm getting huge despite lots of
  //  error, we use a "windup guard"
  // (this happens when the machine is first turned on and
  // it cant help be cold despite its best efforts)
  // not necessary, but this makes windup guard values
  // relative to the current iGain
  windupGuard = WINDUP_GUARD_GAIN / igain; 

  if (iState > windupGuard)
    iState = windupGuard;
  else if (iState < -windupGuard)
    iState = -windupGuard;
  iTerm = igain * iState;

Here is how the AeroQuad controller mitigates windup.

PIDparameters->integratedError += error * G_Dt;
  PIDparameters->integratedError = constrain(PIDparameters->integratedError, -windupGuard, windupGuard);

Where the windupguard is stored in EEPROM and defined here.

float windupGuard; // Read in from EEPROM

Proportional on  Measurement

While the integration term is helpful in removing the constant offset error inherent in the proportional controller (you need some error to generate the proportional term in the first place), the I-term itself, even with windup, is a source of error when the setpoint is changed, for example on start-up. In these situations, the integration term will increase up to the windup guard value and must be removed over time. This can only be done by the system overshooting the setpoint (negative error) in order to subtract out the error.  The bad news is that all the PID controllers used as case studies will exhibit this behavior. The good news is that the Arduino PID controller version 1.2.1 and later, includes Proportional on Measurement  (PonM)  tuning, which addresses this problem.

Brett Beauregard, the author of the Arduino PID library, has written an excellent series of articles on the new Arduino PID library. Start with the article entitled  "Improving the Beginner’s PID – Introduction."  Clicking the Next>> button at the end of each article will take you in-depth on this PID controller. To learn more about WindUp, read the second article entitled "Improving the Beginner’s PID: Reset Windup." To learn more about PonM, read the second article entitled "Introducing Proportional On Measurement."

PID Control Examples

In this section, I am going to look at three control examples.

  1. Bare Bones (PID) Coffee Controller
  2. AeroQuad
  3. Arduino PID library with accompanying Tutorial “Improving the Beginner’s PID: Direction” by Brett Beauregard

The first three control examples are presented in order of the complexity of the PID controller implementation. The coffee controller is a single PID, which can be documented in a single Arduino ino file. The AeroQuad PID software is a modified version of the BBCC: Bare Bones (PID) Coffee Controller with the ability to control multiple control loops. The PID_Beta6 is the Beta version of the Arduino PID library, superseded by PID_v1.

BBCC AeroQuad PID_Beta6 PID_v1
Complexity Factor low medium high high
Ability to Change Tunings on the Fly ? ? yes yes
Inputs Normalized no no yes
Input and Output Limits no no yes
Multiple Control Loops no yes yes
Reset-Windup Mitigation somewhat somewhat yes yes
Proportional on Measurement no no no yes
Proportional on Error yes yes yes yes
Derivative Kick no no no yes
Feed forward no no yes
Integration Calculation includes dT no yes no
Tuning Processing Labview Processing

Like the AeroQuad PID and the coffee controller do not normalize the input. Both include non industrial-standard reset-windup mitigation code. Unlike the AeroQuad PID and Arduino PID library (PID_Beta6), the coffee controller does not calculate the integral term as a function of delta time. 

Tuning

Tuning the PID is where most of the “magic wand” action occurs. For some of the software control examples, the term “Configurator” is used for the development environment used for tuning the PID. It is not clear what IDE was used to develop the Configurator used by AeroQuad. The Coffee Controller, like the Arduino Graphical User Interface (GUI), uses Processing as its IDE for developing a simple configurator. The PIDLibrary also used Processing as illustrated here.

Simple Tuning Method

  1. Turn all gains to 0
  2. Begin turning up proportional gain until the system begins to oscillate.
  3. Reduce the proportional gain until the oscillations stop, and then back down by about 20%.
  4. Slowly increase the derivative term to improve response time and system stability.
  5. Increase the integral term until the system reaches the point of instability and then back it off slightly.

Ziegler-Nichols method 

The Ziegler-Nichols method is outlined in the AVR221: Discrete PID controller article and Jordan's PowerPoint presentationThe first step in this method is setting the I and D gains to zero, increasing the P gain until a sustained and stable oscillation (as close as possible) is obtained on the output. Then the critical gain Kc and the oscillation period Pc is recorded and the P, I and D values are calculated.

Table 1 Ziegler-Nichols Parameters

Fitting a simple first order plus dead time dynamic model to process test data.

PID - Cookbook | Mbed

This tuning method has been ported to the mbed platform. Here is a very nice step-by-step Tuning Example using mbed.

IMC Tuning Method

Since 1942, over one hundred tuning methods have been developed. One of these methods is the Internal Model Control (IMC) tuning method, sometimes called Lambda tuning.  This Application Note describes how to tune control loops using IMC tuning rules.

Tuning the Arduino PID Controller

Read "Improving the Beginner’s PID: Tuning" by Brett Beauregard, the author of the Arduino PID controller, to learn how tuning is handled by his PID controller.

PID Control Software Examples

The next three sections, provide the code used for three different PID controllers. To help compare the programs I have color coded the parameters as defined here.

  • Summing Junction - Sky Blue
  • Proportional Term - Magenta
  • Integral Term - Sea Green
  • Differential Term - Royal Blue

My Little PID Control Software

/**********************************************************************************************
 * My Little PID Controller - Version 1 *
 * by Gary Hill  *
 * March 24, 2021
 * 
 * This is a module that implements a PID control loop
 * initialize it with 3 values: Kp,Ki,Kd
 * and then tune the feedback loop with the setP etc funcs
 * 
 * This was written based PID controllers by 
 * Tim Hirzel 
 * Bare Bones Coffee Controller PID
 * http://www.arduino.cc/playground/Main/BarebonesPIDForEspresso#main 
 * http://processing.org/
 * Tim Wescott
 * http://www.embedded.com/2000/0010/0010feat3.htm
 * Brett Beauregard  brettbeauregard.com
 * Arduino PID Library
 * 
 * All code released under
 * This Code is licensed under a Creative Commons Attribution-ShareAlike 3.0 Unported License.
 **********************************************************************************************/

double kp = 100.0;
double ki = 100.0;
double kd = 100.0;
const double dT = 100.0; // sample time in milliseconds
const double windupGuardMin = 0; // set to output limit
const double windupGuardMax = 255; // set to output limit

void setup() {
  // Initialize serial and wait for port to open:
  Serial.begin(9600);
  while (!Serial) {} // wait for serial port to connect. Needed for native USB port only
}

void loop() {
  static double sp = 0; // set point 
  static double updatePID = 0.0;
  if (updatePID >= millis()){
    uint16_t process_value = analogRead(A4); // value 0 - 1023
    double process_input = PID( (double) process_value, sp);
    analogWrite( LED_BUILTIN, (uint8_t) process_input); // value 0 - 255 
  }
}

/* Input parameter pv = process value, sp = set point
 * Function returns process input value
 */
double PID(double pv, double sp){
  static double last_value = 0;
  static double i_err = 0;

  double error = sp - pv; // error value
  double pTerm = kp * error; // proportional term

  static double iTerm = 0;
  iTerm += ki * error; // Ki unit time (ki = Ki*dT)
  iTerm = constrain(windupGuardMin, iTerm, windupGuardMax);

  double dTerm = kd * (pv - last_value); // Kd unit time (kd = Kd/dT)
  last_value = pv;

  return pTerm + iTerm + dTerm; // process input 
}

/* SetTunings(...)*************************************************************
 * This function allows the controller's dynamic performance to be adjusted. 
 * it's called automatically from the constructor, but tunings can also
 * be adjusted on the fly during normal operation
 * source: Arduino PID Library - Version 1
 * by Brett Beauregard  brettbeauregard.com
 ******************************************************************************/ 
void setTunings(double Kp, double Ki, double Kd)
{
  if (Kp<0 || Ki<0 || Kd<0) return;

  double dispKp = Kp;
  double dispKi = Ki; 
  double dispKd = Kd;

  double SampleTimeInSec = ((double)dT)/1000; 
  kp = Kp;
  ki = Ki * SampleTimeInSec;
  kd = Kd / SampleTimeInSec;
}

/* Tips and Tricks
 * 
 * You can also update on timer overflow bit associated
 * with the motors or Arduino built 8-bit timer T0. 
 * By Alexander Littleton, DeRobot 2021
 * 
 * For standard C++ alternative to Arduino unique constrain()
 * if(iTerm > outMax) iTerm= outMax; 
 * else if(iTerm < outMin) iTerm= outMin;
 * 
 */

AeroQuad PID Control Software

Reference: AeroQuad Downloads

The following AeroQuad header and pde files are key to understanding the AeroQuad  PID software.

AeroQuad.h

This header file defines AeroQuad mnemonics

// Basic axis definitions

#define ROLL 0
#define PITCH 1
#define YAW 2
#define THROTTLE 3
#define MODE 4
#define AUX 5
#define XAXIS 0
#define YAXIS 1
#define ZAXIS 2
#define LASTAXIS 3
#define LEVELROLL 3
#define LEVELPITCH 4
#define LASTLEVELAXIS 5
#define HEADING 5
#define LEVELGYROROLL 6
#define LEVELGYROPITCH 7

float G_Dt = 0.02;

DataStorage.h

This header file is used to read and write default settings to the ATmega EEPROM.

// contains all default values when re-writing EEPROM

void initializeEEPROM(void) {

  PID[ROLL].P = 1.2;
  PID[ROLL].I = 0.0;
  PID[ROLL].D = -7.0;
  PID[PITCH].P = 1.2;
  PID[PITCH].I = 0.0;
  PID[PITCH].D = -7.0;
  PID[YAW].P = 3.0;
  PID[YAW].I = 0.0;
  PID[YAW].D = 0.0;
  PID[LEVELROLL].P = 7.0;
  PID[LEVELROLL].I = 20.0;
  PID[LEVELROLL].D = 0.0;
  PID[LEVELPITCH].P = 7.0;
  PID[LEVELPITCH].I = 20.0;
  PID[LEVELPITCH].D = 0.0;
  PID[HEADING].P = 3.0;
  PID[HEADING].I = 0.0;
  PID[HEADING].D = 0.0;
  PID[LEVELGYROROLL].P = 1.2;
  PID[LEVELGYROROLL].I = 0.0;
  PID[LEVELGYROROLL].D = -14.0;
  PID[LEVELGYROPITCH].P = 1.2;
  PID[LEVELGYROPITCH].I = 0.0;
  PID[LEVELGYROPITCH].D = -14.0;

  windupGuard = 1000.0;

FlightControl.pde

This C++ program calls the PID updatePID function and zeroIntegralError subroutine. Here are a few example calls.

updatePID(receiver.getData(ROLL), gyro.getFlightData(ROLL) + 1500, &PID[ROLL]));
updatePID(receiver.getData(PITCH), gyro.getFlightData(PITCH) + 1500, &PID[PITCH]));
updatePID(receiver.getData(YAW) + headingHold, gyro.getFlightData(YAW) + 1500, &PID[YAW]

PID.h

The PID data structure and PID algorithm

struct PIDdata {
  float P, I, D;
  float lastPosition;
  float integratedError;
} PID[8];

float windupGuard; // Read in from EEPROM

// Modified from http://www.arduino.cc/playground/Main/BarebonesPIDForEspresso
float updatePID(float targetPosition, float currentPosition, struct PIDdata *PIDparameters) {
  float error;
  float dTerm;
  error = targetPosition - currentPosition;
  PIDparameters->integratedError += error * G_Dt;
  PIDparameters->integratedError = constrain(PIDparameters->integratedError, -windupGuard, windupGuard);
  dTerm = PIDparameters->D * (currentPosition - PIDparameters->lastPosition);
  PIDparameters->lastPosition = currentPosition;
  return (PIDparameters->P * error) + (PIDparameters->I * (PIDparameters->integratedError)) + dTerm;
}

void zeroIntegralError() {
  for (axis = ROLL; axis < LASTLEVELAXIS; axis++)
  PID[axis].integratedError = 0;
}

Bare Bones (PID) Coffee Controller

As commented on in the code, the AeroQuad  PID software is a modified version of the BBCC: Bare Bones (PID) Coffee Controller  The coffee controller is a single PID and so is a little simpler to understand.

Like the AeroQuad PID, the coffee controller does not normalize the input. Both include non industrial-standard reset-windup mitigation code. Unlike the AeroQuad PID, the coffee controller does not calculate the integral term as a function of delta time.

(PID_Beta6)

float updatePID(float targetTemp, float curTemp)
{
  // these local variables can be factored out if memory is an issue,
  // but they make it more readable
  double result;
  float error;
  float windupGuard;

  // determine how badly we are doing
  // error = setpoint - process value
  error = targetTemp - curTemp;

  // the pTerm is the view from now, the pgain judges
  // how much we care about error we are at this instant.
  pTerm = pgain * error;

  // iState keeps changing over time; it's
  // overall "performance" over time, or accumulated error
  iState += error;

  // to prevent the iTerm getting huge despite lots of
  //  error, we use a "windup guard"
  // (this happens when the machine is first turned on and
  // it cant help be cold despite its best efforts)
  // not necessary, but this makes windup guard values
  // relative to the current iGain
  windupGuard = WINDUP_GUARD_GAIN / igain; 

  if (iState > windupGuard)
    iState = windupGuard;
  else if (iState < -windupGuard)
    iState = -windupGuard;
  iTerm = igain * iState;

  // the dTerm, the difference between the temperature now
  // and our last reading, indicated the "speed,"
  // how quickly the temp is changing. (aka. Differential)
  dTerm = (dgain* (curTemp - lastTemp));

  // now that we've use lastTemp, put the current temp in
  // our pocket until for the next round
  lastTemp = curTemp;

  // the magic feedback bit
  return  pTerm + iTerm - dTerm;
}

PIDLibrary – PID_Beta6.cpp

You will need AVR Studio to view this file with color coding the C++ code.

/* Compute() ******************************************************************
*  This, as they say, is where the magic happens.  this function should
*  be called every time "void loop()" executes.  the function will decide
*  for itself whether a new pid Output needs to be computed
*
*  Some notes for people familiar with the nuts and bolts of PID control:
*  - I used the Ideal form of the PID equation.  mainly because I like IMC
*    tunings.  lock in the I and D, and then just vary P to get more
*    aggressive or conservative
*
*  - While this controller presented to the outside world as being a Reset
*    Time controller, when the user enters their tunings the I term is
*    converted to Reset Rate.  I did this merely to avoid the div0 error
*    when the user wants to turn Integral action off.
*    
*  - Derivative on Measurement is being used instead of Derivative on Error.
*    The performance is identical, with one notable exception. DonE causes a
*    kick in the controller output whenever there's a setpoint change.
*    DonM does not.
*
*  If none of the above made sense to you, and you would like it to, go to:
*  http://www.controlguru.com.  Dr. Cooper was my controls professor, and
*  is gifted at concisely and clearly explaining PID control 
******************************************************************************
*/

void PID::Compute()
{
  justCalced=false;
  if (!inAuto) return; //if we're in manual just leave;
  unsigned long now = millis();
  //millis() wraps around to 0 at some point. depending on the version of the
  //Arduino Program you are using, it could be in 9 hours or 50 days.
  //this is not currently addressed by this algorithm.
  //...Perform PID Computations if it's time...

  if (now>=nextCompTime)
  {

    //pull in the input and setpoint, and scale them into percent span
    double scaledInput = (*myInput - inMin) / inSpan;
    if (scaledInput>1.0) scaledInput = 1.0;
    else if (scaledInput<0.0) scaledInput = 0.0;

    double scaledSP = (*mySetpoint - inMin) / inSpan;
    if (scaledSP>1.0) scaledSP = 1;
    else if (scaledSP<0.0) scaledSP = 0;

    //compute the error
    double err = scaledSP - scaledInput;

    // check and see if the output is pegged at a limit and only
    // integrate if it is not. (this is to prevent reset-windup)
    if (!(lastOutput >= 1 && err>0) && !(lastOutput <= 0 && err<0))
    {
      accError = accError + err;
    }

    // compute the current slope of the input signal
    // we'll assume that dTime (the denominator) is 1 second.
    double dMeas = (scaledInput - lastInput);
    // if it isn't, the taud term will have been adjusted 
    // in "SetTunings" to compensate
    //if we're using an external bias (i.e. the user used the
    //overloaded constructor,) then pull that in now
    if(UsingFeedForward)
    {
      bias = (*myBias - outMin) / outSpan;
    }

    // perform the PID calculation.
    double output = bias + kc * (err + taur * accError - taud * dMeas);

    //make sure the computed output is within output constraints
    if (output < 0.0) output = 0.0;
    else if (output > 1.0) output = 1.0;
    lastOutput = output;     // remember this output for the windup
                             // check next time
    lastInput = scaledInput; // remember the Input for the derivative
                             // calculation next time
    //scale the output from percent span back out to a real world number
    *myOutput = ((output * outSpan) + outMin);
    nextCompTime += tSample;  // determine the next time the computation
                              // should be performed
    if(nextCompTime < now) nextCompTime = now + tSample;
    justCalced=true;  //set the flag that will tell the outside world
                      // that the output was just computed
  }
}

PID Controller for Line Following Robots

By Jordan Smallwood | October 4th, 2017

Overview

The following PowerPoint presentation introduces Proportional Integral Derivative (PID) controllers and their application to a line following robot. The presentation concludes with an in-depth look with examples of integration into a line following robot in C++.

References

  1. https://en.wikipedia.org/wiki/PID_controller
  2. https://www.cds.caltech.edu/~murray/courses/cds101/fa04/caltech/am04_ch8-3nov04.pdf

Review Questions

  1. To Be Written

Answers

Using your mouse, highlight below in order to reveal the answers.

  1. To Be Written