一,硬件
1.电源
本设计采用两级压降设计,在提升电压转换效率的同时,尽可能减少降压芯片的散热。
一级压降采用DC-DC模块将三节串联的18650电池的12V降到5V,具体选型采用的是TI的TPS5430芯片,其最大电流3A(可用TPS5450代替,最大电流5A),大于本次设计所有用电设备的电流之和,且余量充足,满足设计要求。R33和R34为反馈电路,调节输出电压。原理图如下所示。
二级压降为最常见的线性稳压器AMS1117,将5V降压为3.3V为控制单元供电。这里需要特别注意,虽然LDO可以实现12V直接到3.3V的压降,但是由于压差过大,且从LDO的原理分析,12V到3.3V的转换效率过低,剩下8.7V全部用于发热,极容易导致芯片的损坏,在本设计的第一版测试时,即便采用TI的LM1117作为压降,仍然会导致芯片发热严重,最后击穿的现象。因此两级压降非常有必要。本次设计采用一个LDO为所有3.3V设备供电,但最好将DC-DC输出的5V,再引出两路LDO压降,一路专为MCU供电,另一路为PCB上的其他用电设备供电,防止一个LDO的流过的电流过大。二级压降原理图如下:
电源接口和滤波电容如下所示:
这里在12V滤波位置加了一个反向稳压二极管,从原理上分析,由于本次设计采用了12V的电机,虽然电机电流较小,但是经常会出现电机正反转来回切换的情况,这是在电机正反转切换的瞬间会发生电压激变的情况,而激变的电压输入到控制电路会造成一定的冲击,因此需要加一个反向稳压二极管来消除电机反转带来的电压突变。
2.MCU
本次控制部分采用的是市面上最常见的教学级MCU:STM32F103C8T6,平衡车项目对于MCU的内存要求不高,对于MCU主频要求相对较高,该款MCU支持最大72MHz的主频,满足设计需求,题主在看了arduino的数据手册发现,其实arduino的16Mhz也足够满足本次设计要求。参考ST官方技术手册的典型应用电路画出的MCU原理图如下所示:
在MCU电路设计时,有以下几点需要注意,首先是时钟频率,在不需要精确计时的情况下,比如本次设计中,从成本考虑,不需要低速时钟源(32.768),只需要高速时钟(8Mhz)即可。其次解耦电容是必须要加的,不加也许可以正常运行,但在IO口反转电平时,没有解耦电容会对电源输入有一定的影响,还有就是摆放的个数和位置,MCU有几处供电就加几个解耦电容,位置离MCU供电口越近越好。另外本次设计中为了简化电路,直接将BOOT0/BOOT1全部接地,用SWD进行程序的下载和调试。
3.陀螺仪
本次设计中陀螺仪选择的是应美盛的MPU6050芯片,该款芯片是一款六轴陀螺仪芯片,包括三轴角速度和三轴加速度,并且支持外部扩展,组成九轴陀螺仪芯片,同时通过I2C协议传输数据,可以使用MCU进行模拟I2C通信,对IO外设没有要求,符合本次设计要求。原理图如下所示:
这里有两点需要注意,首先是芯片的焊接:MPU6050采用QFN封装,尺寸非常小,用烙铁焊接比较困难,可以用风枪300度大约30秒即可,不要高于350度,题主第一次焊接时就因为温度过高导致了芯片损坏(如果在读地址的时候芯片只返回地址0x68,多半是芯片烧坏了)。另外需要对该芯片及其外围电路进行单独隔离处理,方便测试阶段确定问题出在什么地方,隔离的方法是在输入输出部分加0Ω电阻,在单独测试可以正常运行后,再接入系统,从何避免了两个模块之间的相互影响,以至于无法确定错误位置。
4.电机驱动
电机驱动采用的是TB6612FNG芯片,该芯片是一款双路H桥电机驱动,采用PWM波控制电机速度,且发热量远小于L298N等常见的电机驱动,不需要外接散热片。原理图如下所示:
这里在12V电压输入位置,同样也做了一个隔离。在所有模块测试完成后,用跳线帽连接即可。
5.WIFI
由于题主对于无线射频方向没有任何设计基础,因此WIFI部分采用基于乐鑫ESP8266芯片的ESP12F模块,无需自己设计天线,只需简单配置外围电路即可正常使用。通过串口与C8T6进行通信。具体设计参考安信可官方的典型应用电路,原理图如下:
6.OLED显示屏
加OLED显示屏主要是为了方便PID参数的调整以及机械零点的确定,直接移植现成的底层函数即可。
7.摄像头
摄像头采用OV2640模块,由于C8T6的引脚和性能限制,无法满足实时视频流的传输和处理,因此在我们采用了ESP32+OV2640组合的模块:ESP32-CAM来实时传输摄像头数据到微信小程序当中。这样既不用单独占用ESP8266的带宽,也无需C8T6进行视频流处理。仅需要3.3V供电即可使用,摄像头底板PCB如下:
7.PCB设计
PCB采用两层板设计,大家可以改进为四层板,只需要将内部两层分别走电和地,其他与两层板差别不大。由于本次设计不涉及高速信号线,无需进行阻抗匹配,因此只要原理图不出问题,不把过孔放在焊盘上(可能会导致焊锡沿着过孔流出去导致虚焊),基本都可以正常使用。另外还需要注意WIFI模块的设计,为其留出信号开孔。 过流大的地方线宽尽可能宽,还有就是地面完整性,电源线即使再宽,铺铜后地线很细也无济于事。PCB如下图所示:
3D模型:
8.电机
本次设计采用的电机型号为GA25-370,该款电机自带霍尔编码器,减速比为25,额定空负载转速为370prm,额定电压12V,最大电流0.5V。其编码器精度为25*370=9250,精度较高,可获得准确的速度参数。满足本次设计需求。
二,软件
(一)STM32
本次设计基于STM32 标准库编程。
MPU6050和OLED显示屏的底层代码是在正点原子移植的,移植的开发板型号为STM32F407战舰V4,可以在正点原子官方下载对应的源码。MPU6050通过调用官方的DMP库将角速度和加速度转换成欧拉角输出。整体逻辑是通过陀螺仪每次刷新角度的中断,在中断函数当中,利用PID算法直立环PD和速度环PI的输出,然后将输出压入到电机去执行,从而实现小车直立。因此本文仅提及控制函数的编写,对于pwm、usart、nvic、exti等不再赘述。
1.控制函数
控制函数由中断服务函数和直立环PD控制器,速度环PI控制器以及转向环PD控制器组成,如下
control.c
#include "control.h"
float Med_Angle=0.0; //机械零点
float Target_Speed=0; //俯仰角
float Turn_Speed=0; //偏航角
float
Vertical_Kp=-210, //直立环KP
Vertical_Kd=-0.6; //直立环KD
float
Velocity_Kp=0.3, //速度环KP
Velocity_Ki=0.0015; //速度环KI
float
Turn_Kd=-0.3, //转向环KD
Turn_Kp=-10; //转向环KP
#define SPEED_Y 50 //¸前进速度
#define SPEED_Z 100 //转弯速度
int Vertical_out,Velocity_out,Turn_out;
//函数声明
int Vertical(float Med,float Angle,float gyro_Y);
int Velocity(int Target,int encoder_left,int encoder_right);
int Turn(int gyro_Z,int RC);
void EXTI9_5_IRQHandler(void)
{
int PWM_out;
if(EXTI_GetITStatus(EXTI_Line5)!=0)
{
if(PBin(5)==0)
{
EXTI_ClearITPendingBit(EXTI_Line5);
//编码器速度采集
Encoder_Left=-Read_Speed(2);
Encoder_Right=Read_Speed(4);
mpu_dmp_get_data(&Pitch,&Roll,&Yaw); //DMP获取欧拉角
MPU_Get_Gyroscope(&gyrox,&gyroy,&gyroz); //角速度
MPU_Get_Accelerometer(&aacx,&aacy,&aacz); //加速度
//WIFI控制前后
if((Fore==0)&&(Back==0))Target_Speed=0;//
if(Fore==1)Target_Speed--;
if(Back==1)Target_Speed++;
Target_Speed=Target_Speed>SPEED_Y?SPEED_Y:(Target_Speed<-SPEED_Y?(-SPEED_Y):Target_Speed);//限幅
/*左右*/
if((Left==0)&&(Right==0))Turn_Speed=0;
if(Left==1)Turn_Speed+=30;
if(Right==1)Turn_Speed-=30;
Turn_Speed=Turn_Speed>SPEED_Z?SPEED_Z:(Turn_Speed<-SPEED_Z?(-SPEED_Z):Turn_Speed);//
if((Left==0)&&(Right==0))Turn_Kd=-0.6;//ÈôÎÞ×óÓÒתÏòÖ¸ÁÔò¿ªÆôתÏòÔ¼Êø
else if((Left==1)||(Right==1))Turn_Kd=0;
Velocity_out=Velocity(Target_Speed,Encoder_Left,Encoder_Right);
Vertical_out=Vertical(Velocity_out+Med_Angle,Pitch,gyroy);
Turn_out=Turn(gyroz,Turn_Speed);
PWM_out=Vertical_out;
MOTO1=PWM_out-Turn_out;
MOTO2=PWM_out+Turn_out;
Limit(&MOTO1,&MOTO2);
Load(MOTO1,MOTO2);
Stop(&Med_Angle,&Pitch);
}
}
}
/*********************
直立环控制器PD
*********************/
int Vertical(float Med,float Angle,float gyro_Y)
{
int PWM_out;
PWM_out=Vertical_Kp*(Angle-Med)+Vertical_Kd*(gyro_Y-0);
return PWM_out;
}
/*********************
速度环控制器PI
*********************/
int Velocity(int Target,int encoder_left,int encoder_right)
{
static int Encoder_S,EnC_Err_Lowout_last,PWM_out,Encoder_Err,EnC_Err_Lowout;
float a=0.7;
Encoder_Err=((encoder_left+encoder_right)-Target);
EnC_Err_Lowout=(1-a)*Encoder_Err+a*EnC_Err_Lowout_last;
EnC_Err_Lowout_last=EnC_Err_Lowout;
Encoder_S+=EnC_Err_Lowout;
Encoder_S=Encoder_S>10000?10000:(Encoder_S<(-10000)?(-10000):Encoder_S);
if(stop==1)Encoder_S=0,stop=0;
PWM_out=Velocity_Kp*EnC_Err_Lowout+Velocity_Ki*Encoder_S;
return PWM_out;
}
/*********************
转向环控制器PD
*********************/
int Turn(int gyro_Z,int RC)
{
int PWM_out;
PWM_out=Turn_Kd*gyro_Z + Turn_Kp*RC;
return PWM_out;
}
u8 Fore,Back,Left,Right;
void USART3_IRQHandler(void)
{
int Bluetooth_data;
if(USART_GetITStatus(USART3,USART_IT_RXNE)!=RESET)//½ÓÊÕÖжϱê־λÀ¸ß
{
Bluetooth_data=USART_ReceiveData(USART3);//±£´æ½ÓÊÕµÄÊý¾Ý
if(Bluetooth_data==0x35)Fore=0,Back=0,Left=0,Right=0;//ɲ
else if(Bluetooth_data==0x31)Fore=1,Back=0,Left=0,Right=0;//ǰ
else if(Bluetooth_data==0x32)Fore=0,Back=1,Left=0,Right=0;//ºó
else if(Bluetooth_data==0x34)Fore=0,Back=0,Left=1,Right=0;//×ó
else if(Bluetooth_data==0x33)Fore=0,Back=0,Left=0,Right=1;//ÓÒ
else Fore=0,Back=0,Left=0,Right=0;//ɲ
}
}
2.编码器函数
编码器读取数据,采用定时器的编码器模式,进行速度读取,如下:
encoder.c
#include "encoder.h"
void Encoder_TIM2_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
TIM_TimeBaseInitTypeDef TIM_TimeBaseInitStruct;
TIM_ICInitTypeDef TIM_ICInitStruct;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA,ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2,ENABLE);
GPIO_InitStruct.GPIO_Mode=GPIO_Mode_IN_FLOATING;
GPIO_InitStruct.GPIO_Pin=GPIO_Pin_0 |GPIO_Pin_1;
GPIO_Init(GPIOA,&GPIO_InitStruct);
TIM_TimeBaseStructInit(&TIM_TimeBaseInitStruct);
TIM_TimeBaseInitStruct.TIM_ClockDivision=TIM_CKD_DIV1;
TIM_TimeBaseInitStruct.TIM_CounterMode=TIM_CounterMode_Up;
TIM_TimeBaseInitStruct.TIM_Period=65535;
TIM_TimeBaseInitStruct.TIM_Prescaler=0;
TIM_TimeBaseInit(TIM2,&TIM_TimeBaseInitStruct);
TIM_EncoderInterfaceConfig(TIM2,TIM_EncoderMode_TI12,TIM_ICPolarity_Rising,TIM_ICPolarity_Rising);
TIM_ICStructInit(&TIM_ICInitStruct);
TIM_ICInitStruct.TIM_ICFilter=10;
TIM_ICInit(TIM2,&TIM_ICInitStruct);
TIM_ITConfig(TIM2,TIM_IT_Update,ENABLE);
TIM_SetCounter(TIM2,0);
TIM_Cmd(TIM2,ENABLE);
}
void Encoder_TIM4_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
TIM_TimeBaseInitTypeDef TIM_TimeBaseInitStruct;
TIM_ICInitTypeDef TIM_ICInitStruct;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB,ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4,ENABLE);
GPIO_InitStruct.GPIO_Mode=GPIO_Mode_IN_FLOATING;
GPIO_InitStruct.GPIO_Pin=GPIO_Pin_6 |GPIO_Pin_7;
GPIO_Init(GPIOB,&GPIO_InitStruct);
TIM_TimeBaseStructInit(&TIM_TimeBaseInitStruct);
TIM_TimeBaseInitStruct.TIM_ClockDivision=TIM_CKD_DIV1;
TIM_TimeBaseInitStruct.TIM_CounterMode=TIM_CounterMode_Up;
TIM_TimeBaseInitStruct.TIM_Period=65535;
TIM_TimeBaseInitStruct.TIM_Prescaler=0;
TIM_TimeBaseInit(TIM4,&TIM_TimeBaseInitStruct);
TIM_EncoderInterfaceConfig(TIM4,TIM_EncoderMode_TI12,TIM_ICPolarity_Rising,TIM_ICPolarity_Rising);
TIM_ICStructInit(&TIM_ICInitStruct);
TIM_ICInitStruct.TIM_ICFilter=10;
TIM_ICInit(TIM4,&TIM_ICInitStruct);
TIM_ClearFlag(TIM4,TIM_FLAG_Update);
TIM_ITConfig(TIM4,TIM_IT_Update,ENABLE);
TIM_SetCounter(TIM4,0);
TIM_Cmd(TIM4,ENABLE);
}
/**********************
速度读取函数
形参:定时器
**********************/
int Read_Speed(int TIMx)
{
int value_1;
switch(TIMx)
{
case 2:value_1=(short)TIM_GetCounter(TIM2);TIM_SetCounter(TIM2,0);break;
case 4:value_1=(short)TIM_GetCounter(TIM4);TIM_SetCounter(TIM4,0);break;
default:value_1=0;
}
return value_1;
}
void TIM2_IRQHandler(void)
{
if(TIM_GetITStatus(TIM2,TIM_IT_Update)!=0)
{
TIM_ClearITPendingBit(TIM2,TIM_IT_Update);
}
}
void TIM4_IRQHandler(void)
{
if(TIM_GetITStatus(TIM4,TIM_IT_Update)!=0)
{
TIM_ClearITPendingBit(TIM4,TIM_IT_Update);
}
}
3.马达驱动函数
将PID计算的结果转换成PWM波,改变占空比来控制电机,包括限幅、赋值。
motor.c
#include "motor.h"
void Motor_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB,ENABLE);
GPIO_InitStruct.GPIO_Mode=GPIO_Mode_Out_PP;
GPIO_InitStruct.GPIO_Pin=GPIO_Pin_12 |GPIO_Pin_13 |GPIO_Pin_14 |GPIO_Pin_15;
GPIO_InitStruct.GPIO_Speed=GPIO_Speed_50MHz;
GPIO_Init(GPIOB,&GPIO_InitStruct);
}
void Limit(int *motoA,int *motoB)
{
if(*motoA>PWM_MAX)*motoA=PWM_MAX;
if(*motoA<PWM_MIN)*motoA=PWM_MIN;
if(*motoB>PWM_MAX)*motoB=PWM_MAX;
if(*motoB<PWM_MIN)*motoB=PWM_MIN;
}
int GFP_abs(int p)
{
int q;
q=p>0?p:(-p);
return q;
}
void Load(int moto1,int moto2)
{
if(moto1<0) Ain1=1,Ain2=0;
else Ain1=0,Ain2=1;
TIM_SetCompare1(TIM1,GFP_abs(moto1));
if(moto2<0) Bin1=1,Bin2=0;
else Bin1=0,Bin2=1;
TIM_SetCompare4(TIM1,GFP_abs(moto2));
}
char PWM_Zero=0,stop=0;
void Stop(float *Med_Jiaodu,float *Jiaodu)
{
if(GFP_abs(*Jiaodu-*Med_Jiaodu)>60)
{
Load(PWM_Zero,PWM_Zero);
stop=1;
}
}
4.主函数
初始化各个函数,以及这里由于在前面的原理图设计里,为了布线方便将JTAG调试引脚用作IO口输出,需要在主函数里将JTAG的调试功能关闭,仅使用SWD进行调试下载。
mian.c
#include "stm32f10x.h"
#include "sys.h"
float Pitch,Roll,Yaw;
short gyrox,gyroy,gyroz;
short aacx,aacy,aacz;
int Encoder_Left,Encoder_Right;
int PWM_MAX=7200,PWM_MIN=-7200;
int MOTO1,MOTO2;
extern int Vertical_out,Velocity_out,Turn_out;
int main(void)
{
delay_init();
NVIC_Config();
uart1_init(115200);
uart3_init(9600);
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable,ENABLE);
OLED_Init();
OLED_Clear();
MPU_Init();
mpu_dmp_init();
MPU6050_EXTI_Init();
Encoder_TIM2_Init();
Encoder_TIM4_Init();
Motor_Init();
PWM_Init_TIM1(0,7199);
while(1)
{
OLED_Float(0,0,Pitch,1);
OLED_ShowString(50,50,"NEFU_YSY");
}
}
(二)ESP8266
由于题主C++学的不好,对于arduino编程相对困难,因此在配置ESP8266芯片时,采用了图形化编程的方式,仅需要程序的执行逻辑即可进行配置。采用了北京师范大学开发的mixly开发环境进行开发,配置如下:
需要注意一点,这样配置完以后不能直接烧录到8266当中,因为他的默认代码当中有串口的默认输出字符串,我们需要先将图形化转换成代码,再将串口打印字符串的语句注释掉。保证我们的串口只输出十六进制的12345。
由此即可将8266接收到的巴法云数据,通过串口发送到STM32,实现了云端的控制。
微信小程序我们参考了巴法云论坛内的程序,这里附一下链接:(开源)微信小程序控制esp8266_esp826601s 巴法云-CSDN博客
其中ESP8266的接线规则是
VCC--------->3.3V
GND--------->GND
TXD--------->3.3V
RXD--------->3.3V
IO_0--------->运行模式(3.3V),下载模式(GND)
IO_2--------->3.3V
切换模式时要复位RST接地。
(三)ESP32-CAM
和ESP8266一样采用mixly编程,配置如下:
三,可以改进的地方
1.由于巴法云无法传输视频流,因此本次设计中的视频流是通过局域网传输的,如果连接本地的WIFI,需要对本地WIFI做内网穿透以后,才能用外网远程接收到视频流。
2.遥控的部分,WiFi可以用2.4G无线模块代替,本次设计是为了用云而用的云,主要是一个学习的目的。实际上用TCP\MQTT协议的云端传输不适合做本地遥控,延迟相对较高。
3.电机选型可以选择精度更高的电机,本次使用的电机,一方面本身精度不够高,另一方面在电机空转的时候,我用手去拧了几次,导致了电机死区过大,经过测试,我的电机在空负载时需要给到3V左右的电时才能慢慢转动,而由于我们PWM波给的速度信号是线性的,因此在输入电机的电压小于3V时电机不动,造成了平衡效果较差。
四,最终效果
final