Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <labust/control/PIDFFController.h>
00035 #include <math.h>
00036
00037 void PIDFF_modelTune(PIDBase* self,
00038 const PT1Model* const model,
00039 float w)
00040 {
00041 self->Kp = model->alpha*w*w;
00042 self->Ki = model->alpha/(w*w*w);
00043 self->Kd = model->alpha*w - model->beta;
00044 self->Kt = self->Tf = 0;
00045
00046 self->model.alpha = model->alpha;
00047 self->model.beta = model->beta;
00048 self->model.betaa = model->betaa;
00049 }
00050
00051 void PIDFF_tune(PIDBase* self, float w)
00052 {
00053 self->Kp = 2*w;
00054 self->Ki = w*w;
00055 self->Kd = self->Kt = self->Tf = 0;
00056 }
00057
00058 void PIDFF_wffStep(PIDBase* self, float Ts, float error, float ff)
00059 {
00060
00061 if (self->autoWindup == 1)
00062 {
00063 self->windup = (self->internalState > self->output) && (error>0);
00064 self->windup = (self->windup) ||
00065 ((self->internalState < self->output) && (error<0));
00066 }
00067 else
00068 {
00069
00070
00071
00072 }
00073
00074
00075 self->internalState += self->Kp*(error-self->lastError);
00076
00077
00078 if (!self->windup) self->internalState += self->Ki*Ts*error;
00079
00080 self->internalState += self->Kd*1/Ts*(error-2*self->lastError+self->llastError);
00081
00082 self->internalState += ff - self->lastFF;
00083
00084 self->output = self->internalState;
00085
00086 if (self->autoWindup == 1)
00087 {
00088 self->output = sat(self->output,-self->outputLimit, self->outputLimit);
00089 }
00090
00091 self->llastError = self->lastError;
00092 self->lastError = error;
00093 self->lastRef = self->desired;
00094 self->lastFF = ff;
00095 }
00096
00097 void PIDFF_dwffStep(PIDBase* self, float Ts, float error, float ff, float ds)
00098 {
00099
00100 if (self->autoWindup == 1)
00101 {
00102 self->windup = (self->internalState > self->output) && (error>0);
00103 self->windup = (self->windup) ||
00104 ((self->internalState < self->output) && (error<0));
00105 }
00106 else
00107 {
00108
00109
00110
00111 }
00112
00113
00114 self->internalState += self->Kp*(error-self->lastError);
00115
00116
00117 if (!self->windup) self->internalState += self->Ki*Ts*error;
00118
00119 self->internalState += self->Kd*(self->lastDerivative - ds);
00120
00121 self->internalState += ff - self->lastFF;
00122
00123 self->output = self->internalState;
00124
00125 if (self->autoWindup == 1)
00126 {
00127 self->output = sat(self->output,-self->outputLimit, self->outputLimit);
00128 }
00129
00130 self->lastDerivative = ds;
00131 self->llastError = self->lastError;
00132 self->lastError = error;
00133 self->lastRef = self->desired;
00134 self->lastFF = ff;
00135 }
00136
00137
00138