Compare commits

...

6 Commits

Author SHA1 Message Date
Chris Giacofei
2dde69d575 Point to Internet Archive.
Just in case this awesome site goes down in the future.
2024-05-02 13:01:34 -04:00
Chris Giacofei
d565cded53 Tracking down compile errors. 2024-05-01 16:13:35 -04:00
Chris Giacofei
b3255d94d4 Initial changes, merging PID and Autotune. 2024-05-01 15:38:01 -04:00
Chris Giacofei
7787498eda incorporate tuning into main library.
Not yet tested.
2024-04-26 08:42:17 -04:00
Brett
9b4ca0e5b6 version 2017-06-20 07:12:13 -07:00
Brett
691f1d7af8 version / license
Incorrect version and license in cpp and h
2017-06-20 07:09:25 -07:00
4 changed files with 355 additions and 218 deletions

View File

@ -1,67 +1,66 @@
/**********************************************************************************************
* Arduino PID Library - Version 1.1.1
* by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com
*
* This Library is licensed under a GPLv3 License
**********************************************************************************************/
* Arduino PID Library - Version 1.2.1
* by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com
*
* This Library is licensed under the MIT License
**********************************************************************************************/
#if ARDUINO >= 100
#include "Arduino.h"
#else
#else
#include "WProgram.h"
#endif
#include <PID_v1.h>
#include "PID_v1.h"
/*Constructor (...)*********************************************************
* The parameters specified here are those for for which we can't set up
* reliable defaults, so we need to have the user set them.
***************************************************************************/
* The parameters specified here are those for for which we can't set up
* reliable defaults, so we need to have the user set them.
***************************************************************************/
PID::PID(double* Input, double* Output, double* Setpoint,
double Kp, double Ki, double Kd, int POn, int ControllerDirection)
{
double Kp, double Ki, double Kd, int POn, int ControllerDirection) {
myOutput = Output;
myInput = Input;
mySetpoint = Setpoint;
inAuto = false;
PID::SetOutputLimits(0, 255); //default output limit corresponds to
//the arduino pwm limits
SampleTime = 100; //default Controller Sample Time is 0.1 seconds
PID::SetControllerDirection(ControllerDirection);
//Tuner = new PID_ATune(Input, Output);
PID::OutputLimits(0, 100);
PID::Direction(ControllerDirection);
PID::SetTunings(Kp, Ki, Kd, POn);
// Autotune defaults
noise_band = 0.5;
autotune_running = false;
oStep = 30;
LookbackSec(10);
SampleTime = 100; //default Controller Sample Time is 0.1 seconds
lastTime = millis()-SampleTime;
}
/*Constructor (...)*********************************************************
* To allow backwards compatability for v1.1, or for people that just want
* to use Proportional on Error without explicitly saying so
***************************************************************************/
* To allow backwards compatability for v1.1, or for people that just want
* to use Proportional on Error without explicitly saying so
***************************************************************************/
PID::PID(double* Input, double* Output, double* Setpoint,
double Kp, double Ki, double Kd, int ControllerDirection)
:PID::PID(Input, Output, Setpoint, Kp, Ki, Kd, P_ON_E, ControllerDirection)
{
double Kp, double Ki, double Kd, int ControllerDirection)
:PID::PID(Input, Output, Setpoint, Kp, Ki, Kd, P_ON_E, ControllerDirection) {
}
/* 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. returns true when the output is computed,
* false when nothing has been done.
**********************************************************************************/
bool PID::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. returns true when the output is computed,
* false when nothing has been done.
**********************************************************************************/
bool PID::Compute() {
if(!inAuto) return false;
unsigned long now = millis();
unsigned long timeChange = (now - lastTime);
if(timeChange>=SampleTime)
{
if(timeChange>=SampleTime) {
/*Compute all the working error variables*/
double input = *myInput;
double error = *mySetpoint - input;
@ -94,27 +93,116 @@ bool PID::Compute()
else return false;
}
int PID::ComputeTune() {
//~ justevaled=false;
if(peakCount>9 && autotune_running) {
autotune_running = false;
FinishUp();
return 1;
}
unsigned long now = millis();
if((now-lastTime)<SampleTime) return false;
lastTime = now;
double refVal = *myInput;
//~ justevaled=true;
if(!autotune_running) {
//initialize working variables the first time around
peakType = 0;
peakCount=0;
atune_peak_change=false;
absMax=refVal;
absMin=refVal;
*mySetpoint = refVal;
autotune_running = true;
outputStart = *myOutput;
*myOutput = outputStart+oStep;
} else {
if(refVal>absMax)absMax=refVal;
if(refVal<absMin)absMin=refVal;
}
//oscillate the output base on the input's relation to the setpoint
if(refVal>*mySetpoint+noise_band) *myOutput = outputStart-oStep;
else if (refVal<*mySetpoint-noise_band) *myOutput = outputStart+oStep;
//bool isMax=true, isMin=true;
isMax=true;isMin=true;
//id peaks
for(int i=nLookBack-1;i>=0;i--) {
double val = lastInputs[i];
if(isMax) isMax = refVal>val;
if(isMin) isMin = refVal<val;
lastInputs[i+1] = lastInputs[i];
}
lastInputs[0] = refVal;
if(nLookBack<9){
//we don't want to trust the maxes or mins until the inputs array has been filled
return 0;
}
if(isMax) {
if(peakType==0)peakType=1;
if(peakType==-1) {
peakType = 1;
atune_peak_change=true;
peak2 = peak1;
}
peak1 = now;
peaks[peakCount] = refVal;
} else if(isMin) {
if(peakType==0)peakType=-1;
if(peakType==1){
peakType=-1;
peakCount++;
atune_peak_change=true;
}
if(peakCount<10)peaks[peakCount] = refVal;
}
if(atune_peak_change && peakCount>2) {
//we've transitioned. check if we can autotune based on the last peaks
double avgSeparation = (abs(peaks[peakCount-1]-peaks[peakCount-2])+abs(peaks[peakCount-2]-peaks[peakCount-3]))/2;
if( avgSeparation < 0.05*(absMax-absMin)){
FinishUp();
autotune_running = false;
return 1;
}
}
atune_peak_change=false;
return 0;
}
void PID::FinishUp(){
*myOutput = outputStart;
//we can generate tuning parameters!
Ku = 4*(2*oStep)/((absMax-absMin)*3.14159);
Pu = (double)(peak1-peak2) / 1000;
}
/* 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
******************************************************************************/
void PID::SetTunings(double Kp, double Ki, double Kd, int POn)
{
* 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
******************************************************************************/
void PID::SetTunings(double Kp, double Ki, double Kd, int POn){
if (Kp<0 || Ki<0 || Kd<0) return;
pOn = POn;
pOnE = POn == P_ON_E;
dispKp = Kp; dispKi = Ki; dispKd = Kd;
double SampleTimeInSec = ((double)SampleTime)/1000;
kp = Kp;
ki = Ki * SampleTimeInSec;
kd = Kd / SampleTimeInSec;
if(controllerDirection ==REVERSE)
{
if(controllerDirection ==REVERSE){
kp = (0 - kp);
ki = (0 - ki);
kd = (0 - kd);
@ -122,19 +210,17 @@ void PID::SetTunings(double Kp, double Ki, double Kd, int POn)
}
/* SetTunings(...)*************************************************************
* Set Tunings using the last-rembered POn setting
******************************************************************************/
* Set Tunings using the last-rembered POn setting
******************************************************************************/
void PID::SetTunings(double Kp, double Ki, double Kd){
SetTunings(Kp, Ki, Kd, pOn);
}
/* SetSampleTime(...) *********************************************************
* sets the period, in Milliseconds, at which the calculation is performed
******************************************************************************/
void PID::SetSampleTime(int NewSampleTime)
{
if (NewSampleTime > 0)
{
* sets the period, in Milliseconds, at which the calculation is performed
******************************************************************************/
void PID::SetSampleTime(int NewSampleTime){
if (NewSampleTime > 0){
double ratio = (double)NewSampleTime
/ (double)SampleTime;
ki *= ratio;
@ -143,22 +229,20 @@ void PID::SetSampleTime(int NewSampleTime)
}
}
/* SetOutputLimits(...)****************************************************
* This function will be used far more often than SetInputLimits. while
* the input to the controller will generally be in the 0-1023 range (which is
* the default already,) the output will be a little different. maybe they'll
* be doing a time window and will need 0-8000 or something. or maybe they'll
* want to clamp it from 0-125. who knows. at any rate, that can all be done
* here.
**************************************************************************/
void PID::SetOutputLimits(double Min, double Max)
{
/* OutputLimits(...)*******************************************************
* This function will be used far more often than SetInputLimits. while
* the input to the controller will generally be in the 0-1023 range (which is
* the default already,) the output will be a little different. maybe they'll
* be doing a time window and will need 0-8000 or something. or maybe they'll
* want to clamp it from 0-125. who knows. at any rate, that can all be done
* here.
**************************************************************************/
void PID::OutputLimits(double Min, double Max){
if(Min >= Max) return;
outMin = Min;
outMax = Max;
if(inAuto)
{
if(inAuto){
if(*myOutput > outMax) *myOutput = outMax;
else if(*myOutput < outMin) *myOutput = outMin;
@ -167,43 +251,49 @@ void PID::SetOutputLimits(double Min, double Max)
}
}
/* SetMode(...)****************************************************************
* Allows the controller Mode to be set to manual (0) or Automatic (non-zero)
* when the transition from manual to auto occurs, the controller is
* automatically initialized
******************************************************************************/
void PID::SetMode(int Mode)
{
bool newAuto = (Mode == AUTOMATIC);
if(newAuto && !inAuto)
{ /*we just went from manual to auto*/
/* Mode(...)*******************************************************************
* Allows the controller Mode to be set to manual (0) or Automatic (non-zero)
* when the transition from manual to auto occurs, the controller is
* automatically initialized
******************************************************************************/
void PID::Mode(int Mode){
bool newAuto = (Mode == 1);
if(newAuto && !inAuto){ /*we just went from manual to auto*/
PID::Initialize();
}
inAuto = newAuto;
OpMode = Mode;
}
int PID::CycleMode() {
if (OpMode + 1 == 3) {
PID::Mode(0);
} else {
PID::Mode(OpMode + 1);
}
return OpMode;
}
/* Initialize()****************************************************************
* does all the things that need to happen to ensure a bumpless transfer
* from manual to automatic mode.
******************************************************************************/
void PID::Initialize()
{
* does all the things that need to happen to ensure a bumpless transfer
* from manual to automatic mode.
******************************************************************************/
void PID::Initialize(){
outputSum = *myOutput;
lastInput = *myInput;
if(outputSum > outMax) outputSum = outMax;
else if(outputSum < outMin) outputSum = outMin;
}
/* SetControllerDirection(...)*************************************************
* The PID will either be connected to a DIRECT acting process (+Output leads
* to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to
* know which one, because otherwise we may increase the output when we should
* be decreasing. This is called from the constructor.
******************************************************************************/
void PID::SetControllerDirection(int Direction)
{
if(inAuto && Direction !=controllerDirection)
{
/* Direction(...)**************************************************************
* The PID will either be connected to a DIRECT acting process (+Output leads
* to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to
* know which one, because otherwise we may increase the output when we should
* be decreasing. This is called from the constructor.
******************************************************************************/
void PID::Direction(int Direction){
if(inAuto && Direction !=controllerDirection){
kp = (0 - kp);
ki = (0 - ki);
kd = (0 - kd);
@ -212,13 +302,34 @@ void PID::SetControllerDirection(int Direction)
}
/* Status Funcions*************************************************************
* Just because you set the Kp=-1 doesn't mean it actually happened. these
* functions query the internal state of the PID. they're here for display
* purposes. this are the functions the PID Front-end uses for example
******************************************************************************/
double PID::GetKp(){ return dispKp; }
double PID::GetKi(){ return dispKi;}
double PID::GetKd(){ return dispKd;}
int PID::GetMode(){ return inAuto ? AUTOMATIC : MANUAL;}
int PID::GetDirection(){ return controllerDirection;}
* Just because you set the Kp=-1 doesn't mean it actually happened. these
* functions query the internal state of the PID. they're here for display
* purposes. this are the functions the PID Front-end uses for example
******************************************************************************/
double PID::Kp(){ return kp; }
double PID::Ki(){ return ki;}
double PID::Kd(){ return kd;}
modes PID::Mode(){ return OpMode;}
int PID::Direction(){ return controllerDirection;}
void PID::Cancel(){ autotune_running = false;}
double PID::TunedKp(){ return 0.6 * Ku;}
double PID::TunedKi(){ return 1.2*Ku / Pu ;} // Ki = Kc/Ti}
double PID::TunedKd(){ return 0.075 * Ku * Pu;} //Kd = Kc * Td}
void PID::OutputStep(double Step){ oStep = Step;}
double PID::OutputStep(){ return oStep;}
void PID::NoiseBand(double Band){ noise_band = Band;}
double PID::NoiseBand(){ return noise_band;}
void PID::LookbackSec(int value){
if (value<1) value = 1;
if(value<25) {
nLookBack = value * 4;
SampleTime = 250;
} else {
nLookBack = 100;
SampleTime = value*10;
}
}
int PID::LookbackSec(){ return nLookBack * SampleTime / 1000;}

View File

@ -1,16 +1,14 @@
#ifndef PID_v1_h
#define PID_v1_h
#define LIBRARY_VERSION 1.1.1
#define LIBRARY_VERSION 1.2.1
enum modes : uint8_t {OFF, AUTOMATIC, MANUAL, OVERFLOW};
class PID
{
public:
//Constants used in some of the functions below
#define AUTOMATIC 1
#define MANUAL 0
#define DIRECT 0
#define REVERSE 1
#define P_ON_M 0
@ -24,14 +22,14 @@ class PID
PID(double*, double*, double*, // * constructor. links the PID to the Input, Output, and
double, double, double, int); // Setpoint. Initial tuning parameters are also set here
void SetMode(int Mode); // * sets PID to either Manual (0) or Auto (non-0)
void Mode(int Mode); // * sets PID to either Manual or Auto
int CycleMode();
bool Compute(); // * performs the PID calculation. it should be
// called every time loop() cycles. ON/OFF and
// calculation frequency can be set using SetMode
// SetSampleTime respectively
void SetOutputLimits(double, double); // * clamps the output to a specific range. 0-255 by default, but
int ComputeTune();
void OutputLimits(double, double); // * clamps the output to a specific range. 0-255 by default, but
// it's likely the user will want to change this depending on
// the application
@ -44,29 +42,39 @@ class PID
void SetTunings(double, double, // * overload for specifying proportional mode
double, int);
void SetControllerDirection(int); // * Sets the Direction, or "Action" of the controller. DIRECT
void Direction(int); // * Sets the Direction, or "Action" of the controller. DIRECT
// means the output will increase when error is positive. REVERSE
// means the opposite. it's very unlikely that this will be needed
// once it is set in the constructor.
void SetSampleTime(int); // * sets the frequency, in Milliseconds, with which
// the PID calculation is performed. default is 100
//Display functions ****************************************************************
double GetKp(); // These functions query the pid for interal values.
double GetKi(); // they were created mainly for the pid front-end,
double GetKd(); // where it's important to know what is actually
int GetMode(); // inside the PID.
int GetDirection(); //
double Kp(); // These functions query the pid for interal values.
double Ki(); // they were created mainly for the pid front-end,
double Kd(); // where it's important to know what is actually
modes Mode(); // inside the PID.
int Direction(); //
// Auto Tune Public
void Cancel(); // * Stops the AutoTune
void OutputStep(double); // * how far above and below the starting value will the output step?
double OutputStep(); //
void LookbackSec(int); // * how far back are we looking to identify peaks
int LookbackSec(); //
void NoiseBand(double); // * the autotune will ignore signal chatter smaller than this value
double NoiseBand(); // this should be acurately set
double TunedKp(); // * once autotune is complete, these functions contain the
double TunedKi(); // computed tuning parameters.
double TunedKd();
private:
void Initialize();
double dispKp; // * we'll hold on to the tuning parameters in user-entered
double dispKi; // format for display purposes
double dispKd; //
double kp; // * (P)roportional Tuning Parameter
double ki; // * (I)ntegral Tuning Parameter
double kd; // * (D)erivative Tuning Parameter
@ -82,9 +90,27 @@ class PID
unsigned long lastTime;
double outputSum, lastInput;
unsigned long SampleTime;
double outMin, outMax;
bool inAuto, pOnE;
modes OpMode;
// Autotune stuff
void FinishUp();
bool isMax, isMin;
double noise_band;
bool autotune_running;
unsigned long peak1, peak2;
int SampleTime;
int nLookBack;
int peakType;
double lastInputs[101];
double peaks[10];
int peakCount;
bool atune_peak_change;
double absMax, absMin;
double oStep;
double outputStart;
double Ku, Pu;
};
#endif

View File

@ -1,11 +1,11 @@
***************************************************************
* Arduino PID Library - Version 1.2.0
* Arduino PID Library - Version 1.2.1
* by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com
*
* This Library is licensed under the MIT License
***************************************************************
- For an ultra-detailed explanation of why the code is the way it is, please visit:
http://brettbeauregard.com/blog/2011/04/improving-the-beginners-pid-introduction/
https://web.archive.org/web/20200607033952/http://brettbeauregard.com/blog/2011/04/improving-the-beginners-pid-introduction
- For function documentation see: http://playground.arduino.cc/Code/PIDLibrary

View File

@ -1,5 +1,5 @@
name=PID
version=1.2.0
version=1.2.1
author=Brett Beauregard
maintainer=Brett Beauregard
sentence=PID controller