直流减速电机增量式PID 通俗易懂版

对于我一个双非学校没上过自控的电子专业本科生而言,这个东西真的是太难了,之前研究了一个A4950驱动,价格便宜,驱动能力高,安全性高,便捷性高,一句话就是比L298N好用,我写完之后发了出去,我的一位老师看完之后,说没看出来好在哪,应该弄一个PID控制的,好吧我弄.为啥是通俗易懂版,这个,因为我理解的也不是很深入,要是有错误希望大佬指点海涵,相信对大部分同学来说应该是够用的,这篇文章写一个电机,本文章研究于平衡小车之家

1.直流电机增量式PID闭环控制原理简述

PID我们一般分为两种,一种叫位置PID一种叫速度PID,位置PID一般用于倒立摆,平衡小车等,使一个参数准确的到达某一个指定的静止状态,比如让一个电机准确的转90度,增量式PID用于让一个动态变量,尽可能稳定的维持在某一个目标值,那吗我们想让小车尽可能准确的匀速行驶,就是让每一个轮子的转速稳定在一个目标值,那具体是怎么实现的呢,我把他分为四个步骤
在这里插入图片描述
看懂这个流程图你至少要知道:
(1)编码电机的基本原理,编码电机的编码器,对应转速不同相同时间内会输出不同个脉冲
(2)单片机通过读取编码器输出的脉冲(连续的脉冲就是一个方波)的上升沿或下降沿,或上升沿和下降沿来获取转速
好的接下来我们就解释这个图
第一步:单片机通过直流减速电机的编码器获取转速,并获得当前转速与目标转速的误差
第二步:根据误差PI控制器会算出一个用于将直流减速电机调整到目标转速的PWM值
第三步:将算出的PWM值输出给直流电机,对直流电机转速进行调整
第四步:再次读取直流电机转速传给单片机

PI控制器:一个函数,输入的是当前转速与目标转速的误差,输出的是调整转速需要用到的PWM值

接下来我介绍一下,让小车匀速的活神仙,离散PID公式

PWM+=Kp×[e(k)-e(k-1)]+Ki×e(k)+Kd×[e(k)-2e(k-1)+e(k-2)]

看着公式眼晕!?别走别走我们最后不用这个复杂的公式
我还是先介绍一下它的参数都代表什么

PWM :输出增量,就是输出值

Kp ,Ki ,Kd 这三个参数是需要随机应变的,根据不断的测试调整得出一组最佳值,什么!?随机应变这四个字是在敷衍你???别走别走一会有例子的好吧你一定看的懂,你一定看的懂

e(k) : 本次误差

e(k-1):上次误差

e(k-2):上上次误差

我们要用的公式的祖宗说完了,我们实际用的公式可以简化为,其具体是由是由两个位置PID公式相减得到的,相减之后省去了KD一项,具体原因是实际任务种KD项的作用不大。

PWM+=Kp×[e(k)-e(k-1)]+Ki×e(k)

这个简单的短短的公式就是开启小车匀速宝藏的钥匙,

C语言实现代码如下

int Incremental_PI (int Encoder,int Target)
{  
   static float Bias,PWM,Last_bias;
   Bias=Target-Encoder;                                  //计算偏差
   PWM+=Velocity_KP*(Bias-Last_bias)+Velocity_KI*Bias;   //增量式PI控制器
   Last_bias=Bias;                                       //保存上一次偏差 
   return PWM;                                           //增量输出
}

我们来一行一行详细解释

int Incremental_PI (int Encoder,int Target)

定义一个返回值为整形的函数叫Incremental_PI输入的是两个整形变量 Encoder,Target (Encoder代表当前速度,Target代表目标速度)

Bias=Target-Encoder; 

计算偏差目标值减去当前值

static float Bias,PWM,Last_bias;

定义三个全局浮点型静态变量,Bias(本次偏差),PWM(输出增量),Last_bias(上次误差)

PWM+=Velocity_KP*(Bias-Last_bias)+Velocity_KI*Bias;

计算出调整偏差所需要的PWM值

Last_bias=Bias;   

保存上一次偏差

return PWM;

返回需要输出的PWM值

2.实验准备

