本系列教程讲解零知小车套件以零知迷你板为主控,使用零知开源平台进行智能小车开发。
使用的硬件:零知智能小车套件-零知智能小车高级版(零知mini主控)
实现的功能:红外循迹、超声波避障、直线运行、手机蓝牙控制、灭火等基本功能。
扩展:可以在小车上加入其它传感器模块进行扩展,比如加入摄像头模块进行监控、加入更多超声波模块实现自动跟随...
高级版系列教程将使用多文件编程的方式来编写程序,教程主要包含以下几个部分:
零知两轮小车高级版(零知mini主控)系列教程-小车组装(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-程序控制电机开跑(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-加入蓝牙实现手机控制(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-红外循迹走S弯(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-超声波自动避障(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-灭火小车(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-使用PID走直线(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-魔术手(点击跳转)
零知两轮小车高级版(零知mini主控)系列教程-贴边行驶(点击跳转)
一、工具原料
(1)组装好的智能小车高级版
二、程序代码
高级版教程将使用多文件编程的方式来编写代码,完整工程可在下面下载。
两轮小车由于万向轮的存在,在行驶的过程中无法保证完全直行。要想让小车直线行驶,就得保证两边轮子的速度大致相等,所以我们要实时测量两边轮子的速度,并调整输出的PWM,这里我们使用PID算法来控制小车电机的PWM输出。
测速程序部分如下:
bool getMotorSpeed(double *left, double *right)
{
time1 = millis();
timechange = time1 - old_time;
if(timechange >= sampletime)
{
detachInterrupt(SM1Pin);
detachInterrupt(SM2Pin);
// 计算车轮转速,单位为rpm/min
*left = (float)(leftCounter * 60000 / (20 * timechange));
*right = (float)(rightCounter * 60000 / (20 * timechange));
// 把脉冲计数值清零,以便计算下一秒的脉冲计数
leftCounter = 0;
rightCounter = 0;
old_time = millis();
attachInterrupt(SM1Pin, LeftCount_CallBack, FALLING);
attachInterrupt(SM2Pin, RightCount_CallBack, FALLING);
return true;
}
else
return false;
}
void RightCount_CallBack()
{
rightCounter++;
}
void LeftCount_CallBack()
{
leftCounter++;
}
PID整定:PID算法本身不难理解,难的主要是对P、I、D三个参数的整定,为了省去我们手动整定参数的麻烦,这里我们使用继电器自整定法来自动整定PID参数。程序如下:
double Kp, Ki, Kd;
double outputHigh, outputLow;
double inputHighAll, inputHighNum, inputLowAll, inputLowNum;
double inputHistory[20];
uint8_t caculateFlag = 1;
uint8_t atemp, btemp;
void getAutoPid(LZSmartCarMotor Motor, PID pid, double *input, double *output, double *setpoint, bool noteFlag, bool isleft){
// 使用手动输入的不是很准确的PID参数使小车达到稳定状态
while(caculateFlag)
{
if (millis() < 5000)
{
pid.Compute();
if (isleft){
Motor.speedGo(1, *output);
Motor.speedGo(3, *output);
}
else{
Motor.speedGo(2, *output);
Motor.speedGo(4, *output);
}
outputLow = *output - outputStep;
outputHigh = *output + outputStep;
}
// 强行震荡,产生波形
else if (millis() < (20 * sampletime + 6000))
{
// 如果当前速度小于设定速度,输出高的PWM,产生波峰
if (*input < *setpoint)
{
if(outputLow < 0)
outputLow = 0;
if (isleft){
Motor.speedGo(1, outputLow);
Motor.speedGo(3, outputLow);
}
else{
Motor.speedGo(2, outputLow);
Motor.speedGo(4, outputLow);
}
}
// 产生波谷
else if (*input > *setpoint)
{
if(outputHigh > 255)
outputLow = 255;
if (isleft){
Motor.speedGo(1, outputHigh);
Motor.speedGo(3, outputHigh);
}
else{
Motor.speedGo(2, outputHigh);
Motor.speedGo(4, outputHigh);
}
}
//记录波形
if (noteFlag == 1)
{
for (int i = 1; i < 20; i++)
{
inputHistory[20 - i] = inputHistory[20 - i - 1];
}
inputHistory[0] = *input;
noteFlag = 0;
}
}
else
{
// 开始分析波形
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);
Kp = controlType == 1 ? 0.6 * Ku : 0.4 * Ku;
Ki = controlType == 1 ? 1.2 * Ku / autoTunePu : 0.48 * Ku / autoTunePu;
Kd = controlType == 1 ? 0.075 * Ku * autoTunePu : 0;
caculateFlag = 0; // 关闭电机自整定
// 串口打印出自整定计算得到的PID参数
Serial.println("******************************");
Serial.println("PID 自整定过程完成!");
Serial.println("自整定的PID参数为: ");
Serial.print("Kp:");
Serial.println(Kp);
Serial.print("Ki:");
Serial.println(Ki);
Serial.print("Kd:");
Serial.println(Kd);
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(Kp, Ki, Kd); // 导入新的PID参数
// delay(2000);
return true;
}
}
}
从上面的代码可以看到,自整定的过程我们分为三步,第一步先让小车达到相对稳定的状态,第二步让小车电机强行震荡产生可分析的波形并记录,第三步分析波形并计算出PID参数。
主程序部分如下所示:
#include "pinsdefine.h"
#include "motor.h"
#include <;PID_v1.h>
LZSmartCarMotor myMotor;
#include "carsensor.h"
//传感器:温湿度、火焰、风扇
CarSensor carsensor;
CarSensor carsensor1;
double kp = 0.5, ki = 0.01, kd = 0;double leftSpeed, rightSpeed;
double leftOut, rightOut;
double Setpoint = 180;
int sampletime = 200; // 采样时间
// 左右轮的PID实例
PID leftpid(&leftSpeed, &leftOut, &Setpoint, kp, ki, kd, DIRECT);
PID rightpid(&rightSpeed, &rightOut, &Setpoint, kp, ki, kd, DIRECT);
void goStraight()
{
carsensor.setSampletime(sampletime); // 设置测速的采样时间
bool flag = carsensor.getMotorSpeed(&leftSpeed, &rightSpeed); // 测速,单位为rpm/min
Serial.print("leftspeed:");
Serial.print(leftSpeed);
Serial.print(" rightspeed:");
Serial.println(rightSpeed);
#if AUTO_PID
carsensor.setPIDType(Pi); //设置PI控制或PID控制
carsensor.getAutoPid(myMotor, leftpid, &leftSpeed, &leftOut, &Setpoint, flag);
carsensor1.getAutoPid(myMotor, rightpid, &rightSpeed, &leftOut, &Setpoint, flag, false);
while(1)
{
carsensor.getMotorSpeed(&leftSpeed, &rightSpeed);
leftpid.Compute();
rightpid.Compute();
Serial.print("leftOut:");
Serial.print(leftOut);
Serial.print(" rightOut:");
Serial.println(rightOut);
myMotor.motorRun(leftOut, rightOut);
}
#else
leftpid.Compute();
rightpid.Compute();
Serial.print("leftOut:");
Serial.print(leftOut);
Serial.print(" rightOut:");
Serial.println(rightOut);
myMotor.motorRun(leftOut, rightOut);
#endif
}
void setup()
{
leftpid.SetMode(AUTOMATIC);
rightpid.SetMode(AUTOMATIC);
leftpid.SetOutputLimits(0, 255);
rightpid.SetOutputLimits(0, 255);
}
void loop()
{
goStraight();
}
完整工程请下载附件
包含全部功能的完整工程: lzsmartcar_v5.zip