今天劳动节了,发个帖子庆祝一下节日,很久没发过帖子了,不知道上次发帖是在那年了,平时工作忙回家看孩子没有时间搞研究了,4月份发生一个小事故手受伤了,在家1个人无聊所以有时间玩会以前买的却没动过的小车,开始认为小车比较简单(材料只是入门那种)做一个给小孩当玩具了,制作当做才发现1堆问题最突出的问题小车不能走直线(开始没PWM),网上确实有很多资料,不过完整的也不是很多,都是最基础问题,到重点的不是不能下载就是资料不全,最后还是要自己研究,程序写的很烂高手见谅吧,希望给需要的朋友一个参考!!
小车才有前2轮驱动,后面1个万向轮(恶梦不能跑直线的开启!)
循迹使用4个红外线对管,1个超声波测距使用航舵控制(实际上还是使用3个超声波测距模块比使用航舵效果会更好)
功能:
1.手机app蓝牙控制
2.左右PWM无极调速
3.超声波测距蔽障(带航舵)
4.红外循迹
5.警车,消防车,救护车三种报警和红蓝爆闪(为了给孩子玩)
手底下就有stc125a60s2,驱动模块什么的都是淘宝买的
制作过程没有拍下来,见谅吧
2节18650串联,使用航舵的朋友注意,航舵耗电很大,需要单独dc模块
上传有限就和看吧
本来有视频的 不会上传先放点图片吧
由于不会写上位软件,最艰苦的就是找上位软件,找了很多没有一个合适的不是需要没人家的小车就是不好用
最后还是选择1个目前认为最好用的软件,这个经常用包括我的家用蓝牙控制器都用这个软件
超声波测距发送到手机上面
电机PWM调速
上下左右控制
/*******************************************************************
智能小车 版本A:
制作人:Gaoshan
日期: 2017-4-7
蓝牙协议:
报警 Blue_alam
前进 Blue_up__
后退 Blue_down
左转 Blue_left
右转 Blue_righ
停止 Blue_stop
加速 Blue_spd+
减速 Blue_spd—
切换 Blue_xjly
测距 Blue_chao
*******************************************************************/
#include<STC12C5A60S2.h>
#include <intrins.h>
#define uchar unsigned char
#define uint unsigned int
sbit buzzer=P0^7;
sbit buzzer1=P0^6;
sbit motor_L1=P0^0;
sbit motor_L2=P0^1;
sbit motor_R1=P0^2;
sbit motor_R2=P0^3;
sbit red1=P2^3;
sbit red2=P2^2;
sbit red3=P2^1;
sbit red4=P2^0;
sbit red5=P1^1;
sbit TX=P0^5;
sbit RX=P0^4;
sbit SEV_PWM=P1^7;
sbit led1=P1^0;
sbit led2=P1^1;
unsigned char code table[]={0x30,0x31,0x32,0x33,0x34,0x35,0x36,0x37,0x38,0x39};
uchar num;
bit flag;
bit zhijiao_flag=1;
bit flag2;
bit test_flag=0;
uchar xjly_flag=1;
uchar buzz=0;
uchar tcp_buf[12]; //接收字符串数组
uchar count=0; //接收字符串计数
uint L_speed=88,R_speed=84;
uint time=0;
uint time2=0;
uint time3=0;
uchar led_flag=0;
bit flag3=0;
long s=0;
long s1=0;
long s2=0;
long s3=0;
bit chao_flag=0;
uchar buff[7]; //字符数组
uchar count1 = 0;
uchar SEV_count = 15;
void delay_ms(uint z);
void delay_us(unsigned int t);
void buzz1();
//void buzz2();
void init();
void PWM_init() ;
void up(int x,int y);
void down(int x,int y);
void left(int x,int y);
void right(int x,int y);
void stop();
void UartInit(void);
void senddata(uchar dat);
void uart_sendstring(uchar *upStr);
void StartModule();
void Conut(void);
void comm(char *parr);
void chao_test();
//void Conut_right(void);
//void Conut_up(void);
//void Conut_left(void);
/**********************************************************/
void delay_ms(uint z) //毫秒延时
{
uint x;
uchar i, j;
for(x=z;x>0;x--)
{
_nop_();
i = 11;
j = 190;
do
{
while (--j);
} while (--i);
}
}
/**********************************************************
void delay_us(unsigned int t) //微秒延时
{
while(--t);
}
/**********************************************************/
void UartInit(void) //9600bps@11.0592MHz
{
PCON &= 0x7F; //波特率不倍速
SCON = 0x50; //8位数据,可变波特率
AUXR |= 0x04; //独立波特率发生器时钟为Fosc,即1T
BRT = 0xDC; //设定独立波特率发生器重装值
AUXR |= 0x01; //串口1选择独立波特率发生器为波特率发生器
AUXR |= 0x10; //启动独立波特率发生器
ES = 1;
EA = 1;
TI=1;//直接使用printf必须加入此句才能实现发送
}
/**********************************************************/
/*PWM初始化函数*/
void PWM_init()
{
CMOD=0x02;
CCAPM0=0x42;
CCAPM1=0x42;
CCAP1L=0x00;
CCAP1H=0x00;
CCAP0L=0x00;
CCAP0H=0x00;
CR=1;
}
void init()
{
TMOD=0x11; //设T0为方式1,GATE=1;
TH0=0;
TL0=0;
TR0=1;
ET0=1; //允许T0中断
TH1 = 0xff; //配置定时器1初值,溢出时间为0.1ms
TL1 = 0xa4;
ET1 = 1; //打开定时器1中断
TR1 = 1; //开启定时器1
motor_L1=0;
motor_L2=0;
motor_R1=0;
motor_R2=0;
buzzer=0;
delay_ms(100);
buzzer=1;
delay_ms(100);
}
/**********************************************************/
void StartModule()
{
TX=1; // 启动一次模块
// _nop_();
// _nop_();
// _nop_();
delay_ms(10); //100MS
TX=0;
}
void Conut(void)
{
while(!RX); //当RX为零时等待
TR0=1; //开启计数
while(RX); //当RX为1计数并等待
TR0=0;
time=TH0*256+TL0;
TH0=0;
TL0=0;
s=(time*1.87)/100; //算出来是CM
// if(chao_flag==1) //超出测量
// {
// chao_flag=0;
//// uart_sendstring("-------");
//// senddata(0x0d);
//// senddata(0x0a);
// }
}
/**********************************************************/
void senddata(uchar dat)
{
ES = 0; //关串口中断
TI = 0; //将串口发送完成中断请求标志清零
SBUF = dat; //写数据到发送缓冲区
while(!TI); //等待发送完成
TI = 0; //将串口发送完成中断请求标志清零
ES = 1; //将串口发送完成中断请求标志清零
}
/* ***************************************************** */
// 函数名称:UART_SendString()
// 函数功能:发送字符串
// 入口参数:待发送的字符串(*upStr)
// 出口参数:无
/* *****************************************************/
void uart_sendstring(uchar *upStr)
{
while(*upStr) // 检测是否发送完毕
{
senddata(*upStr++);
// 调用UART_SendOneByte函数一个字节一个字节发送数据
}
}
/* ***************************************************** */
void buzz1()
{
buzzer=0;
delay_ms(20);
buzzer=1;
}
/***************************************************************************
函数名称:行走函数
函数功能:驱动电机
函数备注:x为左边电机的速度,y为右边电机的速度
-255<x<255,-255<y<255
0~255向前,-255~-1向后,绝对值越大,速度越大
***************************************************************************/
void up(int x,int y)
{
if(y>0)
{
CCAP0L=y;
CCAP0H=y;
motor_R1=0;
motor_R2=1;
}
else
{
CCAP0L=-y;
CCAP0H=-y;
motor_R1=1;
motor_R2=0;
}
if(x>0)
{
CCAP1L=x;
CCAP1H=x;
motor_L1=0;
motor_L2=1;
}
else
{
CCAP1L=-x;
CCAP1H=-x;
motor_L1=1;
motor_L2=0;
}
}
/***************************************************************************/
void down(int x,int y)
{
if(y>0)
{
CCAP0L=y;
CCAP0H=y;
motor_R1=1;
motor_R2=0;
}
else
{
CCAP0L=-y;
CCAP0H=-y;
motor_R1=0;
motor_R2=1;
}
if(x>0)
{
CCAP1L=x;
CCAP1H=x;
motor_L1=1;
motor_L2=0;
}
else
{
CCAP1L=-x;
CCAP1H=-x;
motor_L1=0;
motor_L2=1;
}
}
/***************************************************************************/
void left(int x,int y)
{
if(y>0)
{
CCAP0L=y;
CCAP0H=y;
motor_R1=1;
motor_R2=0;
}
else
{
CCAP0L=-y;
CCAP0H=-y;
motor_R1=0;
motor_R2=1;
}
if(x>0)
{
CCAP1L=x;
CCAP1H=x;
motor_L1=0;
motor_L2=1;
}
else
{
CCAP1L=-x;
CCAP1H=-x;
motor_L1=1;
motor_L2=0;
}
}
/***************************************************************************/
void right(int x,int y)
{
if(y>0)
{
CCAP0L=y;
CCAP0H=y;
motor_R1=0;
motor_R2=1;
}
else
{
CCAP0L=-y;
CCAP0H=-y;
motor_R1=1;
motor_R2=0;
}
if(x>0)
{
CCAP1L=x;
CCAP1H=x;
motor_L1=1;
motor_L2=0;
}
else
{
CCAP1L=-x;
CCAP1H=-x;
motor_L1=0;
motor_L2=1;
}
}
void stop()
{
motor_L1=0;
motor_L2=0;
motor_R1=0;
motor_R2=0;
}
void chao_test()
{
SEV_count=15;
count1 = 0; //占空比参数t改变,让定时器重新计数
delay_ms(2000);
StartModule();
Conut();
s1=s;
uart_sendstring("Distance_UP_");
SBUF = table[s1/100]; while(!TI); TI=0;
SBUF = table[s1%100/10]; while(!TI); TI=0;
SBUF = table[s1%10]; while(!TI); TI=0;
uart_sendstring("cm");
senddata(0x0d);
senddata(0x0a);
SEV_count=24;
count1 = 0; //占空比参数t改变,让定时器重新计数
delay_ms(2000);
StartModule();
Conut(); //计算
s2=s;
uart_sendstring("Distance_LEFT_");
SBUF = table[s2/100]; while(!TI); TI=0;
SBUF = table[s2%100/10]; while(!TI); TI=0;
SBUF = table[s2%10]; while(!TI); TI=0;
uart_sendstring("cm");
senddata(0x0d);
senddata(0x0a);
SEV_count=5;
count1 = 0; //占空比参数t改变,让定时器重新计数
delay_ms(2000);
StartModule();
Conut(); //计算
s3=s;
uart_sendstring("Distance_RIGHT_");
SBUF = table[s3/100]; while(!TI); TI=0;
SBUF = table[s3%100/10]; while(!TI); TI=0;
SBUF = table[s3%10]; while(!TI); TI=0;
uart_sendstring("cm");
senddata(0x0d);
senddata(0x0a);
SEV_count=15;
count1 = 0; //占空比参数t改变,让定时器重新计数
if((s2<20)||(s3<20)) //只要左右各有距离小于20CM小车后退
{
down(68,66); //后退
delay_ms(400);
}
if(s2>s3)
{
left(68,66); //车的左边比车的右边距离小 右转
delay_ms(300);
}
if(s3>s2)
{
right(68,66); //车的左边比车的右边距离大 左转
delay_ms(300);
}
flag2=0;
}
/**********************************************************
void comm(char *parr) //串口浮点发送
{
do
{
SBUF=*parr++; //字符发送
while(!TI);
TI=0;
}while(*parr);
}
/**********************************************************/
void main()
{
init();
PWM_init();
UartInit();
SEV_count=15; //航舵归位
count1 = 0; //占空比参数t改变,让定时器重新计数
while(1)
{
if(buzz==1) buzzer=0;
if(buzz==2) buzzer1=0;
if(buzz==0) {buzzer=1; buzzer1=1;}
if(xjly_flag==1)
{
if(test_flag==1)
{
SEV_count=15;
count1 = 0; //占空比参数t改变,让定时器重新计数
delay_ms(1000);
StartModule();
Conut();
s1=s;
uart_sendstring("Distance_UP_");
SBUF = table[s1/100]; while(!TI); TI=0;
SBUF = table[s1%100/10]; while(!TI); TI=0;
SBUF = table[s1%10]; while(!TI); TI=0;
uart_sendstring("cm");
senddata(0x0d);
senddata(0x0a);
SEV_count=24;
count1 = 0; //占空比参数t改变,让定时器重新计数
delay_ms(1000);
StartModule();
Conut(); //计算
s2=s;
uart_sendstring("Distance_LEFT_");
SBUF = table[s2/100]; while(!TI); TI=0;
SBUF = table[s2%100/10]; while(!TI); TI=0;
SBUF = table[s2%10]; while(!TI); TI=0;
uart_sendstring("cm");
senddata(0x0d);
senddata(0x0a);
SEV_count=5;
count1 = 0; //占空比参数t改变,让定时器重新计数
delay_ms(1000);
StartModule();
Conut(); //计算
s3=s;
uart_sendstring("Distance_RIGHT_");
SBUF = table[s3/100]; while(!TI); TI=0;
SBUF = table[s3%100/10]; while(!TI); TI=0;
SBUF = table[s3%10]; while(!TI); TI=0;
uart_sendstring("cm");
senddata(0x0d);
senddata(0x0a);
SEV_count=15;
count1 = 0; //伎毡炔问齮改变,让定时器重新
test_flag=0;
}
}
if(xjly_flag==2) //循迹模式
{
if(zhijiao_flag==1) //直角标志位
{
if(red1==0&&red2==0&&red3==0&&red4==0)
up(68,66);
}
if(red1==0&&red2==0&&red3==1&&red4==0)
{
left(182,80);
zhijiao_flag=1;
}
if(red1==0&&red2==1&&red3==0&&red4==0)
{
right(82,180);
zhijiao_flag=1;
}
if(red1==0&&red2==0&&red3==1&&red4==1)
{
left(76,74);
}
if(red1==1&&red2==1&&red3==0&&red4==0)
{
right(76,74);
}
if(red1==0&&red2==0&&red3==0&&red4==1)
{
left(60,68);
zhijiao_flag=0;
}
if(red1==1&&red2==0&&red3==0&&red4==0)
{
right(60,68);
zhijiao_flag=0;
}
if(red1==1&&red2==1&&red3==1&&red4==1)
stop();
}
if(xjly_flag==4)
{
stop();
xjly_flag=1;
}
if(xjly_flag==3) //超声波避障模式
{
if(flag2==0)
{
StartModule(); //启动检测
Conut(); //计算距离
}
if(s<20) //距离小于20CM
{
stop(); //小车停止
flag2=1;
chao_test(); //方向函数
}
if(s>20) //距离大于,30CM往前走
up(68,66);
}
}
}
void interrupt_uart() interrupt 4
{
if(TI)
{
TI = 0;
REN = 1;
}
if(RI)
{
RI = 0;
tcp_buf[count]=SBUF; //接收串口发出字符串放进数组
if(tcp_buf[0]=='B') //如果接受字符串第一个字符为'B'将继续接受,反之放弃接受
count++;
else
count=0;
/**************************************/
if(count>8) //如果接受字节大于8个开始检测接受字节后六位数据
{
// 第1路开关 wifi 开关
//如果接受数组0-8位接受到 “Blue_alam”执行以下函数
if(tcp_buf[5]=='a'&&tcp_buf[6]=='l'&&tcp_buf[7]=='a'&&tcp_buf[8]=='m') //报警
{
buzz++;
if(buzz==3)
{
buzz=0;
uart_sendstring("Buzzer_OFF");
senddata(0x0d);
senddata(0x0a);
}
uart_sendstring("Buzzer_ON");
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='u'&&tcp_buf[6]=='p'&&tcp_buf[7]=='_'&&tcp_buf[8]=='_') //前进
{
up(L_speed,R_speed);
uart_sendstring("Car_UP");
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='d'&&tcp_buf[6]=='o'&&tcp_buf[7]=='w'&&tcp_buf[8]=='n') //后退
{
down(L_speed,R_speed);
uart_sendstring("Car_DOWN");
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='l'&&tcp_buf[6]=='e'&&tcp_buf[7]=='f'&&tcp_buf[8]=='t') //左转
{
left(L_speed,R_speed);
uart_sendstring("Car_LEFT");
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='r'&&tcp_buf[6]=='i'&&tcp_buf[7]=='g'&&tcp_buf[8]=='h') //右转
{
right(L_speed,R_speed);
uart_sendstring("Car_RIGHT");
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='x'&&tcp_buf[6]=='j'&&tcp_buf[7]=='l'&&tcp_buf[8]=='y') //蓝牙,循迹,蔽障切换
{
xjly_flag++;
if(xjly_flag==1)
{
stop();
uart_sendstring("BLUE_Mode");
senddata(0x0d);
senddata(0x0a);
}
if(xjly_flag==2)
{
uart_sendstring("Cyc_Mode");
senddata(0x0d);
senddata(0x0a);
}
if(xjly_flag==3)
{
uart_sendstring("Barrier_Mode");
senddata(0x0d);
senddata(0x0a);
}
if(xjly_flag==4)
{
uart_sendstring("BLUE_Mode");
senddata(0x0d);
senddata(0x0a);
}
buzz1();
}
if(tcp_buf[5]=='s'&&tcp_buf[6]=='p'&&tcp_buf[7]=='d'&&tcp_buf[8]=='+') //加速
{
L_speed--;
if(L_speed<=4)
L_speed=4;
R_speed--;
if(R_speed<=1)
R_speed=1;
uart_sendstring("LMS_");
SBUF = table[L_speed/100]; while(!TI); TI=0;
SBUF = table[L_speed%100/10]; while(!TI); TI=0;
SBUF = table[L_speed%10]; while(!TI); TI=0;
uart_sendstring(" ");
uart_sendstring("RMS_");
SBUF = table[R_speed/100]; while(!TI); TI=0;
SBUF = table[R_speed%100/10]; while(!TI); TI=0;
SBUF = table[R_speed%10]; while(!TI); TI=0;
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='s'&&tcp_buf[6]=='p'&&tcp_buf[7]=='d'&&tcp_buf[8]=='-') //减速
{
L_speed++;
if(L_speed>=92)
L_speed=92;
R_speed++;
if(R_speed>=88)
R_speed=88;
uart_sendstring("lMS_");
SBUF = table[L_speed/100]; while(!TI); TI=0;
SBUF = table[L_speed%100/10]; while(!TI); TI=0;
SBUF = table[L_speed%10]; while(!TI); TI=0;
uart_sendstring(" ");
uart_sendstring("RMS_");
SBUF = table[R_speed/100]; while(!TI); TI=0;
SBUF = table[R_speed%100/10]; while(!TI); TI=0;
SBUF = table[R_speed%10]; while(!TI); TI=0;
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='s'&&tcp_buf[6]=='t'&&tcp_buf[7]=='o'&&tcp_buf[8]=='p') //停止
{
stop();
}
if(tcp_buf[5]=='c'&&tcp_buf[6]=='h'&&tcp_buf[7]=='a'&&tcp_buf[8]=='o') //测距
{
test_flag=1;
uart_sendstring("Distance......");
senddata(0x0d);
senddata(0x0a);
}
if(tcp_buf[5]=='l'&&tcp_buf[6]=='e'&&tcp_buf[7]=='d'&&tcp_buf[8]=='_') //测距
{
flag3=~flag3;
if(flag3==1)
{
uart_sendstring("LED_ON");
senddata(0x0d);
senddata(0x0a);
}
else
{
uart_sendstring("LED_OFF");
senddata(0x0d);
senddata(0x0a);
}
}
count=0;
}
}
}
void zd0() interrupt 1 //T0中断用来计数器溢出,超过测距范围
{
chao_flag=1; //中断溢出标志
}
/* 定时器0中断服务程序 */
void Time1_Int() interrupt 3
{
TR1 = 0; //关闭定时器0
TH1 = 0xff; //重装初值0.1ms
TL1 = 0xa4;
time2++;
if(flag3==1)
{
if(led_flag==0)
{
if(time2==500)
{
time2=0;
led2=~led2;
time3++;
if(time3==20)
{
time3=0;
time2=0;
led1=1;
led_flag=1;
}
}
}
if(led_flag==1)
{
if(time2==500)
{
time2=0;
led1=~led1;
time3++;
if(time3==20)
{
time3=0;
time2=0;
led2=1;
led_flag=2;
}
}
}
if(led_flag==2)
{
if(time2==500)
{
time2=0;
led1=~led1;
led2=~led2;
time3++;
if(time3==20)
{
time3=0;
time2=0;
led1=1;
led2=1;
led_flag=0;
}
}
}
}
else
{
led1=1;
led2=1;
time2=0;
time3=0;
led_flag=0;
}
//舵机
if(count1 <= SEV_count) //控制占空比上下
{
SEV_PWM = 1;
}
else
{
SEV_PWM = 0;
}
count1++;
if (count1 >= 200) //T = 20ms则定时器计数变量清0
{
count1 = 0;
}
TR1 = 1; //开启定时器0
}
以前发帖子,大家要程序经常需要下载,这回直接贴里面了有问题可以交流 weixin16736099