Skip to content

Commit

Permalink
Initial Commit
Browse files Browse the repository at this point in the history
It still needs a lot of work, but it's a start
  • Loading branch information
br3ttb committed Jan 6, 2012
0 parents commit 167d074
Show file tree
Hide file tree
Showing 4 changed files with 440 additions and 0 deletions.
149 changes: 149 additions & 0 deletions PID_AutoTune_v0/Examples/AutoTune_Example/AutoTune_Example.pde
@@ -0,0 +1,149 @@
#include <PID_v1.h>
#include <PID_AutoTune_v0.h>

byte ATuneModeRemember=0;
double input=80, output=50, setpoint=180;
double kp=2,ki=0.5,kd=2;

double kpmodel=1.5, taup=100, theta[50];
double outputStart=5;
double aTuneStep=20, aTuneNoise=1;
unsigned int aTuneLookBack=10;

boolean tuning = false;
unsigned long modelTime, serialTime;

PID myPID(&input, &output, &setpoint,kp,ki,kd, DIRECT);
PID_ATune aTune(&input, &output);

//set to false to connect to the real world
boolean useSimulation = true;

void setup()
{
if(useSimulation)
{
for(byte i=0;i<50;i++)
{
theta[i]=outputStart;
}
modelTime = 0;
}
serialTime = 0;
}

void loop()
{
unsigned long now = millis();

if(!useSimulation)
{ //pull the input in from the real world
input = analogRead(0);
}

if(tuning)
{
byte val = (aTune.Runtime());
if (val!=0)
{
tuning = false;
}
if(!tuning)
{ //we're done, set the tuning parameters
kp = aTune.GetKp();
ki = aTune.GetKi();
kd = aTune.GetKd();
myPID.SetTunings(kp,ki,kd);
AutoTuneHelper(false);
}
}
else myPID.Compute();

if(useSimulation)
{
theta[30]=output;
if(now>=modelTime)
{
modelTime +=100;
DoModel();
}
}
else
{
analogWrite(0,output);
}

//send-receive with processing if it's time
if(millis()>serialTime)
{
SerialReceive();
SerialSend();
serialTime+=500;
}
}

void changeAutoTune()
{
if(!tuning)
{
//initiate autotune
AutoTuneHelper(true);
aTune.SetNoiseBand(aTuneNoise);
aTune.SetOutputStep(aTuneStep);
aTune.SetLookbackSec((int)aTuneLookBack);
tuning = true;
}
else
{ //cancel autotune
aTune.Cancel();
tuning = false;
AutoTuneHelper(false);
}
}

void AutoTuneHelper(boolean start)
{
if(start)
{
ATuneModeRemember = myPID.GetMode();
myPID.SetMode(MANUAL);
}
else
{
myPID.SetMode(ATuneModeRemember);
}
}


void SerialSend()
{
Serial.print(setpoint); Serial.print(" ");
Serial.print(input); Serial.print(" ");
Serial.print(output); Serial.print(" ");
Serial.println(tuning);
}

void SerialReceive()
{
if(Serial.available())
{
int b = Serial.read();
Serial.flush();
if((b==1 && !tuning) || (b!=1 && tuning))changeAutoTune();
}
}

void DoModel()
{
//cycle the dead time
for(byte i=0;i<49;i++)
{
theta[i] = theta[i+1];
}
//compute the input
input = (kpmodel / taup) *(theta[0]-outputStart) + input*(1-1/taup) + ((float)random(-10,10))/100;

}



198 changes: 198 additions & 0 deletions PID_AutoTune_v0/PID_AutoTune_v0.cpp
@@ -0,0 +1,198 @@
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif

#include <PID_AutoTune_v0.h>


PID_ATune::PID_ATune(double* Input, double* Output)
{
input = Input;
output = Output;
controlType =0 ; //default to PI
noiseBand = 0.5;
running = false;
oStep = 30;
SetLookbackSec(10);
lastTime = millis();

}



void PID_ATune::Cancel()
{
running = false;
}

int PID_ATune::Runtime()
{
justevaled=false;
if(peakCount>9 && running)
{
running = false;
FinishUp();
return 1;
}
unsigned long now = millis();

if((now-lastTime)<sampleTime) return false;
lastTime = now;
double refVal = *input;
justevaled=true;
if(!running)
{ //initialize working variables the first time around
peakType = 0;
peakCount=0;
justchanged=false;
absMax=refVal;
absMin=refVal;
setpoint = refVal;
running = true;
initCount=0;
outputStart = *output;
*output = 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>setpoint+noiseBand) *output = outputStart-oStep;
else if (refVal<setpoint-noiseBand) *output = 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
initCount++;
return 0;
}

if(isMax)
{
if(peakType==0)peakType=1;
if(peakType==-1)
{
peakType = 1;
justchanged=true;
peak2 = peak1;
}
peak1 = now;
peaks[peakCount] = refVal;

}
else if(isMin)
{
if(peakType==0)peakType=-1;
if(peakType==1)
{
peakType=-1;
peakCount++;
justchanged=true;
}

if(peakCount<10)peaks[peakCount] = refVal;
}

if(justchanged && 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();
running = false;
return 1;

}
}
justchanged=false;
return 0;
}
void PID_ATune::FinishUp()
{
*output = outputStart;
//we can generate tuning parameters!
Ku = 4*oStep/((absMax-absMin)*3.14159);
Pu = (double)(peak1-peak2) / 1000;
}

double PID_ATune::GetKp()
{
return controlType==1 ? 0.6 * Ku : 0.4 * Ku;
}

double PID_ATune::GetKi()
{
return controlType==1? 1.2*Ku / Pu : 0.48 * Ku / Pu; // Ki = Kc/Ti
}

double PID_ATune::GetKd()
{
return controlType==1? 0.075 * Ku * Pu : 0; //Kd = Kc * Td
}

void PID_ATune::SetOutputStep(double Step)
{
oStep = Step;
}

double PID_ATune::GetOutputStep()
{
return oStep;
}

void PID_ATune::SetControlType(int Type) //0=PI, 1=PID
{
controlType = Type;
}
int PID_ATune::GetControlType()
{
return controlType;
}

void PID_ATune::SetNoiseBand(double Band)
{
noiseBand = Band;
}

double PID_ATune::GetNoiseBand()
{
return noiseBand;
}

void PID_ATune::SetLookbackSec(int value)
{
if (value<1) value = 1;

if(value<25)
{
nLookBack = value * 4;
sampleTime = 250;
}
else
{
nLookBack = 100;
sampleTime = value*10;
}
}

int PID_ATune::GetLookbackSec()
{
return nLookBack * sampleTime / 1000;
}

0 comments on commit 167d074

Please sign in to comment.