refactoring
This commit is contained in:
parent
55010eda5b
commit
5ba67f98db
|
@ -227,12 +227,8 @@ static msg_t ivThread(int param) {
|
|||
}
|
||||
|
||||
if (engineConfiguration->isVerboseIAC && engineConfiguration->idleMode == IM_AUTO) {
|
||||
idlePid.showPidStatus(logger, "idle",engineConfiguration->idleDT);
|
||||
scheduleMsg(logger, "rpm=%d/%d position=%f iTerm=%.5f dTerm=%.5f",
|
||||
getRpmE(engine),
|
||||
adjustedTargetRpm,
|
||||
iacPosition,
|
||||
idlePid.iTerm, idlePid.dTerm);
|
||||
idlePid.showPidStatus(logger, "idle", engineConfiguration->idleDT);
|
||||
|
||||
}
|
||||
|
||||
actualIdlePosition = iacPosition;
|
||||
|
|
|
@ -24,7 +24,7 @@ void Pid::init(pid_s *pid, float minResult, float maxResult) {
|
|||
this->maxResult = maxResult;
|
||||
|
||||
dTerm = iTerm = 0;
|
||||
prevError = 0;
|
||||
prevResult = prevInput = prevTarget = prevError = 0;
|
||||
}
|
||||
|
||||
bool Pid::isSame(pid_s *pid) {
|
||||
|
@ -38,6 +38,8 @@ float Pid::getValue(float target, float input) {
|
|||
|
||||
float Pid::getValue(float target, float input, float dTime) {
|
||||
float error = target - input;
|
||||
prevTarget = target;
|
||||
prevInput = input;
|
||||
|
||||
float pTerm = pid->pFactor * error;
|
||||
iTerm += pid->iFactor * dTime * error;
|
||||
|
@ -61,6 +63,7 @@ float Pid::getValue(float target, float input, float dTime) {
|
|||
} else if (result < minResult) {
|
||||
result = minResult;
|
||||
}
|
||||
prevResult = result;
|
||||
return result;
|
||||
}
|
||||
|
||||
|
@ -123,4 +126,11 @@ void Pid::showPidStatus(Logging *logging, const char*msg, int dTime) {
|
|||
pid->iFactor,
|
||||
pid->dFactor,
|
||||
dTime);
|
||||
|
||||
scheduleMsg(logging, "%f input=%d/target=%f iTerm=%.5f dTerm=%.5f",
|
||||
prevResult,
|
||||
prevInput,
|
||||
prevTarget,
|
||||
iTerm, dTerm);
|
||||
|
||||
}
|
||||
|
|
|
@ -47,6 +47,10 @@ private:
|
|||
pid_s *pid;
|
||||
|
||||
float prevError;
|
||||
// these are only used for logging
|
||||
float prevTarget;
|
||||
float prevInput;
|
||||
float prevResult;
|
||||
};
|
||||
|
||||
#endif /* PID_H_ */
|
||||
|
|
Loading…
Reference in New Issue