mirror of https://github.com/rusefi/speeduino.git
Multiple fixes for closed loop PWM idle
This commit is contained in:
parent
0677499036
commit
147febb97d
14
idle.ino
14
idle.ino
|
@ -13,7 +13,7 @@ Idle Control
|
|||
Currently limited to on/off control and open loop PWM and stepper drive
|
||||
*/
|
||||
long longRPM;
|
||||
PID idlePID(&longRPM, &idle_pwm_target_value, &idle_cl_target_rpm, configPage3.idleKP, configPage3.idleKI, configPage3.idleKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
|
||||
integerPID idlePID(&longRPM, &idle_pwm_target_value, &idle_cl_target_rpm, configPage3.idleKP, configPage3.idleKI, configPage3.idleKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
|
||||
|
||||
void initialiseIdle()
|
||||
{
|
||||
|
@ -45,6 +45,7 @@ void initialiseIdle()
|
|||
iacPWMTable.axisX = configPage4.iacBins;
|
||||
|
||||
iacCrankDutyTable.xSize = 4;
|
||||
iacCrankDutyTable.valueSize = SIZE_BYTE;
|
||||
iacCrankDutyTable.values = configPage4.iacCrankDuty;
|
||||
iacCrankDutyTable.axisX = configPage4.iacCrankBins;
|
||||
|
||||
|
@ -59,10 +60,12 @@ void initialiseIdle()
|
|||
case 3:
|
||||
//Case 3 is PWM closed loop
|
||||
iacClosedLoopTable.xSize = 10;
|
||||
iacClosedLoopTable.valueSize = SIZE_BYTE;
|
||||
iacClosedLoopTable.values = configPage4.iacCLValues;
|
||||
iacClosedLoopTable.axisX = configPage4.iacBins;
|
||||
|
||||
iacCrankDutyTable.xSize = 4;
|
||||
iacCrankDutyTable.valueSize = SIZE_BYTE;
|
||||
iacCrankDutyTable.values = configPage4.iacCrankDuty;
|
||||
iacCrankDutyTable.axisX = configPage4.iacCrankBins;
|
||||
|
||||
|
@ -72,7 +75,6 @@ void initialiseIdle()
|
|||
idle2_pin_mask = digitalPinToBitMask(pinIdle2);
|
||||
idle_pwm_max_count = 1000000L / (16 * configPage3.idleFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 512hz
|
||||
idlePID.SetOutputLimits(0, idle_pwm_max_count);
|
||||
TIMSK4 |= (1 << OCIE4C); //Turn on the C compare unit (ie turn on the interrupt)
|
||||
idlePID.SetMode(AUTOMATIC); //Turn PID on
|
||||
break;
|
||||
|
||||
|
@ -148,11 +150,15 @@ void idleControl()
|
|||
|
||||
case 3: //Case 3 is PWM closed loop
|
||||
//No cranking specific value for closed loop (yet?)
|
||||
idle_cl_target_rpm = table2D_getValue(&iacClosedLoopTable, currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET) * 2; //All temps are offset by 40 degrees
|
||||
idle_cl_target_rpm = table2D_getValue(&iacClosedLoopTable, currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET) * 10; //All temps are offset by 40 degrees
|
||||
longRPM = currentStatus.RPM; //The PID object needs a long as the RPM input. A separate variable is used for this
|
||||
//idle_pwm_target_value = percentage(currentStatus.idleDuty, idle_pwm_max_count);
|
||||
idlePID.SetOutputLimits(0, idle_pwm_max_count);
|
||||
idlePID.SetTunings(configPage3.idleKP, configPage3.idleKI, configPage3.idleKD);
|
||||
|
||||
idlePID.Compute();
|
||||
if( idle_pwm_target_value == 0 ) { TIMSK4 &= ~(1 << OCIE4C); digitalWrite(pinIdle1, LOW); }
|
||||
else{ TIMSK4 |= (1 << OCIE4C); } //Turn on the C compare unit (ie turn on the interrupt)
|
||||
//idle_pwm_target_value = 104;
|
||||
break;
|
||||
|
||||
case 4: //Case 4 is open loop stepper control
|
||||
|
|
|
@ -199,3 +199,190 @@ byte PID::GetKd(){ return dispKd;}
|
|||
int PID::GetMode(){ return inAuto ? AUTOMATIC : MANUAL;}
|
||||
int PID::GetDirection(){ return controllerDirection;}
|
||||
|
||||
/*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.
|
||||
***************************************************************************/
|
||||
integerPID::integerPID(long* Input, long* Output, long* Setpoint,
|
||||
byte Kp, byte Ki, byte Kd, byte ControllerDirection)
|
||||
{
|
||||
|
||||
myOutput = Output;
|
||||
myInput = Input;
|
||||
mySetpoint = Setpoint;
|
||||
inAuto = false;
|
||||
|
||||
integerPID::SetOutputLimits(0, 255); //default output limit corresponds to
|
||||
//the arduino pwm limits
|
||||
|
||||
//SampleTime = 100; //default Controller Sample Time is 0.1 seconds
|
||||
|
||||
integerPID::SetControllerDirection(ControllerDirection);
|
||||
integerPID::SetTunings(Kp, Ki, Kd);
|
||||
|
||||
//lastTime = millis()-SampleTime;
|
||||
}
|
||||
|
||||
|
||||
/* 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 integerPID::Compute()
|
||||
{
|
||||
if(!inAuto) return false;
|
||||
unsigned long now = millis();
|
||||
SampleTime = (now - lastTime);
|
||||
//if(timeChange>=SampleTime)
|
||||
{
|
||||
/*Compute all the working error variables*/
|
||||
long input = *myInput;
|
||||
long error = *mySetpoint - input;
|
||||
ITerm+= (ki * error)/100;
|
||||
//ITerm+= divs100(ki * error);
|
||||
if(ITerm > outMax) ITerm= outMax;
|
||||
else if(ITerm < outMin) ITerm= outMin;
|
||||
long dInput = (input - lastInput);
|
||||
|
||||
/*Compute PID Output*/
|
||||
long output = (kp * error)/100 + ITerm- (kd * dInput)/100;
|
||||
//long output = divs100(kp * error) + ITerm- divs100(kd * dInput);
|
||||
|
||||
if(output > outMax) output = outMax;
|
||||
else if(output < outMin) output = outMin;
|
||||
*myOutput = output;
|
||||
|
||||
/*Remember some variables for next time*/
|
||||
lastInput = input;
|
||||
//lastTime = now;
|
||||
return true;
|
||||
}
|
||||
//else return false;
|
||||
}
|
||||
|
||||
|
||||
/* 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 integerPID::SetTunings(byte Kp, byte Ki, byte Kd)
|
||||
{
|
||||
if (Kp<0 || Ki<0 || Kd<0) return;
|
||||
|
||||
dispKp = Kp; dispKi = Ki; dispKd = Kd;
|
||||
|
||||
/*
|
||||
double SampleTimeInSec = ((double)SampleTime)/1000;
|
||||
kp = Kp;
|
||||
ki = Ki * SampleTimeInSec;
|
||||
kd = Kd / SampleTimeInSec;
|
||||
*/
|
||||
long InverseSampleTimeInSec = 100000 / SampleTime;
|
||||
kp = Kp;
|
||||
ki = (Ki * 100) / InverseSampleTimeInSec;
|
||||
kd = (Kd * InverseSampleTimeInSec) / 100;
|
||||
|
||||
if(controllerDirection ==REVERSE)
|
||||
{
|
||||
kp = (0 - kp);
|
||||
ki = (0 - ki);
|
||||
kd = (0 - kd);
|
||||
}
|
||||
}
|
||||
|
||||
/* SetSampleTime(...) *********************************************************
|
||||
* sets the period, in Milliseconds, at which the calculation is performed
|
||||
******************************************************************************/
|
||||
void integerPID::SetSampleTime(int NewSampleTime)
|
||||
{
|
||||
if (NewSampleTime > 0)
|
||||
{
|
||||
unsigned long ratioX1000 = (unsigned long)(NewSampleTime * 1000) / (unsigned long)SampleTime;
|
||||
ki = (ki * ratioX1000) / 1000;
|
||||
//kd /= ratio;
|
||||
kd = (kd * 1000) / ratioX1000;
|
||||
SampleTime = (unsigned long)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 integerPID::SetOutputLimits(long Min, long Max)
|
||||
{
|
||||
if(Min >= Max) return;
|
||||
outMin = Min;
|
||||
outMax = Max;
|
||||
|
||||
if(inAuto)
|
||||
{
|
||||
if(*myOutput > outMax) *myOutput = outMax;
|
||||
else if(*myOutput < outMin) *myOutput = outMin;
|
||||
|
||||
if(ITerm > outMax) ITerm= outMax;
|
||||
else if(ITerm < outMin) ITerm= outMin;
|
||||
}
|
||||
}
|
||||
|
||||
/* 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 integerPID::SetMode(int Mode)
|
||||
{
|
||||
bool newAuto = (Mode == AUTOMATIC);
|
||||
if(newAuto == !inAuto)
|
||||
{ /*we just went from manual to auto*/
|
||||
integerPID::Initialize();
|
||||
}
|
||||
inAuto = newAuto;
|
||||
}
|
||||
|
||||
/* Initialize()****************************************************************
|
||||
* does all the things that need to happen to ensure a bumpless transfer
|
||||
* from manual to automatic mode.
|
||||
******************************************************************************/
|
||||
void integerPID::Initialize()
|
||||
{
|
||||
ITerm = *myOutput;
|
||||
lastInput = *myInput;
|
||||
if(ITerm > outMax) ITerm = outMax;
|
||||
else if(ITerm < outMin) ITerm = 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 integerPID::SetControllerDirection(byte Direction)
|
||||
{
|
||||
if(inAuto && Direction !=controllerDirection)
|
||||
{
|
||||
kp = (0 - kp);
|
||||
ki = (0 - ki);
|
||||
kd = (0 - kd);
|
||||
}
|
||||
controllerDirection = 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
|
||||
******************************************************************************/
|
||||
byte integerPID::GetKp(){ return dispKp; }
|
||||
byte integerPID::GetKi(){ return dispKi;}
|
||||
byte integerPID::GetKd(){ return dispKd;}
|
||||
int integerPID::GetMode(){ return inAuto ? AUTOMATIC : MANUAL;}
|
||||
int integerPID::GetDirection(){ return controllerDirection;}
|
||||
|
|
|
@ -44,6 +44,81 @@ class PID
|
|||
|
||||
|
||||
|
||||
//Display functions ****************************************************************
|
||||
byte GetKp(); // These functions query the pid for interal values.
|
||||
byte GetKi(); // they were created mainly for the pid front-end,
|
||||
byte GetKd(); // where it's important to know what is actually
|
||||
int GetMode(); // inside the PID.
|
||||
int GetDirection(); //
|
||||
|
||||
private:
|
||||
void Initialize();
|
||||
|
||||
byte dispKp; // * we'll hold on to the tuning parameters in user-entered
|
||||
byte dispKi; // format for display purposes
|
||||
byte dispKd; //
|
||||
|
||||
byte kp; // * (P)roportional Tuning Parameter
|
||||
byte ki; // * (I)ntegral Tuning Parameter
|
||||
byte kd; // * (D)erivative Tuning Parameter
|
||||
|
||||
int controllerDirection;
|
||||
|
||||
long *myInput; // * Pointers to the Input, Output, and Setpoint variables
|
||||
long *myOutput; // This creates a hard link between the variables and the
|
||||
long *mySetpoint; // PID, freeing the user from having to constantly tell us
|
||||
// what these values are. with pointers we'll just know.
|
||||
|
||||
unsigned long lastTime;
|
||||
long ITerm, lastInput;
|
||||
|
||||
unsigned long SampleTime;
|
||||
long outMin, outMax;
|
||||
bool inAuto;
|
||||
};
|
||||
|
||||
class integerPID
|
||||
{
|
||||
|
||||
|
||||
public:
|
||||
|
||||
//Constants used in some of the functions below
|
||||
#define AUTOMATIC 1
|
||||
#define MANUAL 0
|
||||
#define DIRECT 0
|
||||
#define REVERSE 1
|
||||
|
||||
//commonly used functions **************************************************************************
|
||||
integerPID(long*, long*, long*, // * constructor. links the PID to the Input, Output, and
|
||||
byte, byte, byte, byte); // Setpoint. Initial tuning parameters are also set here
|
||||
|
||||
void SetMode(int Mode); // * sets PID to either Manual (0) or Auto (non-0)
|
||||
|
||||
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(long, long); //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
|
||||
|
||||
|
||||
|
||||
//available but not commonly used functions ********************************************************
|
||||
void SetTunings(byte, byte, // * While most users will set the tunings once in the
|
||||
byte); // constructor, this function gives the user the option
|
||||
// of changing tunings during runtime for Adaptive control
|
||||
void SetControllerDirection(byte); // * 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 ****************************************************************
|
||||
byte GetKp(); // These functions query the pid for interal values.
|
||||
byte GetKi(); // they were created mainly for the pid front-end,
|
||||
|
|
Loading…
Reference in New Issue