fixed issue #3 and issue #4

-Changed Compute() to a bool from a void,  allowing the calling function
to know when the pid calculation has just been evaluated

-cleaned up the initialization code in the constructor
This commit is contained in:
Brett Beauregard 2012-10-04 20:47:12 -04:00
parent 169cdd0908
commit d4ce7050a5
3 changed files with 14 additions and 10 deletions

View File

@ -20,6 +20,12 @@
PID::PID(double* Input, double* Output, double* Setpoint,
double Kp, double Ki, double Kd, int ControllerDirection)
{
myOutput = Output;
myInput = Input;
mySetpoint = Setpoint;
inAuto = false;
PID::SetOutputLimits(0, 255); //default output limit corresponds to
//the arduino pwm limits
@ -29,22 +35,18 @@ PID::PID(double* Input, double* Output, double* Setpoint,
PID::SetTunings(Kp, Ki, Kd);
lastTime = millis()-SampleTime;
inAuto = false;
myOutput = Output;
myInput = Input;
mySetpoint = Setpoint;
}
/* 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
* pid Output needs to be computed. returns true when the output is computed,
* false when nothing has been done.
**********************************************************************************/
void PID::Compute()
bool PID::Compute()
{
if(!inAuto) return;
if(!inAuto) return false;
unsigned long now = millis();
unsigned long timeChange = (now - lastTime);
if(timeChange>=SampleTime)
@ -67,7 +69,9 @@ void PID::Compute()
/*Remember some variables for next time*/
lastInput = input;
lastTime = now;
return true;
}
else return false;
}

View File

@ -20,7 +20,7 @@ class PID
void SetMode(int Mode); // * sets PID to either Manual (0) or Auto (non-0)
void Compute(); // * performs the PID calculation. it should be
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

View File

@ -1,5 +1,5 @@
***************************************************************
* Arduino PID Library - Version 1.0.1
* Arduino PID Library - Version 1.1.0
* by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com