1.Arduino mega 2560
2.12V电源一个 我用的是航模电池
3.直流电机驱动 A4950
链接: A4950驱动详解
4.编码电机
5.面包板
6.杜邦线若干
接线图如下:

mega 2560 引脚外设引脚
2编码器A相
50编码器B相
5A4950驱动AIN1
6A4950驱动AIN2
5V面包板+
GND面包板-
编码电机引脚所接引脚
电机线﹢A4950驱动AOUT1
电机线 -A4950驱动AOUT2
编码器5v面包板+
编码器GND面包板-
编码器A相mega2560 2号引脚
编码器B相mega2560 50号引脚
A4950驱动所接引脚
VCC面包板﹢
GND面包板-
VM驱动12V电源+
AIN1mega2560 5号引脚
AIN2mega2560 6号引脚
AOUT1编码电机电机线+
AOUT2编码电机电机线-
12V驱动电源所接引脚
正极A4950VM
GND面包板-

3.实验预备知识

1.编码器AB相
编码器的A相和B相输出的是有相位差的两个脉冲,实际上就是两个方波,那我们是如何从编码器A相和B相输出的方波例区分我们所认定的正反的呢

举个栗子比如我们的计数器是通过检测A相输出方波的上升沿计数的,那当我们检测到A相输出的上升沿时,发现如果此时B相输出的是高电平那我们就可以认定为此时电机在正转,当检测到A相的上升沿时,如果B相输出的是低电平那我们就可以认定为电机是反转

如果只检测一个相位在单位时间内的一个边沿出现的次数,我们将这种测速方法称为M测速法,如果我们将AB相的上升沿和下降沿都做检测的话就可以达到四倍精度又称四分频测速,然而Arduino mega 2560 只有6个中断IO口,其中还有和I2C通信口和Serial1串口共用的IO口,所以我们做一台车只使用四个中断IO口每一个中断IO口对应一个电机的编码器,但我们可以检测A相的上升沿和下降沿采用二分频测速在这里插入图片描述
2.定时内部中断
如果你要用Arduino做四轮的PID小车你就至少需要四个中断IO口,一般来说我们都是采用Mega2560 ,下面是arduino系列单片机对应引脚号和中断号
在这里插入图片描述
需要对设定时间内的脉冲的上升沿和下降沿计数,而且不占用CPU,我们就需要用到定时内部中断,当然了arduino 最大的好处就是方便 ,我们不需要像使用32一样去配置一大堆寄存器和一大堆模式,我们就采用一个外国小伙为我们写好的mega2560内部定时器库

#include <FlexiTimer2.h>        //定时中断

配置也十分简单 在setup()里写两行就够了

  FlexiTimer2::set(5, control); //5毫秒定时中断函数,每5s执行一次control函数
  FlexiTimer2::start ();      //中断使能 

好如过你了解了这些基础知识,那我们就开始

4.实验代码

以下代码实现功能为,从串口输入一个目标转速Velocity,使电机的转速尽可能准确的维持在目标值 ,Velocity所代表的是指定时间内上升沿和下降沿的个数 ,指定时间即为我在内部定时中断里设置的时间,又称采样周期

unsigned int Motor_AIN1=5;       //控制A电机的PWM引脚  一定改成自己用的
unsigned int Motor_AIN2=6;        
String Target_Value;             //串口获取的速度字符串变量
int value;                       //用于存储通过PI控制器计算得到的用于调整电机转速的PWM值的整形变量 
#include <FlexiTimer2.h>         //定时中断头文件库
/***********编码器引脚************/
#define ENCODER_A 2              //编码器A相引脚
#define ENCODER_B 50             //编码器B相引脚
int Velocity,Count=0;            //Count计数变量 Velocity存储设定时间内A相上升沿和下降沿的个数
float Velocity_KP =7.2, Velocity_KI =0.68,Target=0;//Velocity_KP,Velocity_KI.PI参数  Target目标值
/*********** 限幅************
*以下两个参数让输出的PWM在一个合理区间
*当输出的PWM小于40时电机不转 所以要设置一个启始PWM
*arduino mega 2560 单片机的PWM不能超过255 所以 PWM_Restrict 起到限制上限的作用
*****************************/
int startPWM=40;                 //初始PWM
int PWM_Restrict=215;            //startPW+PWM_Restric=255<256
void setup() 
{
  Serial.begin(9600);            //打开串口
  Serial.println("/*****开始驱动*****/");
  pinMode(ENCODER_A,INPUT);     //设置两个相线为输入模式
  pinMode(ENCODER_B,INPUT);
  pinMode(Motor_AIN1,OUTPUT);   //设置两个驱动引脚为输出模式
  pinMode(Motor_AIN2,OUTPUT); 
  FlexiTimer2::set(5, control); //5毫秒定时中断函数
  FlexiTimer2::start ();        //中断使能 
  attachInterrupt(0, READ_ENCODER_A, CHANGE);      //开启对应2号引脚的0号外部中断,触发方式为CHANGE 即上升沿和下降沿都触发,触发的中断函数为 READ_ENCODER_A 
}

