Skip to the content.

AutoPID

Arduino AutoPID library

About

PID Controllers

PID controller on Wikipedia: A proportional–integral–derivative controller (PID controller or three term controller) is a control loop feedback mechanism widely used in industrial control systems and a variety of other applications requiring continuously modulated control. A PID controller continuously calculates an error value e(t) as the difference between a desired setpoint (SP) and a measured process variable (PV) and applies a correction based on proportional, integral, and derivative terms (denoted P, I, and D respectively) which give their name to the controller.

https://upload.wikimedia.org/wikipedia/commons/3/33/PID_Compensation_Animated.gif

Features

Time-scaling and Automatic Value Updating

The PID controller’s run() function can be called as often as possible in the main loop, and will automatically only perform the updated calculations at a specified time-interval. The calculations take the length of this time-interval into account, so the interval can be adjusted without needing to recaculate the PID gains.

Since the PID object stores pointers to the input, setpoint, and output, it can automatically update those variables without extra assignment statements.

Bang-Bang Control

This library includes optional built-in bang-bang control. When the input is outside of a specified range from the setpoint, the PID control is deactivated, and the output is instead driven to max (bang-on) or min (bang-off).

This can help approach the setpoint faster, and reduce overshooting due to integrator wind-up.

PWM (Relay) Control

Since the output of a PID control is an analog value, this can be adapted to control an on-off digital output (such as a relay) using pulse-width modulation.

Installation

Via Arduino IDE Library Manager

Sketch -> Include Library -> Manage Libraries… -> search for “autopid” Arduino Library Manager screen

Via ZIP File

Download zip file and extract to Arduino/libraries folder

Documentation

AutoPID Functions

AutoPID::AutoPID Constructor

Creates a new AutoPID object

AutoPID(double *input, double *setpoint, double *output, 
  double outputMin, double outputMax, 
  double Kp, double Ki, double Kd)

AutoPID::setGains

Manual adjustment of PID gains

void setGains(double Kp, double Ki, double Kd)

AutoPID::setBangBang

Set the bang-bang control thresholds

void setBangBang(double bangOn, double bangOff)
void setBangBang(double bangRange)

AutoPID::setOutputRange

Manual (re)adjustment of output range

void setOutputRange(double outputMin, double outputMax)

AutoPID::setTimeStep

Manual adjustment of PID time interval for calculations

void setTimeStep(unsigned long timeStep)

AutoPID::atSetPoint

Indicates if input has reached desired setpoint

bool atSetPoint(double threshold)

AutoPID::run

Automatically runs PID calculations at certain time interval. Reads input, setpoint, and updates output

void run()

AutoPID::stop

Stops PID calculations and resets internal PID calculation values (integral, derivative)

void stop()

AutoPID::reset

Resets internal PID calculation values (integral, derivative)

void reset()

AutoPID::isStopped

Indicates if PID calculations have been stopped

bool isStopped()

AutoPID::getIntegral

Get current value of integral. Useful for storing states after a power cycle

double getIntegral()

AutoPID::setIntegral

Override current value of integral, useful for resuming states after a power cycle

void setIntegral(double integral)

AutoPIDRelay Functions

AutoPIDRelay::AutoPIDRelay Constructor

AutoPIDRelay(double *input, double *setpoint, bool *relayState,
  double pulseWidth, double Kp, double Ki, double Kd)

AutoPIDRelay::getPulseValue

double getPulseValue();

Examples

Basic Temperature Control

/*
   AutoPID BasicTempControl Example Sketch

   This program reads a dallas temperature probe as input, potentiometer as setpoint, drives an analog output.
   It lights an LED when the temperature has reached the setpoint.
*/
#include <AutoPID.h>
#include <DallasTemperature.h>
#include <OneWire.h>

//pins
#define POT_PIN A0
#define OUTPUT_PIN A1
#define TEMP_PROBE_PIN 5
#define LED_PIN 6

#define TEMP_READ_DELAY 800 //can only read digital temp sensor every ~750ms

//pid settings and gains
#define OUTPUT_MIN 0
#define OUTPUT_MAX 255
#define KP .12
#define KI .0003
#define KD 0

double temperature, setPoint, outputVal;

OneWire oneWire(TEMP_PROBE_PIN);
DallasTemperature temperatureSensors(&oneWire);

//input/output variables passed by reference, so they are updated automatically
AutoPID myPID(&temperature, &setPoint, &outputVal, OUTPUT_MIN, OUTPUT_MAX, KP, KI, KD);

unsigned long lastTempUpdate; //tracks clock time of last temp update

//call repeatedly in loop, only updates after a certain time interval
//returns true if update happened
bool updateTemperature() {
  if ((millis() - lastTempUpdate) > TEMP_READ_DELAY) {
    temperature = temperatureSensors.getTempFByIndex(0); //get temp reading
    lastTempUpdate = millis();
    temperatureSensors.requestTemperatures(); //request reading for next time
    return true;
  }
  return false;
}//void updateTemperature


void setup() {
  pinMode(POT_PIN, INPUT);
  pinMode(OUTPUT_PIN, OUTPUT);
  pinMode(LED_PIN, OUTPUT);

  temperatureSensors.begin();
  temperatureSensors.requestTemperatures();
  while (!updateTemperature()) {} //wait until temp sensor updated

  //if temperature is more than 4 degrees below or above setpoint, OUTPUT will be set to min or max respectively
  myPID.setBangBang(4);
  //set PID update interval to 4000ms
  myPID.setTimeStep(4000);

}//void setup


void loop() {
  updateTemperature();
  setPoint = analogRead(POT_PIN);
  myPID.run(); //call every loop, updates automatically at certain time interval
  analogWrite(OUTPUT_PIN, outputVal);
  digitalWrite(LED_PIN, myPID.atSetPoint(1)); //light up LED when we're at setpoint +-1 degree

}//void loop

Relay Temperature Control

See an example usage here


Ryan Downing ~ 2017