科技节智能车小记
比赛要求
本次科技节比赛要求通过遥控和电磁的方式,让小车绕着赛道跑一圈,时间最短者获胜
- 遥控器和小车必须用单片机控制
- PCB必须自制或者用洞洞板
赛道如下:
(并没有三叉路口,对新生十分友好)
设计思路
总体思路
开发板
为了在短时间内快速完成开发,采用了arduino开发板
谁能拒绝一块粉色的开发板呢
车模
车模方面,一开始使用最便宜的4个电机的小车,但发现效果太垃圾了
首先,电机也没有编码器,无法准确控制车轮的转速
其次,转速根本不够快,很难在内卷的时代获胜
可能是学长看到我的车模太垃圾了,友情提供了一个车模,技术参数如下:
- 采用520电机驱动,最高支持电压12V
- 自带霍尔编码器,精度为330脉冲/转
图片如下:
电机驱动
考虑到电流不会特别大,于是采用了性价比最高的DRV8833驱动板
- 支持pwm控制,可以调速
- 最大10.8V电压和1.5A电流 (比赛的时候直接上12V了,也没炸)
遥控车思路
首先,需要有一个遥控器
结合玩遥控车的经验,采用arduino+摇杆电位计的方式
最初的设计图如下:
摇杆返回模拟值电压,通过arduino自带的ADC,转成0-1024的整型值
int x1 = analogRead(A1);//left
int x2 = analogRead(A2);//right
接着,要进行通信
通信方面,采用HC-12 wifi无线串口模块,默认波特率9600
发送的时候,将左右摇杆的数值组合为字符串,并且使用分隔符,确保接受端能正常接收。
HC.print('L');
HC.print(leftsig);//符号
HC.print(sendleft);//数值
HC.print('R');//分隔符
HC.print(rightsig);//符号
HC.print(sendright);//数值
HC.print('x');
HC.print('z');
接收的时候,由于长度不固定,需要全部读入,arduino里面有一个readStringUntil函数,十分滴好用。我发送的时候采用z结尾,所以可以完整的读到全部数据。
然后,对接收到的数据进行分割,按照位转化成整型数,代码如下 (点击可展开)
:::details
//接收的数据 L+100R+100xz
j=0;
rec=HC.readStringUntil('z');
len=rec.length();
while(i<len&&rec[i]!='R')
{
i++;
}
switch(i)
{
case 5://表示有5位(L+100)的情况,直接为100
{
if(rec[1]=='+')
left=100;
else
left=-100;
break;
}
case 4://4位(数字两位),依次转化
{
if(rec[1]=='+')
left=10*(rec[2]-'0')+rec[3]-'0';
else
left=-(10*(rec[2]-'0')+rec[3]-'0');
break;
}
case 3://3位(数字只有一位)
{
if(rec[1]=='+')
left=rec[2]-'0';
else
left=-(rec[2]-'0');
break;
}
default:
left=0;
}
:::
再者,要让车跑起来
首先,要接收编码器的数据。
霍尔编码器,每转过一定角度就会产生一次脉冲,因此,可以使用io口中断的方式,每收到一次脉冲,计数器+1,只要计数周期恒定,计数的多少就反映了当前的转速。
还要判断正反转,传感器有AB相位,A为高,B为低时正转,反则为反转
下图为正转的时候ab相位的输出波形图:
判断代码如下:
attachInterrupt(digitalPinToInterrupt(2), left, RISING);//启用2口中断
void left()
{
if(digitalRead(10)==1)
leftcount++;
else
leftcount--;
}
这样即可获得转速,每次循环结束读取数值之后,将数值清零就行了
接着,采用pid算法,对电机进行控制
我这里只用了p和d控制,已经获得了不错的效果,对于突然变化的负载的反应速度还算可以。
:::warning
提示:控制电机的转速需要用到增量式pid算法,而不是位置式
:::
关于pid算法的原理和两种pid的区别,我(可能)会再写一篇文章来解释
然后,将pid计算之后的转速信号转化为pwm,输入到电机驱动板之中,就可以控制小车的转速了。
至此,遥控车的制作完成,剩下的就是练操作以及熟悉赛道了
电磁车思路
电磁车和寻迹小车差不多,只不过,电磁电磁车巡的是电磁赛道。
赛道中央会有一条电线,其中通有20kHz,100mA的正弦交流电。
根据高中知识,交流电会在电线附近激发交变磁场
通过电磁传感器搭载的电感,可以感知磁场,从而感知车辆偏离中心线的程度。
输出的是四个电感感应到的数值,实测数值在100-500之间
进行归一化处理,限制幅度,方便计算误差 (其实就是把得到的数值都除以一个常数)
接着,进行p计算,将两边电感的差值乘以一个系数,加到左右车轮的转速上,实现控制小车的转向
经过一番调参,最终实现小车的寻迹
核心代码如下:
//读取电感
float x1 = analogRead(A0)/3.0;
float x2 = analogRead(A1)/3.0;
float x3 = analogRead(A2)/3.0;
float x4 = analogRead(A3)/3.0;
float err2=(x1+x2)/2-(x3+x4)/2;//取平均值,最终的误差
float basespeed=90;//基础转速
//计算两轮转速
leftpid(basespeed-err3*p);//差速转向
rightpid(basespeed+err3*p);
比赛结果
首先,感谢大二学长的不杀之恩,毕竟他们的车模和代码是去打国赛的啊...
最后,在12.6V电压的“超频”下,本车包揽两个组别的第一,成绩如下
- 遥控组18.8s
- 电磁组19.8s
- 获得共计1200元奖金 (虽然下学期才到账)
最后,本项目所有代码如下,欢迎交流
抄也没用,比赛已经打完了了
开源环节
遥控组发送(遥控器代码)
:::details
#include <SoftwareSerial.h>
SoftwareSerial HC(3,2);//RX=3,TX=2
void setup() {
// put your setup code here, to run once:
Serial.begin(9600);
HC.begin(9600);
pinMode(4, OUTPUT);
pinMode(5, OUTPUT);
pinMode(6, OUTPUT);
pinMode(7, OUTPUT);
pinMode(8, OUTPUT);
pinMode(9, OUTPUT);
pinMode(10, OUTPUT);
pinMode(11, OUTPUT);
pinMode(12, OUTPUT);
pinMode(A1, INPUT);
pinMode(A2, INPUT);
for(int i=4;i<=13;i++)
{
digitalWrite(i,0);
}
digitalWrite(4,1);
digitalWrite(9,1);
for(int i=0;i<4;i++)
{
digitalWrite(i+4,0);
digitalWrite(i+9,0);
digitalWrite(i+5,1);
digitalWrite(i+10,1);
delay(100);
}
for(int i=4;i<=13;i++)
{
digitalWrite(i,0);
}
digitalWrite(11,1);
}
float left;
float right;
int sendleft=0;
int sendright=0;
char charleft;
char leftsig;
char rightsig;
char charright;
int gcount=0;//
int light[14]={0};//分别代表
void loop()
{
// put your main code here, to run repeatedly:
delayMicroseconds(100);//主延时
gcount++;
if(gcount==200)
{
gcount=0;
int x1 = analogRead(A1);//left
int x2 = analogRead(A2);//right
//Serial.println(x1);
//left判定
if(abs(x1-541)>=3)
{
if(x1-514>0)
left=(x1-514)/509.0;
else
left=(x1-514)/514.0;
}
else
{
left=0;
}
if(left>100)
{
left=100;
}
if(left<-100)
{
left=-100;
}
if(abs(x2-533)>=5)
{
if(x2-533>0)
right=(x2-533)/490.0;
else
right=(x2-533)/533.0;
}
else
{
right=0;
}
if(right>100)
{
right=100.0;
}
if(right<-100)
{
right=-100.0;
}
sendleft=left*100;
sendright=right*100;
//led灯效 --------------------------------------led part-------------------------------
if(sendleft<=0)
{
for(int i=4;i<=8;i++)
light[i]=0;
}
else
if(sendleft>0&&sendleft<=20)
{
light[8]=1;
for(int i=4;i<=7;i++)
light[i]=0;
}
else
if(sendleft>20&&sendleft<=40)
{
light[8]=1;
light[7]=1;
light[6]=0;
light[5]=0;
light[4]=0;
}
else
if(sendleft>40&&sendleft<=60)
{
light[8]=1;
light[7]=1;
light[6]=1;
light[5]=0;
light[4]=0;
}
else
if(sendleft>60&&sendleft<=80)
{
light[8]=1;
light[7]=1;
light[6]=1;
light[5]=1;
light[4]=0;
}
else
{
light[8]=1;
light[7]=1;
light[6]=1;
light[5]=1;
light[4]=1;
}
// left led--------------------------------------------left led end-----------------------------
if(sendright>80)
{
light[9]=0;
light[10]=0;
light[11]=1;
light[12]=1;
light[13]=1;
}
else
if(sendright<80&&sendright>=40)
{
light[9]=0;
light[10]=0;
light[11]=1;
light[12]=1;
light[13]=0;
}
else
if(abs(sendright)<40)
{
light[9]=0;
light[10]=0;
light[11]=1;
light[12]=0;
light[13]=0;
}
else
if(sendright<=-40&&sendright>=-80)
{
light[9]=0;
light[10]=1;
light[11]=1;
light[12]=0;
light[13]=0;
}
else
{
light[9]=1;
light[10]=1;
light[11]=1;
light[12]=0;
light[13]=0;
}
if(sendleft>=0) leftsig='+';
else leftsig='-';
if(sendright>=0) rightsig='+';
else rightsig='-';
//符号处理
sendleft=abs(sendleft);
sendright=abs(sendright);
//转字符发送
// Serial.print(sendleft);
// Serial.print(" ");
// Serial.println(sendright);
// for(int i=4;i<=13;i++)
// {
// Serial.print(light[i]);
// Serial.print(" ");
// }
// Serial.print("\n");
HC.print('L');
HC.print(leftsig);
HC.print(sendleft);
HC.print('R');
HC.print(rightsig);
HC.print(sendright);
HC.print('x');
HC.print('z');
}
//----------------------------------------end of receive--------------------------------
//HC.print(charright);
if(gcount%5==0)
{
digitalWrite(4,light[4]);
digitalWrite(5,light[5]);
// digitalWrite(6,0);
// digitalWrite(7,0);
// digitalWrite(8,0);
// digitalWrite(9,0);
// digitalWrite(10,0);
// digitalWrite(11,0);
digitalWrite(12,0);
digitalWrite(13,0);
}
else
if(gcount%5==1)
{
digitalWrite(4,0);
digitalWrite(5,0);
digitalWrite(6,light[6]);
digitalWrite(7,light[7]);
// digitalWrite(8,0);
// digitalWrite(9,0);
// digitalWrite(10,0);
// digitalWrite(11,0);
// digitalWrite(12,0);
// digitalWrite(13,0);
}
else
if(gcount%5==2)
{
// digitalWrite(4,0);
// digitalWrite(5,0);
digitalWrite(6,0);
digitalWrite(7,0);
digitalWrite(8,light[8]);
digitalWrite(9,light[9]);
// digitalWrite(10,0);
// digitalWrite(11,0);
// digitalWrite(12,0);
// digitalWrite(13,0);
}
else
if(gcount%5==3)
{
// digitalWrite(4,0);
// digitalWrite(5,0);
// digitalWrite(6,0);
// digitalWrite(7,0);
digitalWrite(8,0);
digitalWrite(9,0);
digitalWrite(10,light[10]);
digitalWrite(11,light[11]);
// digitalWrite(12,0);
// digitalWrite(13,0);
}
else
if(gcount%5==4)
{
// digitalWrite(4,0);
// digitalWrite(5,0);
// digitalWrite(6,0);
// digitalWrite(7,0);
// digitalWrite(8,0);
// digitalWrite(9,0);
digitalWrite(10,0);
digitalWrite(11,0);
digitalWrite(12,light[12]);
digitalWrite(13,light[13]);
}
// Serial.print('L');
// Serial.print(leftsig);
// Serial.print(charleft);
// Serial.print('R');
// Serial.print(rightsig);
// Serial.print(charright);
}
:::
遥控组接收 (车上的代码)
:::details
#include <SoftwareSerial.h>
SoftwareSerial HC(7,4);//RX,TX
void setup() {
// put your setup code here, to run once:
Serial.begin(9600);
HC.begin(9600);
attachInterrupt(digitalPinToInterrupt(2), left, RISING);//2为左边中断口
attachInterrupt(digitalPinToInterrupt(3), right, RISING);//3为右边中断口
pinMode(6, OUTPUT); //in2
pinMode(5, OUTPUT); //in1(left)
pinMode(10,INPUT);
pinMode(12,INPUT);
pinMode(11, OUTPUT); //in2(right)
pinMode(9, OUTPUT); //in1
}
long int leftcount=0;
long int rightcount=0;
void left()
{
if(digitalRead(10)==1)
leftcount++;
else
leftcount--;
}
void right()
{
if(digitalRead(12)==0)
rightcount++;
else
rightcount--;
}
int leftlasterr=0;//左边lasterr
int leftnowerr=0;//左边当前误差
float leftout=0;//左边输出
void leftpid(float lefttar)
{
leftnowerr=lefttar-leftcount;
//Serial.print(leftnowerr);
leftout+=leftnowerr*1.5+(leftnowerr-leftlasterr)*7.5;
if(leftout>255)
leftout=255;
if(leftout<-255)
leftout=-255;
if(abs(leftnowerr)<=1&&abs(lefttar)<=1)
leftout=0;
}
int rightlasterr=0;//左边lasterr
int rightnowerr=0;//左边当前误差
float rightout=0;//左边输出
void rightpid(float righttar)
{
rightnowerr=righttar-rightcount;
rightout+=rightnowerr*1.5+(rightnowerr-rightlasterr)*7.5;
if(rightout>255)
rightout=255;
if(rightout<-255)
rightout=-255;
if(abs(rightnowerr)<1&&abs(righttar)<1)
rightout=0;
}
String rec;
void loop() {
// put your main code here, to run repeatedly:
//Serial.println(HC.available());
char re;
int left;
int right;
char leftsig;
char rightsig;
int i=0;
int j=0;
int len;
float leftmotor;
float rightmotor;
int left1,left2,left3,right1,right2,right3;
//Serial.println("ok");
if(HC.available())
{
i=0;
j=0;
rec=HC.readStringUntil('z');
len=rec.length();
//Serial.println(rec);
while(i<len&&rec[i]!='R')
{
i++;
}
switch(i)
{
case 5:
{
if(rec[1]=='+')
left=100;
else
left=-100;
break;
}
case 4:
{
if(rec[1]=='+')
left=10*(rec[2]-'0')+rec[3]-'0';
else
left=-(10*(rec[2]-'0')+rec[3]-'0');
break;
}
case 3:
{
if(rec[1]=='+')
left=rec[2]-'0';
else
left=-(rec[2]-'0');
break;
}
default:
left=0;
}
while(i+j<len&&rec[i+j]!='x')
{
j++;
}
switch(j)
{
case 5:
{
if(rec[i+1]=='+')
right=100;
else
right=-100;
break;
}
case 4:
{
if(rec[i+1]=='+')
right=10*(rec[i+2]-'0')+rec[i+3]-'0';
else
right=-(10*(rec[i+2]-'0')+rec[i+3]-'0');
break;
}
case 3:
{
if(rec[i+1]=='+')
right=rec[i+2]-'0';
else
right=-(rec[i+2]-'0');
break;
}
default:
right=0;
}
}//读取遥控器数值end
//left*=0.5;
//可用
if(abs(left)>=10)
{
leftmotor=left*(100+right)/100.0;
rightmotor=left*(100-right)/100.0;
}
else
{
leftmotor=left+right*0.09;
rightmotor=left-right*0.09;
}
//可用勿删
float t=abs(left);
if(t<=10)
{
leftmotor=left+right*0.09;
rightmotor=left-right*0.09;
}
if(t>10&&t<=20)
{
leftmotor=left+right*0.13;
rightmotor=left-right*0.13;
}
if(t>20&&t<=30)
{
leftmotor=left+right*0.17;
rightmotor=left-right*0.17;
}
if(t>30&&t<=40)
{
leftmotor=left+right*0.5;
rightmotor=left-right*0.5;
}
if(t>40)
{
leftmotor=left+right*1;
rightmotor=left-right*1;
}
//计算速度
if(leftmotor>100)
{
leftmotor=100;
}
if(leftmotor<-100)
{
leftmotor=-100;
}
if(rightmotor>100)
{
rightmotor=100;
}
if(rightmotor<-100)
{
rightmotor=-100;
}
//解算速度
//右边电机驱动
leftpid((int)leftmotor);//-------------------pid计算
rightpid((int)rightmotor);
// Serial.print(left);//期望转速
// Serial.print(" ");
// Serial.print(right);//期望转速
// Serial.println(" ");
Serial.print(leftmotor*0.4);//期望转速
Serial.print(" ");
Serial.print(leftcount);//实际转速
Serial.print(" ");
Serial.print(" ");
Serial.print(leftout);//输出
Serial.print(rightmotor*0.4);//期望转速
Serial.print(" ");
Serial.print(rightcount);//实际转速
Serial.print(" ");
Serial.println(rightout);//输出
if(rightout>0)
{
digitalWrite(11, LOW);
analogWrite(9, (int)rightout);
}
if(rightout<0)
{
digitalWrite(9, LOW);
analogWrite(11, (int)abs(rightout));
}
if(rightout==0)
{
digitalWrite(11, LOW);
digitalWrite(9, LOW);
}
//左边电机驱动
if(leftout>0)
{
digitalWrite(5, LOW);
analogWrite(6, (int)leftout);
}
if(leftout<0)
{
digitalWrite(6, LOW);
analogWrite(5, (int)abs(leftout));
}
if(leftout==0)
{
digitalWrite(5, LOW);
digitalWrite(6, LOW);
}
//更新数据,清除编码器
leftlasterr=leftnowerr;
rightlasterr=rightnowerr;
leftcount=0;
rightcount=0;
delay(25);
}
:::
电磁组
:::details
void setup() {
// put your setup code here, to run once:
Serial.begin(9600);
attachInterrupt(digitalPinToInterrupt(2), left, RISING);//2为左边中断口
attachInterrupt(digitalPinToInterrupt(3), right, RISING);//3为右边中断口
pinMode(6, OUTPUT); //in2
pinMode(5, OUTPUT); //in1(left)
pinMode(10,INPUT);
pinMode(12,INPUT);
pinMode(11, OUTPUT); //in2(right)
pinMode(9, OUTPUT); //in1
}
long int leftcount=0;
long int rightcount=0;
void left()
{
if(digitalRead(10)==1)
leftcount++;
else
leftcount--;
}
void right()
{
if(digitalRead(12)==0)
rightcount++;
else
rightcount--;
}
float leftlasterr=0;//左边lasterr
float leftnowerr=0;//左边当前误差
float leftout=0;//左边输出
int leftpid(float lefttar)
{
leftnowerr=lefttar-leftcount;
leftout+=leftnowerr*2+(leftnowerr-leftlasterr)*8;
if(leftout>255)
leftout=255;
if(leftout<-255)
leftout=-255;
if(abs(leftnowerr)<1&&abs(lefttar)<1)
leftout=0;
}
float rightlasterr=0;//左边lasterr
float rightnowerr=0;//左边当前误差
float rightout=0;//左边输出
int rightpid(float righttar)
{
rightnowerr=righttar-rightcount;
rightout+=rightnowerr*2+(rightnowerr-rightlasterr)*8;
if(rightout>255)
rightout=255;
if(rightout<-255)
rightout=-255;
if(abs(rightnowerr)<1&&abs(righttar)<1)
rightout=0;
}
float leftmotor=20;
float rightmotor=20;
int basespeed=100;//100 30s
float p=0.6;
void loop() {
// put your main code here, to run repeatedly:
delay(50);
float x1 = analogRead(A0)/3.0;//left
float x2 = analogRead(A1)/3.0;//right
float x3 = analogRead(A2)/3.0;//right
float x4 = analogRead(A3)/3.0;//right
int last_x1=x1;
int last_x2=x2;
int last_x3=x3;
int last_x4=x4;
float err=x2-x3;//正的偏差左转,负的右转
float err1=x1-x4;
float err2=(x1+x2)/2-(x3+x4)/2;
float err3=(err+err1)/2;
// Serial.print(x1);
// Serial.print(' ');
// Serial.print(x2);
// Serial.print(' ');
// Serial.print(x3);
// Serial.print(' ');
// Serial.print(x4);
// Serial.print(' ');
Serial.print(err3);
Serial.print(' ');
Serial.print(basespeed-err3*p);
Serial.print(' ');
Serial.print(basespeed+err3*p);
Serial.print(' ');
Serial.print(leftcount);
Serial.print(' ');
Serial.println(rightcount);
// Serial.print(leftmotor);//期望转速
// Serial.print(" ");
// Serial.print(leftcount);//实际转速
// Serial.print(" ");
// Serial.print(" ");
// Serial.print(leftout);//输出
// Serial.print(rightmotor);//期望转速
// Serial.print(" ");
// Serial.print(rightcount);//实际转速
// Serial.print(" ");
// Serial.println(rightout);//输出
leftpid(basespeed-err3*p);//-------------------pid计算
rightpid(basespeed+err3*p);
//Serial.println(leftout);
if(rightout>0)
{
digitalWrite(11, LOW);
analogWrite(9, (int)rightout);
}
if(rightout<0)
{
digitalWrite(9, LOW);
analogWrite(11, (int)abs(rightout));
}
if(rightout==0)
{
digitalWrite(11, LOW);
digitalWrite(9, LOW);
}
//左边电机驱动
if(leftout>0)
{
digitalWrite(5, LOW);
analogWrite(6, (int)leftout);
}
if(leftout<0)
{
digitalWrite(6, LOW);
analogWrite(5, (int)abs(leftout));
}
if(leftout==0)
{
digitalWrite(5, LOW);
digitalWrite(6, LOW);
}
//更新数据,清除编码器
leftlasterr=leftnowerr;
rightlasterr=rightnowerr;
leftcount=0;
rightcount=0;
}
:::
:::tip
感谢观看~
:::
by rocket 202211.21 23:14