void loop() 
{
  while(Serial.available()>0)          //检测串口是否接收到了数据
  {
    Target_Value=Serial.readString();  //读取串口字符串
    Target=Target_Value.toFloat();     //将字符串转换为浮点型,并将其赋给目标值
    Serial.print("目标转速频率:");      //串口打印出设定的目标转速
    Serial.println(Target);


  }
}
/**********外部中断触发计数器函数************
*根据转速的方向不同我们将计数器累计为正值或者负值(计数器累计为正值为负值为计数器方向)
*只有方向累计正确了才可以实现正确的调整,否则会出现逆方向满速旋转
*
*※※※※※※超级重点※※※※※※
*
*所谓累计在正确的方向即
*(1)计数器方向
*(2)电机输出方向(控制电机转速方向的接线是正着接还是反着接)
*(3)PI 控制器 里面的误差(Basi)运算是目标值减当前值(Target-Encoder),还是当前值减目标值(Encoder-Target)
*三个方向只有对应上才会有效果否则你接上就是使劲的朝着一个方向(一般来说是反方向)满速旋转

我例子里是我自己对应好的,如果其他驱动单片机在自己尝试的时候出现满速旋转就是三个方向没对应上

下列函数中由于在A相上升沿触发时,B相是低电平,和A相下降沿触发时B是高电平是一个方向,在这种触发方式下,我们将count累计为正,另一种情况将count累计为负
********************************************/
void READ_ENCODER_A() 
{
    
    if (digitalRead(ENCODER_A) == HIGH) 
    {     
     if (digitalRead(ENCODER_B) == LOW)      
       Count++;  //根据另外一相电平判定方向
     else      
       Count--;
    }
    
    else 
    {    
     if (digitalRead(ENCODER_B) == LOW)      
     Count--; //根据另外一相电平判定方向
     else      
     Count++;
    }
    
}
/**********定时器中断触发函数*********/
void control()
{     

        Velocity=Count;    //把采用周期(内部定时中断周期)所累计的脉冲上升沿和下降沿的个数,赋值给速度
        Count=0;           //并清零
        value=Incremental_PI_A(Velocity,Target);  //通过目标值和当前值在这个函数下算出我们需要调整用的PWM值
        Set_PWM(value);    //将算好的值输出给电机
        
}
/***********PI控制器****************/
int Incremental_PI_A (int Encoder,int Target)
{  
   static float Bias,PWM,Last_bias;                      //定义全局静态浮点型变量 PWM,Bias(本次偏差),Last_bias(上次偏差)
   Bias=Target-Encoder;                                  //计算偏差,目标值减去当前值
   PWM+=Velocity_KP*(Bias-Last_bias)+Velocity_KI*Bias;   //增量式PI控制计算
   
   if(PWM>PWM_Restrict)
   PWM=PWM_Restrict;                                     //限幅
   
   if(PWM<-PWM_Restrict)
   PWM=-PWM_Restrict;                                    //限幅  
   
   Last_bias=Bias;                                       //保存上一次偏差 
   return PWM;                                           //增量输出
}
/**********实际控制函数*********/
void Set_PWM(int motora)                        
{ 
  if (motora > 0)                                  //如果算出的PWM为正
  {
    analogWrite(Motor_AIN1, motora+startPWM);      //让PWM在设定正转方向(我们认为的正转方向)正向输出调整
    analogWrite(Motor_AIN2, 0); 
  }
  else if(motora == 0)                             //如果PWM为0停车
  {
    analogWrite(Motor_AIN2, 0);
    analogWrite(Motor_AIN1, 0);   
  }
  else if (motora < 0)                              //如果算出的PWM为负
  {
    analogWrite(Motor_AIN2, -motora+startPWM);      //让PWM在设定反转方向反向输出调整
    analogWrite(Motor_AIN1, 0);
  }
}

