本系列教程讲解零知小车套件以零知esp32为主控,使用零知开源平台进行智能小车开发。
实现的功能:红外循迹、超声避障、直线运行、手机蓝牙控制等基本功能。
扩展:可以在小车上加入其它传感器模块进行扩展,比如加入摄像头模块进行监控、加入火焰传感器做灭火小车、加入更多超声波模块实现自动跟随...
零知两轮小车入门版(ESP32主控)教程1-小车组装
零知两轮小车入门版(ESP32主控)教程2-让小车跑起来
零知两轮小车入门版(ESP32主控)教程3-手机WiFi/蓝牙控制小车
零知两轮小车入门版(ESP32主控)教程4-超声波自动避障
零知两轮小车入门版(ESP32主控)教程5-红外循迹
零知两轮小车入门版(ESP32主控)教程6-使用PID走直线
(1)组装好的智能小车
(2)零知ESP32
PID整定,是一个令人头疼的问题。PID算法本身不复杂,容易理解,难的是PID参数的整定,这里我们使用继电器自整定法来自动整定PID参数,继电器自整定法是系统运行的过程中强行震荡产生波形,然后分析波形计算出PID的方法,这省去我们手动调参的麻烦。
/**********************************************************
* 文件: auto_PID.ino by 零知实验室([url]www.lingzhilab.com[/url])
* -^^- 零知开源,让电子制作变得更简单! -^^-
* 时间: 2019/12/07 14:58
* 说明:
************************************************************/
#include <PID_v1.h>
#define AUTO_PID 1
#define LEFT_MOTO1 27
#define LEFT_MOTO2 14
#define LEFT2_MOTO1 33
#define LEFT2_MOTO2 32
#define RIGHT_MOTO1 12
#define RIGHT_MOTO2 13
#define RIGHT2_MOTO1 26
#define RIGHT2_MOTO2 25
#define SEP1 34
#define SEP2 35
int leftCounter = 0, rightCounter = 0;
unsigned long time1 = 0, old_time = 0; // 时间标记
unsigned long timechange = 0;
int sampletime = 200; // 采样标记
double speedLeft, speedRight;
bool noteFlag = 0;
bool controlType = 0; // 0为PI控制,1为PID控制
double Kp = 0.5,Ki = 0.01,Kd = 0;
double leftIn, leftOut, Setpoint = 200;
double rightIn, rightOut;
PID leftPID(&leftIn, &leftOut, &Setpoint, Kp, Ki, Kd, DIRECT);
PID rightPID(&rightIn, &rightOut, &Setpoint, Kp, Ki, Kd, DIRECT);
#if AUTO_PID
class AutoPid{
double autoKp, autoKi, autoKd;
double outputHigh, outputLow, outputStep = 20;
double inputHighAll, inputHighNum, inputLowAll, inputLowNum;
double inputHistory[20];
uint8_t atemp, btemp;
public:
bool caculateFlag = 1;
void autoPid(PID pid, double *input, double *output, double *setpoint, bool noteFlag, bool isleft);
};
AutoPid leftauto;
AutoPid rightauto;
#endif
// 复位或上电后运行一次:
void setup() {
//在这里加入初始化相关代码,只运行一次:
Serial.begin(9600);
leftPID.SetMode(AUTOMATIC);
rightPID.SetMode(AUTOMATIC);
leftPID.SetOutputLimits(0,255);
rightPID.SetOutputLimits(0,255);
pinMode(LEFT_MOTO1,OUTPUT);
pinMode(LEFT_MOTO2,OUTPUT);
pinMode(LEFT2_MOTO1,OUTPUT);
pinMode(LEFT2_MOTO2,OUTPUT);
pinMode(RIGHT_MOTO1,OUTPUT);
pinMode(RIGHT_MOTO2,OUTPUT);
pinMode(RIGHT2_MOTO1,OUTPUT);
pinMode(RIGHT2_MOTO2,OUTPUT);
ledcAttachPin(LEFT_MOTO1,1);
ledcAttachPin(LEFT_MOTO2,2);
ledcAttachPin(LEFT2_MOTO1,3);
ledcAttachPin(LEFT2_MOTO2,4);
ledcAttachPin(RIGHT_MOTO1,5);
ledcAttachPin(RIGHT_MOTO2,6);
ledcAttachPin(RIGHT2_MOTO1,7);
ledcAttachPin(RIGHT2_MOTO2,8);
ledcSetup(1, 6000, 8);
ledcSetup(2, 6000, 8);
ledcSetup(3, 6000, 8);
ledcSetup(4, 6000, 8);
ledcSetup(5, 6000, 8);
ledcSetup(6, 6000, 8);
ledcSetup(7, 6000, 8);
ledcSetup(8, 6000, 8);
pinMode(SEP1,INPUT);
pinMode(SEP2,INPUT);
attachInterrupt(SEP1, RightCount_CallBack,FALLING); // 设置外部中断SEP1
attachInterrupt(SEP2, LeftCount_CallBack,FALLING); // 设置外部中断SEP2
}
//一直循环执行:
void loop() {
// 在这里加入主要程序代码,重复执行:
noteFlag = speedDetection(&speedLeft, &speedRight, sampletime); //测速
leftIn = speedLeft;
rightIn = speedRight;
#if AUTO_PID
leftauto.autoPid(leftPID, &leftIn, &leftOut, &Setpoint, noteFlag, true);
rightauto.autoPid(rightPID, &rightIn, &rightOut, &Setpoint, noteFlag, false);
if(leftauto.caculateFlag == 0 && rightauto.caculateFlag == 0){
#endif
leftPID.Compute();
rightPID.Compute();
motoRun(leftOut, rightOut);
#if AUTO_PID
}
#endif
}
// 控制电机,正值
void motoRun(int speedL,int speedR){
if(speedL > 0){
ledcWrite(1,0);
ledcWrite(2,speedL);
ledcWrite(3,0);
ledcWrite(4,speedL);
}else{
ledcWrite(1,-speedL);
ledcWrite(2,0);
ledcWrite(3,-speedL);
ledcWrite(4,0);
}
if(speedR>0){
ledcWrite(5,0);
ledcWrite(6,speedR);
ledcWrite(7,0);
ledcWrite(8,speedR);
}else{
ledcWrite(5,-speedR);
ledcWrite(6,0);
ledcWrite(7,-speedR);
ledcWrite(8,0);
}
}
#if AUTO_PID
void AutoPid::autoPid(PID pid, double *input, double *output, double *setpoint, bool noteFlag, bool isleft)
{
if (millis() < 5000)
{
pid.Compute();
if (isleft){
motoRun(*output, NULL);
}
else{
motoRun(NULL, *output);
}
}
else if (millis() < (20 * sampletime + 6000))
{
outputLow = *output - outputStep;
outputHigh = *output + outputStep;
//如果当前速度小于设定速度,输出高的PWM,产生波峰
if (*input < *setpoint)
{
*output = outputHigh;
if (*output > 255)
*output = 255;
}
else if (*input > *setpoint)
{
*output = outputLow;
if (*output < 0)
*output = 0;
}
if (isleft){
motoRun(*output, NULL);
}
else{
motoRun(NULL, *output);
}
if (noteFlag == 1)
{
for (int i = 1; i < 20; i++)
{
inputHistory[20 - i] = inputHistory[20 - i - 1];
}
inputHistory[0] = *input;
noteFlag = 0;
}
}
else
{
while (caculateFlag)
{
// 开始分析波形
for (int i = 1; i < 20; i++)
{
// 波峰
if (inputHistory[i] > inputHistory[i - 1] && inputHistory[i] > inputHistory[i + 1])
{
inputHighAll += inputHistory[i]; // 波峰数据累加
inputHighNum++; // 波峰个数加1
if (inputHighNum == 1)
atemp = i; // 记录第一个波峰的位置
btemp = i; // 记录最后一个波峰的位置
}
// 波谷
else if (inputHistory[i] < inputHistory[i - 1] && inputHistory[i] < inputHistory[i + 1])
{
inputLowAll += inputHistory[i];
inputLowNum++;
}
}
float autoTuneA = (inputHighAll / inputHighNum) - (inputLowAll / inputLowNum); // 波峰与波谷之差的平均值
float autoTunePu = (btemp - atemp) * (sampletime / 1000) / (inputHighNum - 1); // 两个波峰之间的时间间隔
// 根据公式计算PID
double Ku = 4 * outputStep / (autoTuneA * 3.14159);
autoKp = controlType == 1 ? 0.6 * Ku : 0.4 * Ku;
autoKi = controlType == 1 ? 1.2 * Ku / autoTunePu : 0.48 * Ku / autoTunePu;
autoKd = controlType == 1 ? 0.075 * Ku * autoTunePu : 0;
caculateFlag = 0; // 关闭电机自整定
// 串口打印出自整定计算得到的PID参数
Serial.println("******************************");
Serial.println("自整定的PID参数为: ");
Serial.print("Kp:");
Serial.println(autoKp);
Serial.print("Ki:");
Serial.println(autoKi);
Serial.print("Kd:");
Serial.println(autoKd);
Serial.println(" ");
Serial.print("震荡过程中的峰峰值 A:");
Serial.print(autoTuneA);
Serial.println("rpm/min");
Serial.print("两个波峰之间的时间间隔Pu:");
Serial.print(autoTunePu);
Serial.println("秒");
Serial.println("******************************");
Serial.println(" ");
pid.SetTunings(autoKp, autoKi, autoKd); // 导入新的PID参数
delay(2000);
}
}
}
#endif
//测速
bool speedDetection(double *left, double *right, int sampleTime)
{
time1 = millis(); // 以毫秒为单位,获取当前时间
timechange = time1 - old_time;
if(timechange >= sampleTime)
{
detachInterrupt(SEP1);
detachInterrupt(SEP2);
// 计算当前速度
*left = (float)leftCounter * 60000 / (20.0 * timechange);
*right = (float)rightCounter * 60000 / (20.0 * timechange);
// //记录波形数据
// if(noteFlag = 1){
// for (int i = 1; i < 20; i++) {
// inputHistory[20 - i] = inputHistory[20 - i - 1];
// }
// inputHistory[0] = speed;
// }
//把脉冲计数值清零,以便计算下一次的脉冲计数
leftCounter = 0;
rightCounter = 0;
old_time = millis(); // 记录测速时的时间节点
attachInterrupt(SEP1, RightCount_CallBack,FALLING);
attachInterrupt(SEP2, LeftCount_CallBack,FALLING);
return true;
}
else
return false;
}
void RightCount_CallBack()
{
rightCounter++;
}
void LeftCount_CallBack()
{
leftCounter++;
}
将以上代码验证上传至零知智能小车的主控板即可。