STM32--智能小车
简介
功能:避障,红外循迹,蓝牙控制
材料:红外循迹模块,电机驱动,两个电机,舵机,超声波测距,蓝牙模块,降压模块,12v锂电池,stlink下载,杜邦线若干(有两根必须能承受12v电压功率)
此项目搭建材料,主程序编写与模块编写全由我一人完成,耗时5天
困难
制作这小车遇到的困难:
1.循迹模块遇到黑色返回或遇到白色都无返回值,但白色与黑色之间的转换指示灯会亮灭
原因:其所接杜邦线电阻过大,导致红外模块遇见黑色传回高电平被电线分压分太多,导致stm32无法接受到高电平
解决方法:换电阻小一点的杜邦线
2.蓝牙随便输出一个指令后就与手机蓝牙断开
原因:stlink 5v供电不足
解决方法:换成减压模块的5v
3.pwm输出无法用差速法改变小车转弯
原因:代码原因
注:每次调试完小车必须把降压模块与电池的联系,如果没有断开电池与降压模块的联系,在下载程序时会将降压模块烧毁
大体程序思路
1.三个模式用枚举表示,并且三个模式随时可以用蓝牙来切换
2.避障模式,将舵机转到正前方,当前方距离小于18cm大于2cm时,舵机转向右侧,获取右侧在2-18cm距离有无障碍物,并将创建一个变量存储这个距离,再用同方法获取左侧的值,将两个值比较如果右侧的值大于||右侧2-18cm没有障碍物那右转且将舵机转到正前方,else if 如果左边的值大于18cm就左转且将舵机转到正前方,else 后退
3.循迹模式,如果左红外模块遇见黑线就往右靠,如果右红外模块遇见黑线就往左靠,如果两边都遇见黑线就停可能遇见十字路口了
程序源码
main.c
#include "stm32f10x.h"
#include "Delay.h"
#include "PWM.h"
#include "MOTOR.h"
#include "HC-SR04.h"
#include "SG90.h"
#include "SERIAL.h"
#include "TCRT5000.h"
// 定义模式枚举
typedef enum {
MODE_BLUETOOTH = 0, // 蓝牙控制模式
MODE_AVOID, // 避障模式
MODE_LINE_TRACK // 巡线模式
} OperationMode;
// 定义传感器状态
typedef enum {
LINE_NONE = 0, // 未检测到黑线
LINE_LEFT, // 左侧传感器检测到黑线
LINE_RIGHT, // 右侧传感器检测到黑线
LINE_BOTH // 两侧都检测到黑线
} LineState;
volatile OperationMode currentMode = MODE_BLUETOOTH; // 当前模式,默认为蓝牙控制
volatile uint8_t bluetoothCmd = 0; // 蓝牙接收的字符
// 获取巡线传感器状态
LineState GetLineState(void) {
uint8_t leftSensor = GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_12);
uint8_t rightSensor = GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_13);
if (leftSensor == SET && rightSensor == SET ) {
return LINE_BOTH;
} else if (leftSensor == SET) {
return LINE_LEFT;
} else if (rightSensor == SET) {
return LINE_RIGHT;
} else {
return LINE_NONE;
}
}
int main(void) {
// 初始化各模块
PWM_Init(); // PWM初始化(用于电机控制)
MOTOR_Init(); // 电机初始化
HCSR04_Init(); // 超声波模块初始化
SG90_Init(); // 舵机初始化
SERIAL_Init(); // 串口(蓝牙)初始化
TCRT5000_Init(); // 红外传感器初始化
// 设置舵机初始角度为90°(正前方)
SG90_SetCompare3(90);
Delay_ms(500); // 等待舵机稳定
while (1) {
// 检查蓝牙数据,切换模式
if (USART_GetFlagStatus(USART1, USART_FLAG_RXNE) == SET) {
bluetoothCmd = USART_ReceiveData(USART1);
switch (bluetoothCmd) {
case '1':
currentMode = MODE_BLUETOOTH;
// 切换到蓝牙模式时停止电机
MOTOR_SETSPEED1(0);
MOTOR_SETSPEED2(0);
break;
case '2':
currentMode = MODE_AVOID;
// 切换到避障模式时重置舵机位置
SG90_SetCompare3(90);
Delay_ms(500);
break;
case '3':
currentMode = MODE_LINE_TRACK;
break;
default:
break;
}
}
// 根据当前模式执行相应操作
switch (currentMode) {
case MODE_BLUETOOTH:
// 蓝牙控制模式:通过串口控制移动
SERIAL_UP(bluetoothCmd); // 处理前进指令'A'
SERIAL_DOWN(bluetoothCmd); // 处理后退指令'B'
bluetoothCmd=SERIAL_LEFT(bluetoothCmd); // 处理左转指令'C'
bluetoothCmd=SERIAL_RIGHT(bluetoothCmd); // 处理右转指令'D'
SERIAL_STOP(bluetoothCmd); // 处理停止指令'G'
SERIAL_TAIC(bluetoothCmd); // 处理原地转向指令'E'
break;
case MODE_AVOID: {
// 避障模式:检测前方障碍物并决策
float distance = HCSR04_MY(); // 获取前方距离
if (distance < 18.0 && distance > 2.0) { // 检测到障碍物(2cm-18cm范围内)
// 第一步:停止前进
MOTOR_SETSPEED1(0);
MOTOR_SETSPEED2(0);
Delay_ms(300);
// 第二步:舵机转向0°(右侧)
SG90_SetCompare3(0);
Delay_ms(800);
float rightDistance = HCSR04_MY(); // 测量右侧距离
// 第三步:舵机转向180°(左侧)
SG90_SetCompare3(180);
Delay_ms(800);
float leftDistance = HCSR04_MY(); // 测量左侧距离
// 第四步:恢复舵机到90°(正前方)
SG90_SetCompare3(90);
Delay_ms(500);
// 决策转向方向
if (rightDistance >= 18.0 && rightDistance > leftDistance) {
// 右侧无障碍且比左侧空间大,右转
MOTOR_SETSPEED1(60);
MOTOR_SETSPEED2(-60);
Delay_ms(400);
} else if (leftDistance >= 18.0) {
// 左侧无障碍,左转
MOTOR_SETSPEED1(-60);
MOTOR_SETSPEED2(60);
Delay_ms(400);
} else {
// 两侧都有障碍,后退然后尝试转向
MOTOR_SETSPEED1(-80);
MOTOR_SETSPEED2(-80);
Delay_ms(600);
MOTOR_SETSPEED1(-60);
MOTOR_SETSPEED2(60);
Delay_ms(400);
}
} else {
// 前方无障碍,继续前进
MOTOR_SETSPEED1(70);
MOTOR_SETSPEED2(70);
}
break;
}
case MODE_LINE_TRACK: {
// 巡线模式:根据双红外传感器检测黑线
LineState state = GetLineState();
switch (state) {
case LINE_BOTH:
// 两侧都检测到黑线(可能到达终点或十字路口),停止或前进
MOTOR_SETSPEED1(50);
MOTOR_SETSPEED2(50);
break;
case LINE_LEFT:
// 只有左侧检测到黑线,向右调整
MOTOR_SETSPEED1(80);
MOTOR_SETSPEED2(30);
break;
case LINE_RIGHT:
// 只有右侧检测到黑线,向左调整
MOTOR_SETSPEED1(30);
MOTOR_SETSPEED2(80);
break;
case LINE_NONE:
default:
// 未检测到黑线,根据上一次状态决定方向
// 这里简单处理为停止,实际可以添加更复杂的逻辑
MOTOR_SETSPEED1(0);
MOTOR_SETSPEED2(0);
break;
}
break;
}
}
Delay_ms(10); // 短暂延时,防止程序过于频繁执行
}
}
PWM.C
#include "stm32f10x.h" // Device header
void PWM_Init(void )
{
RCC_APB1PeriphClockCmd (RCC_APB1Periph_TIM2,ENABLE ); //开启定时器2的时钟
RCC_APB2PeriphClockCmd (RCC_APB2Periph_GPIOA,ENABLE ); //开启GPIOA定时器
GPIO_InitTypeDef S1;
S1.GPIO_Mode =GPIO_Mode_AF_PP ; //给pin1和pin0引脚设置复用推挽输出
S1.GPIO_Pin =GPIO_Pin_0 |GPIO_Pin_1 ;
S1.GPIO_Speed =GPIO_Speed_50MHz ;
GPIO_Init (GPIOA ,&S1);
TIM_InternalClockConfig (TIM2 ); //设置定时器2的时钟信号为72mhz
TIM_TimeBaseInitTypeDef S2;
S2.TIM_ClockDivision =TIM_CKD_DIV1 ; //不分频
S2.TIM_CounterMode =TIM_CounterMode_Up ; //向上计数
S2.TIM_Period =100-1; //设置自动重装器
S2.TIM_Prescaler =36-1; //设置预分频器
TIM_TimeBaseInit (TIM2,&S2);
TIM_OCInitTypeDef S3;
TIM_OCStructInit (&S3); //初始化结构体(给结构体所有数都赋一个初始值)
S3.TIM_OCMode =TIM_OCMode_PWM1 ; //设置输出比较模式1,当计数小于rcc时输出正
S3.TIM_OCPolarity =TIM_OCPolarity_High ;
S3.TIM_OutputState = TIM_OutputState_Enable;
S3.TIM_Pulse =0; //设置占空比
TIM_OC1Init(TIM2,&S3);
TIM_OC2Init(TIM2,&S3);
TIM_Cmd (TIM2,ENABLE );
}
HC-SR04.c
#include "stm32f10x.h" // Device header
#include "Delay.h"
#include "PWM.h"
void HCSR04_Init(void )
{
RCC_APB2PeriphClockCmd (RCC_APB2Periph_GPIOB,ENABLE );
RCC_APB2PeriphClockCmd (RCC_APB2Periph_TIM1,ENABLE );
GPIO_InitTypeDef S1;
S1.GPIO_Mode =GPIO_Mode_Out_PP;
S1.GPIO_Pin =GPIO_Pin_14;
S1.GPIO_Speed =GPIO_Speed_50MHz ;
GPIO_Init (GPIOB ,&S1);
S1.GPIO_Mode =GPIO_Mode_IPD ;
S1.GPIO_Pin =GPIO_Pin_15;
GPIO_Init (GPIOB ,&S1);
TIM_InternalClockConfig (TIM1 );
TIM_TimeBaseInitTypeDef S2;
S2.TIM_ClockDivision =TIM_CKD_DIV1 ;
S2.TIM_CounterMode =TIM_CounterMode_Up ;
S2.TIM_Period =50000-1;
S2.TIM_Prescaler =72-1;
S2.TIM_RepetitionCounter =0;
TIM_TimeBaseInit(TIM1 ,&S2);
}
float HCSR04_MY(void )
{
uint32_t NUM;
//发送至少持续10us的高电平
GPIO_ResetBits (GPIOB ,GPIO_Pin_14);
Delay_us (2);
GPIO_SetBits (GPIOB ,GPIO_Pin_14 );
Delay_us (20);
GPIO_ResetBits (GPIOB,GPIO_Pin_14);
//等待pin15收到高电平
while(GPIO_ReadInputDataBit (GPIOB,GPIO_Pin_15 )==RESET );
//收到后把计数器置0,并给定时器使能
TIM1 ->CNT =0;
TIM_Cmd (TIM1 ,ENABLE );
//等pin15的电平变低,得到pin15持续高电平的时间,给定时器失能
while(GPIO_ReadInputDataBit (GPIOB,GPIO_Pin_15 )==SET );
TIM_Cmd (TIM1 ,DISABLE );
//把计数器的值给num
NUM=TIM_GetCounter (TIM1 );
//计算距离
float M=(NUM*1.0*0.034)/2;
Delay_ms (100);
if(NUM >38000)
{
M=0;
}
//返回距离
return M;
}
SG90.c
#include "stm32f10x.h" // Device header
#include "PWM.h"
void SG90_Init(void )
{
RCC_APB1PeriphClockCmd (RCC_APB1Periph_TIM3,ENABLE ); //开启定时器2的时钟
RCC_APB2PeriphClockCmd (RCC_APB2Periph_GPIOB ,ENABLE ); //开启gpio时钟,这是给舵机准备
GPIO_InitTypeDef S1;
S1.GPIO_Mode =GPIO_Mode_AF_PP ; //给pin1和pin0引脚设置复用推挽输出
S1.GPIO_Pin =GPIO_Pin_0 ;
S1.GPIO_Speed =GPIO_Speed_50MHz ;
GPIO_Init (GPIOB,&S1);
TIM_InternalClockConfig (TIM3 ); //舵机使用的TIM3定时器
TIM_TimeBaseInitTypeDef S2;
S2.TIM_ClockDivision =TIM_CKD_DIV1 ; //不分频
S2.TIM_CounterMode =TIM_CounterMode_Up ; //向上计数
S2.TIM_Period =20000-1; //设置自动重装器,舵机规定频率为50hz
S2.TIM_Prescaler =72-1; //设置预分频器
TIM_TimeBaseInit (TIM3,&S2);
TIM_OCInitTypeDef S3;
TIM_OCStructInit (&S3); //初始化结构体(给结构体所有数都赋一个初始值)
S3.TIM_OCMode =TIM_OCMode_PWM1 ; //设置输出比较模式1,当计数小于rcc时输出正
S3.TIM_OCPolarity =TIM_OCPolarity_High ;
S3.TIM_OutputState = TIM_OutputState_Enable;
S3.TIM_Pulse =0; //设置占空比
TIM_OC3Init(TIM3,&S3);
TIM_Cmd (TIM3,ENABLE );
}
void SG90_SetCompare3(float NUM)
{
TIM_SetCompare3(TIM3 ,NUM/180*2000+500);
}
MOTOR.c
#include "stm32f10x.h" // Device header
#include "PWM.h"
#include <stdlib.h>
void MOTOR_Init(void )
{
PWM_Init ();
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_InitTypeDef GPIO_InitStructure; //调节反向需要用的脚
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP ;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4|GPIO_Pin_5 |GPIO_Pin_6 |GPIO_Pin_7 ;
GPIO_Init(GPIOA, &GPIO_InitStructure);
}
void MOTOR_SETSPEED1(int8_t NUM) //调节左轮速度
{
if (NUM < 0)
{
GPIO_SetBits(GPIOA, GPIO_Pin_4); // IN1 = 1(正转)
GPIO_ResetBits(GPIOA, GPIO_Pin_5); // IN2 = 0
TIM_SetCompare1(TIM2,-NUM ); // 设置占空比
} else if (NUM > 0) {
GPIO_ResetBits(GPIOA, GPIO_Pin_4); // IN1 = 0
GPIO_SetBits(GPIOA, GPIO_Pin_5); // IN2 = 1(反转)
TIM_SetCompare1(TIM2, NUM ); // 取绝对值
} else {
GPIO_ResetBits(GPIOA, GPIO_Pin_4); // IN1 = 0(停止)
GPIO_ResetBits(GPIOA, GPIO_Pin_5); // IN2 = 0
TIM_SetCompare1(TIM2, 0); // 占空比 0%
}
}
void MOTOR_SETSPEED2(int8_t NUM) //调节右轮速度
{
if (NUM <0)
{
GPIO_SetBits(GPIOA, GPIO_Pin_6); // IN1 = 1(正转)
GPIO_ResetBits(GPIOA, GPIO_Pin_7); // IN2 = 0
TIM_SetCompare2(TIM2,-NUM ); // 设置占空比
} else if (NUM > 0) {
GPIO_ResetBits(GPIOA, GPIO_Pin_6); // IN1 = 0
GPIO_SetBits(GPIOA, GPIO_Pin_7); // IN2 = 1(反转)
TIM_SetCompare2(TIM2, NUM ); // 取绝对值
} else {
GPIO_ResetBits(GPIOA, GPIO_Pin_6); // IN1 = 0(停止)
GPIO_ResetBits(GPIOA, GPIO_Pin_7); // IN2 = 0
TIM_SetCompare2(TIM2, 0); // 占空比 0%
}
}
TCRT5000.c
#include "stm32f10x.h" // Device header
void TCRT5000_Init(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
// 使能GPIOB时钟
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
// 配置 PB12 为输入模式,用于接收传感器信号
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12|GPIO_Pin_13 ;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD ; // 上拉输入。根据传感器特性,也可选用IPD(下拉输入)
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &GPIO_InitStructure);
/**
如果pin12来低电平就说明红外传感器,感受到黑色,来高电平就是白色
**/
}