上传代码使用效果如下
在这里插入图片描述
那怎么看出来它是不是匀速的呢
如果没有上位机示波器的话
你可以将Volocity在串口打印出来
傻是傻了点但是可以用

void loop() 
{
  while(Serial.available()>0)
  {
    Target_Value=Serial.readString();
    Target=Target_Value.toFloat();
    Serial.print("目标转速频率:");
    Serial.println(Target);
  }
  Serial.println(Velocity);     //这句是新加的
}

比如我输入了一个10可以看到输出的速度会在10上下浮动我截了一张在抖动的,其实大部分时间输出的速度还是维持在10的,输出的速度也不会超过[9.11]一直会在这个范围也就是10的上下1浮动
在这里插入图片描述
如果有上位机示波器的话呢看到能更舒服一点
黄线是调整转速输出的PWM值,白线是实际值,红线是目标值
红线基本和白线重合看不到了
在这里插入图片描述
我们再仔细看一下白线和红线偏差不超过1,四个轮都调成这个程度实际效果亲测效果还挺好,我觉得够用,当然你可以接着调
在这里插入图片描述

5.Kp,Ki参数调节

好那关键问题来了Kp和Ki的参数怎么调呢
实际上因为我们只用到两个参数,还是比较好调的
1.一般来说第一个参数Kp起让实际值保持稳定的浮动在一个固定值上下的作用.Kp这个参数的大小和电机驱动的能力以及驱动电源的电压值有关,驱动能力越强一般Kp越大,情况是多样的,唯有不断尝试,看哪个参数出来的效果最好,震荡幅度最小,震荡次数最少.
和位置PID的个人觉得调整方式不太一样,这里不想做太多复杂的解释.
但还是可以给大家点建议以我例子中的参数为例,我用的是A4950,12V的驱动电源,使用的参数是Velocity_KP =7.2,如果你用的驱动组合比我更强劲(驱动模块比我用的好,驱动电压比我高)那你就从我的例子的参数开始一点一点往上尝试,顺带一提L298N驱动能力和A4950差不多

2.第二个参数Ki起让这个固定值是目标值的作用,用来消除稳态误差,又称静差,具体是怎么表现的呢
我把上面例子的参数用的是

Velocity_KP =7.2, Velocity_KI =0.68

接下来我把Ki变成0

// An highlighted block
Velocity_KP =7.2, Velocity_KI =0

就会出现如下情况,白线虽然也是在一个固定值上下浮动,但是这个固定值离我们的目标值,也就是红线明显有偏差.这个原理大家不是很明白的话可以去搜稳态误差,Ki起的就是消除稳态误差的作用
在这里插入图片描述
我们吧Velocity_KI 再次赋值0.68
可以看到红线白线又开始"纠缠不清"
在这里插入图片描述
在让想小车匀速的PI控制例子中,这个Ki不用给太大

后记

在最后调参数这块,之前我也看了好多,这个调参的文章,还有一大堆口诀什么什么的,我个人觉得似乎确实并不太好理解,而且基本是用于第一类位置PID的,然后感觉都不如自己直接尝试来的痛快,大概都是先调Kp使系统稳定,然后Ki让系统消除静态误差稳定在该稳定的值,第一次写PID的老实说有点害怕,怕自己哪块理解的不到位,误导大家,如果有写的不妥当的地方还希望大家批评指正,希望能帮到大家

附件 L298N PID程序

大家A4950驱动用的少,然后自己弄了一个L298N的希望能帮到大家
在这里插入图片描述
接线表格

