详细方案四:pwm与720电机控制
电机硬件分析
什么是电机?
电机(俗称"马达")是指依据电磁感应定律实现电能转换或传递的一种电磁装置。它的主要作用是产生驱动转矩,作为用电器或各种机械的动力源。其中本四轴采用的电机是直流电机。直流电动机是将直流电能转换为机械能的电动机。因其良好的调速性能而在电力拖动中得到广泛应用。
那么是不是直接在电机两端加上电压就可以了?
直接在直流电机加上电压,确实能够使得电机转动而且转速完全能够满足四轴飞行的动力,但是这样的四轴没法控制电机的转速,加电后四轴只会朝天上飞而且没法控制。最后有可能炸机。
那怎么控制电机的转速?
直流电动机是将直流电能转换为机械能的电动机,也就是说只要控制住电流的话,就可以控制电机的转速了。那问题就变成了如何控制电流了。
电流怎样控制电机的转速?
我们想想,有电流电机就转,没电流电机就不转。那如果、10ms内,如果6ms电机有电流,4ms没电流。电机是前6ms转,后4ms不转?实际上是10ms电机都在转。前6ms电机有电流电机转,后4ms虽然没有电流但是由于惯性的作用电机依旧在转,只不过转速在不断的减少。如果将将10ms的周期不断的循环,不断认为地控制电流的导通的时间是不是就可以控制电机的转速了。其中这周期不能太大一般为ms或者ns级别的。
那么问题又来到了怎么控制电流上了
根据欧姆定律,在电阻不变的情况下,电压与电流成正比。高电平就是有电流流经电机,低电平就是电路断开没有电流流经电机。这个让电流能否流进电机就好像一个门阀且该门阀的开关的速度要达到ms和ns级别,那这门阀无疑MOS管是最佳人选。外加电压在MOS管在栅源极上如果大于MOS的开启电压MOS管内部就会导通,如果外加栅源极小于MOS的开启电压MOS管处于截止区,也就是该电路断开
最后的难题是电压
有什么电压能够在周期内输入稳定的高低电平到MOS管的栅源极?那就属PWM波最好了。
PWM波即是通过单片机在一个周期内,让单片机的IO口输出一段时间的高电平,一段时间的低电平。如上图所示为为一个方波的周期,其占空比为t/T。其调节高低电平过程如下图
本四轴电机采用的是720空心杯电机。电机的驱动原理是通过STM32芯片IO口输出PWM波(调节高电平的占空比)然后经过NMOS管来驱动电机的转速其电路图如下:
电路分析:
单片机IO口输出PWM波给电路,后经过R8和R10分压(防止电压直接加载到NMOS导致击穿同时也保证了栅源电压大于开启电压)
如果此时的PWM波电压处于高电平那么NMOS管导通,此时电池提供的电压和电流经过电机接地。如果此时PWM波电压处于低电平NMOS管就会截止,电路断开没法接地电机转动的速度逐渐减少,只有等到下一个高电平来临的时候电机的转速才会提升。
电路中的电容的作用是去耦的作用,由于电机在转动的时候会产生磁场导致电机的电压上下波动,该电压有滤波的左右
此外在电机一旁并联二极管是因为电机在减速产生了电磁感应会有微弱的电流,防止它内流。二极管有分流消耗的作用。
软件分析
本四轴采用的是STM32F411单片机芯片。本次采用的是PWM1模式使用的时钟是TIM3
单片机该如何产生PWM波?
- 如上图所示,假设单片机某IO口是锯齿波。其中ARR是单片机计数器的上限。单片机首 先开启TIM3定时器从0计数到ARR后又从0重新开始计数到ARR不断的循环重复。
- 在0到ARR的计数期间单片机内部存在一个CCRX的输入捕获比较器,里面装载着参考电压。用来比较锯齿波的电压是否大于参考电压。如果大于那么IO口输出高电平,低于参考电压则输出低电平。
- 其中占空比就是高电平时间占据整个定时周期的时间,也就是
- 所以要调节占空比直接调节CCRX的值就可以了。
单片机产生PWM波的工作过程
- 如上图所示,就是单片机产生pwm波的模式一,其中OCIM是控制pwm模式几的。
- OCIM被配置为模式一计数模式是向上计数的时候,一旦TIMx CNT < CCR1时通道1为有效电平否则是无效电平。如果是向下计数模式的时候则是相反。
- 输出的OC1ref有效电平到达CCIP寄存器前,则通过设计是否为1/0如果为1则说明有OC1ref输出是高电平有效,反之为低电平。
- 最有CO1E是IO口中断输出使能,为1时信号能够输出,为0则禁止输出
上述的PWM波产生过程图的输入的CNT与CCR1的比较究竟是怎么回事?
- CCR1其实是CCRx寄存器中的一个值,如上图所示如果CCRx等于4且为向上计数时。0-3的为有效电平,若OCREF为1则为高电平有效,剩下的低电平有效,CCxIF则相反。
- 此外单片机的IO口输出为PWM输出功能,并非普通IO口所以在配置的时候要设置为复用的IO口输出,期间还有到了TIM1定时器,所以还要将TIM3的定时器功能映射到IO口上。
编程前的准备
编程需要的步骤
①四个电机定义
②电机最大最小速度定义
③使能定时器和IO口时钟
④初始化IO口为复用功能输出和GPIO复用映射到TIM3
⑤初始化定时器和输出比较参数
⑥使能定时器
编程代码
#include "stm32f4xx.h"
#include "motor.h"
#define Moto_PwmMax 1000
int16_t MOTO1_PWM = 0;
int16_t MOTO2_PWM = 0;
int16_t MOTO3_PWM = 0;
int16_t MOTO4_PWM = 0;
/******************************************************************************************
*函 数:void TIM3_GpioConfig(void)
*功 能:TIM3 PWM输出通道GPIO设置
*参 数:无
*返回值:无
*备 注:TIM3 CH1(PWM1) -> PA6
* TIM3 CH2(PWM2) -> PA7
* TIM3 CH3(PWM3) -> PB0
* TIM3 CH4(PWM4) -> PB1
*******************************************************************************************/
void TIM3_GpioConfig(void){
GPIO_InitTypeDef GPIO_InitStructure;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); //TIM3 时钟使能
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA|RCC_AHB1Periph_GPIOB, ENABLE); //GPIOA GPIOB 时钟使能
//GPIOB 配置: TIM3 CH1 (PA6), TIM3 CH2 (PA7), TIM3 CH3 (PB0) and TIM3 CH4 (PB2)
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; //复用模式
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz; //速度100M
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; //推完输出
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; //上拉输入
//PA6 PA7 初始化
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 ;
GPIO_Init(GPIOA, &GPIO_InitStructure);
//PB0 PB1 初始化
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 ;
GPIO_Init(GPIOB, &GPIO_InitStructure);
//连接 TIM3 的通道到 AF2
GPIO_PinAFConfig(GPIOA, GPIO_PinSource6, GPIO_AF_TIM3);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource7, GPIO_AF_TIM3);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource0, GPIO_AF_TIM3);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource1, GPIO_AF_TIM3);
}
/******************************************************************************************
*函 数:void MOTOR_Init(void)
*功 能:输出PWM初始化
*参 数:无
*返回值:无
*备 注:TIMx_ARR 决定方波的周期
* TIMx_CCRx 决定方波的占空比
*******************************************************************************************/
void MOTOR_Init(void){
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
TIM3_GpioConfig();
//更新中断时间 Tout = (ARR-1)*(PSC-1)/CK_INT
//TIM2~TIM5时钟来源于APB1*2
TIM_TimeBaseStructure.TIM_Period = 1000-1; //自动重装载值
TIM_TimeBaseStructure.TIM_Prescaler = 100-1; //预分频值
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
//PWM1 模式配置 通道1
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_Pulse = 0;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
TIM_OC1Init(TIM3, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable); //电机1
TIM_OC2Init(TIM3, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(TIM3, TIM_OCPreload_Enable); //电机2
TIM_OC3Init(TIM3, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(TIM3, TIM_OCPreload_Enable); //电机3
TIM_OC4Init(TIM3, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(TIM3, TIM_OCPreload_Enable); //电机4
//ARR 寄存器预装载
TIM_ARRPreloadConfig(TIM3, ENABLE);
//TIM_PrescalerConfig(TIM3, PrescalerValue, TIM_PSCReloadMode_Immediate);
TIM_Cmd(TIM3,ENABLE); //使能TIM3
}
/*****************************************************************************
*函 数:void Moto_Pwm(int16_t MOTO1_PWM,int16_t MOTO2_PWM,int16_t MOTO3_PWM,int16_t MOTO4_PWM)
*功 能:电机要输出数值转换成PWM波形输出
*参 数:MOTO1_PWM 电机1
* MOTO2_PWM 电机2
* MOTO3_PWM 电机3
* MOTO3_PWM 电机4
*返回值:无
*备 注:无
*****************************************************************************/
void Moto_Pwm(int16_t MOTO1_PWM,int16_t MOTO2_PWM,int16_t MOTO3_PWM,int16_t MOTO4_PWM){
if(MOTO1_PWM>Moto_PwmMax) MOTO1_PWM = Moto_PwmMax;
if(MOTO2_PWM>Moto_PwmMax) MOTO2_PWM = Moto_PwmMax;
if(MOTO3_PWM>Moto_PwmMax) MOTO3_PWM = Moto_PwmMax;
if(MOTO4_PWM>Moto_PwmMax) MOTO4_PWM = Moto_PwmMax;
if(MOTO1_PWM<0) MOTO1_PWM = 0;
if(MOTO2_PWM<0) MOTO2_PWM = 0;
if(MOTO3_PWM<0) MOTO3_PWM = 0;
if(MOTO4_PWM<0) MOTO4_PWM = 0;
TIM3->CCR1 = MOTO1_PWM;
TIM3->CCR2 = MOTO2_PWM;
TIM3->CCR3 = MOTO3_PWM;
TIM3->CCR4 = MOTO4_PWM;
}