PID算法改进
积分限幅
限制积分的幅度,防止积分深度饱和
使用程序模拟电机断电的情况
uint8_t Motor_Flag = 1;
int main(void)
{
OLED_Init();
Key_Init();
LED_Init();
Motor_Init();
Encoder_Init();
RP_Init();
Serial_Init();
Timer_Init();
OLED_Printf(0, 0, OLED_8X16, "Speed Control");
OLED_Update();
while(1)
{
KeyNum = Key_GetNum();
if(KeyNum == 1)
{
Motor_Flag = ~Motor_Flag;
}
if(Motor_Flag == 1)
{
LED_ON();
}
else
{
LED_OFF();
}
//使用旋钮来修改PID参数和Target
/* PID参数的范围为:0 ~ 2 */
Kp = RP_GetValue(1) / 4095.0 * 2;
Ki = RP_GetValue(2) / 4095.0 * 2;
Kd = RP_GetValue(3) / 4095.0 * 2;
/* 目标值Target的范围为: -100 ~ +100 */
Target = RP_GetValue(4) / 4095.0 * 200 - 100;
OLED_Printf(0, 16, OLED_8X16, "Kp:%4.2f", Kp);
OLED_Printf(0, 32, OLED_8X16, "Ki:%4.2f", Ki);
OLED_Printf(0, 48, OLED_8X16, "Kd:%4.2f", Kd);
OLED_Printf(64, 16, OLED_8X16, "Tar:%+04.0f", Target);
OLED_Printf(64, 32, OLED_8X16, "Act:%+04.0f", Actual);
OLED_Printf(64, 48, OLED_8X16, "Out:%+04.0f", Out);
OLED_Update();
Serial_Printf("%f,%f,%f,%f\r\n", Target, Actual, Out, ErrorInt);
}
}
void TIM1_UP_IRQHandler(void)
{
static uint16_t Count = 0;
if (TIM_GetITStatus(TIM1, TIM_IT_Update) == SET)
{
Key_Tick();
Count++;
if(Count >= 40)
{
Count = 0;
/* 获取实际值 */
Actual = Encoder_Get();
/* 获取本次误差和上次误差 */
Error1 = Error0;
Error0 = Target - Actual;
/* 积分误差(累加) */
if(fabs(Ki) > EPSILON)
{
ErrorInt += Error0;
}
else
{
ErrorInt = 0;
}
/* PID计算 */
Out = Kp * Error0 + Ki * ErrorInt + Kd * (Error0 - Error1);
/* 输出限幅 */
if(Out > 100) {Out = 100;}
if(Out < -100) {Out = -100;}
/* 执行控制 */
if(Motor_Flag == 1)
{
Motor_SetPWM(Out);
}
else
{
Motor_SetPWM(0);
}
}
TIM_ClearITPendingBit(TIM1, TIM_IT_Update);
}
}
当电机故障时,实际值为0,导致误差始终存在,所以误差积分会不断累加。经过一段时间,误差积分就会陷入深度饱和状态,此时电机恢复正常,电机会满速旋转且无法控制。这是因为积分项过大,使得其他项的调控形同虚设,只有等到积分项反向积分退出饱和状态后,才会恢复PID调控。
/* 积分限幅 */
if(ErrorInt > 260){ErrorInt = 260;}
if(ErrorInt < -260){ErrorInt = -260;}
积分限幅的上限和下限可以通过观察图像中ErrorInt能达到的最大值和最小值来确定
积分限幅后的波形
积分分离
误差小于一个限度才开始积分,反之则去掉积分部分
在位置式PID定位置PID控制中,仅使用 p d 调节
问题一:实际值与目标值之间无法完全重合,会有较小的误差。
误差产生的原因是:误差太小。误差 * Kp是 P 项输出的力,这个力的大小不足以驱动电机转动
问题二:固定位置的力的大小不是很强,通过很小的外力就可能导致位置偏移
以上问题可以通过加入 Ki 项调节解决,但是加入 I 项后会有较为严重的超调现象
解决一:只要存在误差,积分项就会不断累积,知道能够驱动电机旋转
解决二:当外力作用时,实际值与目标值存在误差,积分项累加,使力不断增大以对抗外力,从而使位置回正。
超调问题:当实际值与目标值相等时,误差为0,p项输出的力立刻变为0,但是积分项累加不会立刻变为0,所以导致超调。积分项反向积分,直到值为0。
定速度控制时不会导致超调的原因是:定速度控制时有摩擦力,积分项累积的力正好抵消摩檫力从而使电机匀速旋转。但是定位置控制时,保持位置恒定不需要输出力,所以会导致超调。
使用积分分离解决超调问题
/* 获取实际值 */
Actual += Encoder_Get();
/* 获取本次误差和上次误差 */
Error1 = Error0;
Error0 = Target - Actual;
/* 积分分离 */
if(fabs(Error0) < 50)
{
ErrorInt += Error0;
}
else
{
ErrorInt = 0;
}
/* PID计算 */
Out = Kp * Error0 + Ki * ErrorInt + Kd * (Error0 - Error1);
/* 输出限幅 */
if(Out > 100) {Out = 100;}
if(Out < -100) {Out = -100;}
/* 执行控制 */
Motor_SetPWM(Out);
可以观察到超调现象已经很小或者消失。
变速积分
根据误差的大小调整积分的速度
/* 获取实际值 */
Actual += Encoder_Get();
/* 获取本次误差和上次误差 */
Error1 = Error0;
Error0 = Target - Actual;
/* 变速积分 */
float C = 1 / (0.2 * fabs(Error0) + 1);
ErrorInt += C * Error0;
/* PID计算 */
Out = Kp * Error0 + Ki * ErrorInt + Kd * (Error0 - Error1);
/* 输出限幅 */
if(Out > 100) {Out = 100;}
if(Out < -100) {Out = -100;}
/* 执行控制 */
Motor_SetPWM(Out);
不完全微分
给微分项加入一阶惯性单元(低通滤波器)
图中显示噪声对误差的影响,绿线为无噪声时的误差波形,红线为噪声影响的误差波形
P项输出取决于本次误差的幅值,噪声的幅值一般不大。所以噪声对P项影响不大
I项输出取决与曲线与X轴和Y轴围成的面积,噪声使误差有时偏大,有时偏小,相互抵消。所以噪声对I项影响也不大
D项输出取决与本次误差与上次误差连线的斜率,由图可以观察到,绿线和红线在某点的斜率相差较大,甚至有方向相反的情况出现。所以噪声对D项影响非常大
因此,我们对微分项加入滤波。
为什么不直接对输出进行滤波?
对输入进行滤波虽然可以过滤噪声,让输入更加平滑,但同时也会使输入波形的相位产生滞后,这对快速的控制不利。
/* 获取实际值 */
Actual += Encoder_Get();
/* 使用程序模拟噪声 */
Actual += rand() % 42 - 20;
/* 获取本次误差和上次误差 */
Error1 = Error0;
Error0 = Target - Actual;
/* 积分误差(累加) */
if(fabs(Ki) > EPSILON)
{
ErrorInt += Error0;
}
else
{
ErrorInt = 0;
}
/* 将微分项拿出来方便观察 */
// DifOut = Kd * (Error0 - Error1);
/* 不完全微分 */
float a = 0.9; //滤波强度
DifOut = (1 - a) * Kd * (Error0 - Error1) + a * DifOut;
/* PID计算 */
Out = Kp * Error0 + Ki * ErrorInt + DifOut;
/* 输出限幅 */
if(Out > 100) {Out = 100;}
if(Out < -100) {Out = -100;}
/* 执行控制 */
Motor_SetPWM(Out);
图中黄色线为加入噪声后微分项输出。左边为正常PID控制,右边为使用不完全微分后的现象
微分先行
将对误差的微分替换为对实际值的微分
从图中可以看到,当目标值大幅度切换时,误差突变。这会导致D项瞬间输出一个非常大的正向调控力,然后又会输出一个比较大的反向调控力,然后随着误差变化逐渐放缓,斜率从负的比较大变化为负的比较小,D项输出反向比较小的调控力。
问题一:在切换的瞬间,极短的时间内,D项的输出突然由正的非常大变化为负的比较大
问题二:D项的设计初衷,是给系统增加阻尼,阻碍实际值的变化。但是目标值切换瞬间产生的正向非常大的力是阻尼的反作用,助长了实际值的变化。
/* 记录上一次的实际值 */
Actual1 = Actual;
/* 获取实际值 */
Actual += Encoder_Get();
/* 获取本次误差和上次误差 */
Error1 = Error0;
Error0 = Target - Actual;
/* 积分误差(累加) */
if(fabs(Ki) > EPSILON)
{
ErrorInt += Error0;
}
else
{
ErrorInt = 0;
}
/* 微分先行,同时将微分项的输出单独拿出来,方便观察 */
DifOut = - Kd * (Actual - Actual1);
/* PID计算 */
Out = Kp * Error0 + Ki * ErrorInt + DifOut;
/* 输出限幅 */
if(Out > 100) {Out = 100;}
if(Out < -100) {Out = -100;}
/* 执行控制 */
Motor_SetPWM(Out);
大幅度快速改变Target,微分项输出图。左边为正常微分,右边为微分先行。
输出偏移
在非0输出时,给输出值加一个固定偏移
int main(void)
{
OLED_Init();
Key_Init();
Motor_Init();
Encoder_Init();
RP_Init();
Serial_Init();
Timer_Init();
OLED_Printf(0, 0, OLED_8X16, "Location Control");
OLED_Update();
while(1)
{
KeyNum = Key_GetNum();
if(KeyNum == 1)
{
Out += 1;
}
if(KeyNum == 2)
{
Out -= 1;
}
Motor_SetPWM(Out);
OLED_Printf(0, 16, OLED_8X16, "Out:%+04.0f", Out);
OLED_Update();
}
}
void TIM1_UP_IRQHandler(void)
{
static uint16_t Count = 0;
if (TIM_GetITStatus(TIM1, TIM_IT_Update) == SET)
{
Key_Tick();
TIM_ClearITPendingBit(TIM1, TIM_IT_Update);
}
}
使用按键测试能够使电机旋转的最小输出,作为输出偏移的偏移值
/* 获取实际值 */
Actual += Encoder_Get();
/* 获取本次误差和上次误差 */
Error1 = Error0;
Error0 = Target - Actual;
/* 积分误差(累加) */
if(fabs(Ki) > EPSILON)
{
ErrorInt += Error0;
}
else
{
ErrorInt = 0;
}
/* PID计算 */
Out = Kp * Error0 + Ki * ErrorInt + Kd * (Error0 - Error1);
/* 输出偏移 */
int16_t offset = 5;
if(Out > 0.1)
{
Out += offset;
}
else if(Out < -0,1)
{
Out -= offset;
}
else
{
Out = 0;
}
/* 输出限幅 */
if(Out > 100) {Out = 100;}
if(Out < -100) {Out = -100;}
/* 执行控制 */
Motor_SetPWM(Out);
可以看到,加入输出偏移后,目标值与实际值重合的较好,但是输出偏移会造成最终实际位置的抖动,这需要输入死区来解决。
输入死区
误差小于一个限度时不进行调控
/* 获取实际值 */
Actual += Encoder_Get();
/* 获取本次误差和上次误差 */
Error1 = Error0;
Error0 = Target - Actual;
/* 输入死区 4为死区大小,根据实际调节至系统不再抖动就行*/
if(fabs(Error0) < 4)
{
Out = 0;
}
else
{
/* 积分误差(累加) */
if(fabs(Ki) > EPSILON)
{
ErrorInt += Error0;
}
else
{
ErrorInt = 0;
}
/* PID计算 */
Out = Kp * Error0 + Ki * ErrorInt + Kd * (Error0 - Error1);
/* 输出偏移 */
int16_t offset = 5;
if(Out > 0.1)
{
Out += offset;
}
else if(Out < -0,1)
{
Out -= offset;
}
else
{
Out = 0;
}
}
/* 输出限幅 */
if(Out > 100) {Out = 100;}
if(Out < -100) {Out = -100;}
/* 执行控制 */
Motor_SetPWM(Out);
以上改进措施,需要根据实际进行使用,并不是使用了这些措施最终的结果就会更好,有时反而会取到相反的结果。