mega 2560 引脚外设引脚
2编码器A相
50编码器B相
3L298N驱动IN1
4L298N驱动IN2
7L298N驱动ENA
5V面包板+
GND面包板-
编码电机引脚所接引脚
电机线﹢L298N驱动AOUT2
电机线 -L298N驱动AOUT1
编码器5v面包板+
编码器GND面包板-
编码器A相mega2560 2号引脚
编码器B相mega2560 50号引脚
L298N所接引脚
5V面包板﹢
GND面包板-
12V驱动12V电源+
IN1mega2560 3号引脚
IN2mega2560 4号引脚
ENAmega2560 7号引脚
OUT2编码电机电机线+
OUT1编码电机电机线-
12v驱动电源所接引脚
正极L298N-12V
GND面包板-
const unsigned int Motor_PWM=7;
const unsigned int L298N_IN1=3;
const unsigned int L298N_IN2=4;

int value;
#include <FlexiTimer2.h>      

#define ENCODER_A 2
#define ENCODER_B 50
String Target_Value;
int Velocity,Count=0;
float Velocity_KP =7.2, Velocity_KI =0.68,Target=0;
int startPWM=0;              
int PWM_Restrict=255;
void setup() 
{
  Serial.begin(9600);           
  Serial.println("/*****开始驱动*****/");
  pinMode(ENCODER_A,INPUT);
  pinMode(ENCODER_B,INPUT);
  pinMode(L298N_IN1,OUTPUT);   
  pinMode(L298N_IN2,OUTPUT); 
  pinMode(Motor_PWM,OUTPUT);
  FlexiTimer2::set(5, control); 
  FlexiTimer2::start ();      //中断使能 
  attachInterrupt(0, READ_ENCODER_A, CHANGE);           
}

void loop() 
{
 while(Serial.available()>0)          //检测串口是否接收到了数据
  {
    Target_Value=Serial.readString();  //读取串口字符串
    Target=Target_Value.toFloat();     //将字符串转换为浮点型,并将其赋给目标值
    Serial.print("目标转速频率:");      //串口打印出设定的目标转速
    Serial.println(Target);
  }
}
void control()
{     

        Velocity=Count;    //单位时间内读取位置信息
        Count=0;           //并清零
        value=Incremental_PI_A(Velocity,Target);
        Set_PWM(value);       
        
}
void READ_ENCODER_A() 
{
    if (digitalRead(ENCODER_A) == HIGH) 
    {     
     if (digitalRead(ENCODER_B) == LOW)      
       Count++;  //根据另外一相电平判定方向
     else      
       Count--;
    }
    else 
    {    
     if (digitalRead(ENCODER_B) == LOW)      
     Count--; //根据另外一相电平判定方向
     else      
     Count++;
    }
}
int Incremental_PI_A (int Encoder,int Target)
{  float Bias;
   static float PWM=0,Last_bias=0;
   Bias=Target-Encoder;                                  //计算偏差
   PWM+=Velocity_KP*(Bias-Last_bias)+Velocity_KI*Bias;   //增量式PI控制器
   if(PWM>PWM_Restrict)PWM=PWM_Restrict;                                   //限幅
   if(PWM<-PWM_Restrict)PWM=-PWM_Restrict;                                 //限幅  
   Last_bias=Bias;                                       //保存上一次偏差 
   return PWM;                                           //增量输出
}
void Set_PWM(int motora) 
{ 
  if (motora > 0)
  {
    digitalWrite(L298N_IN1,HIGH);
    digitalWrite(L298N_IN2,LOW);
    analogWrite(Motor_PWM, motora+startPWM);
  }
  else if(motora == 0)   
  {
    digitalWrite(L298N_IN1,LOW);
    digitalWrite(L298N_IN2,LOW);
  }
  else if (motora < 0)  
  {
    digitalWrite(L298N_IN1,LOW);
    digitalWrite(L298N_IN2,HIGH);    
    analogWrite(Motor_PWM, -motora+startPWM);
  }
}

四轮程序

然后要是想要定时中断库但是还没有积分的话,可以关注我通过CSDN推广的的 微信公众号 浩浩的科研笔记 付费资料里花3块卖四轮的PID代码,赠送定时中断库,不做硬件了就拿出来发挥点余热吧。

补充信息(2024.4.5)

5年过去了好久没看这部分内容了,今天有小朋友发邮件说定时FlexiTimer2.h中断库arduino 2.0 以上的编译器可能存在不兼容的情况,这里告知大家一下。

Logo

旨在为数千万中国开发者提供一个无缝且高效的云端环境,以支持学习、使用和贡献开源项目。

更多推荐