Arduino PID Library by Brett Beauregard contact: br3ttb@gmail.com
PID Library
PID Front-End using Processing.org
Older Versions can be viewed / downloaded here
If you are unfamiliar with PID control, a good place you start might be: http://en.wikipedia.org/wiki/PID_controller
There has been a PID algorithm for the Arduino available for some time now. The goal of this library was to create a more modular pid controller on-par with those found in industry. All of the standard industrial error checks are in there. The main improvements that this Library brings are:
I throw around a lot to terms in this wiki. hopefully this example will help decipher some of them. Let's say our PID controller is working as the cruise control in a car. in that situation:
(these are by no means comprehensive)
Description: Creates a PID object and links it to the Input, Output, and Setpoint. Initial tuning parameters are also set here.
Arguments:
Description: Decides if the PID calculation needs to be performed, and if so, performs it. Ideally this method should be called every time loop() cycles. The PID's Auto / Manual state and calculation frequency can be set using the SetMode(...) and SetCalcFrequency(...) functions respectively.
Description: sets PID to either Manual (0) or Auto (non-0) Mode
Available Constants: MANUAL, AUTO
Description: This function tells the controller What 0% and 100% are for the Output. By default these limits are 0-255: the Arduino PWM output limits. Take a look at Example 2 below to see how this function was used to quickly set up an on/off time window.
Arguments:
Description: While most users will set the tunings once during creation, this function gives the user the option of changing tunings during runtime for Adaptive control
Arguments:
There are also more advanced methods available
/********************************************************
* PID Simple Example
* Reading analog input 0 to control analog PWM output 3
********************************************************/
#include <PID_Beta6.h>
//Define Variables we'll be connecting to
double Setpoint, Input, Output;
//Specify the links and initial tuning parameters
PID myPID(&Input, &Output, &Setpoint,2,5,1);
void setup()
{
//initialize the variables we're linked to
Input = analogRead(0);
Setpoint = 100;
//turn the PID on
myPID.SetMode(AUTO);
}
void loop()
{
Input = analogRead(0);
myPID.Compute();
analogWrite(3,Output);
}
/***************************************************
* Advanced PID Example
* PID input: Analog input 0
* output = time proportion on/off of output 0 (50% = 2 sec on, 2 sec off)
* and just to make it more complicated:
* - start with a setpoint ramp (0 to 500 over 5 minutes (300 seconds))
* - use gap control (moderate tunings when within 100 of setpoint, aggressive when outside 100)
***************************************************/
#include <PID_Beta6.h>
unsigned long windowStartTime;
unsigned long RampStartTime;
double Input, Output, Setpoint;
PID pid(&Input, &Output, &Setpoint, 3,4,1);
unsigned long printTime= millis();
void setup()
{
pid.SetOutputLimits(0,4000); //tell the PID to range the output from 0 to 4000
Output = 4000; //start the output at its max and let the PID adjust it from there
pid.SetMode(AUTO); //turn on the PID
windowStartTime = millis();
RampStartTime = millis();
}
void loop()
{
//Set Point Ramp
if(millis()-RampStartTime<300000)
{
Setpoint = ((double)(millis()-RampStartTime))/(300000.0)*500.0;
}
else Setpoint = 500;
//Set Tuning Parameters based on how close we are to setpoint
if(abs(Setpoint-Input)>100)pid.SetTunings(6,4,1); //aggressive
else pid.SetTunings(3,4,1); //comparatively moderate
//give the PID the opportunity to compute if needed
Input = analogRead(0);
pid.Compute();
//turn the output pin on/off based on pid output
if(millis()-windowStartTime>4000) windowStartTime+=4000;
if(Output > millis()-windowStartTime) digitalWrite(0,HIGH);
else digitalWrite(0,LOW);
}