03.实现BLDCDriver驱动输出PWM
小于 1 分钟
03.实现BLDCDriver驱动输出PWM
确切来说是实现了一个接口,需要外部提供三个函数
_initDriver
初始化驱动_enableDriver
启用/禁用驱动_setPhraseVoltage
设置三相电压- 因为这三个函数的具体实现都是和硬件相关的,
- 在不同硬件上(如stm32或arduino)会有不同的实现方式
具体实现
BLDCDriver.cpp
#include "BLDCDriver.hpp"
#include "Arduino.h"
BLDCDriver::BLDCDriver(void (*_initDriver)(),
void (*_enableDriver)(bool enable),
void (*_setPhraseVoltage)(int16_t u_a, int16_t u_b, int16_t u_c))
{
this->_initDriver = _initDriver;
this->_enableDriver = _enableDriver;
this->_setPhraseVoltage = _setPhraseVoltage;
}
void BLDCDriver::initDriver()
{
this->_initDriver();
}
void BLDCDriver::enableDriver(bool enable)
{
this->_enableDriver(enable);
}
/**
* 设置相电压
* @param u_a int16_t [-32768,32767] 表示 [-1,1] 精度:1/32768 = 0.0000305
*/
void BLDCDriver::setPhraseVoltage(int16_t u_a, int16_t u_b, int16_t u_c)
{
this->_setPhraseVoltage(u_a, u_b, u_c);
}
BLDCDriver.hpp
#ifndef __BLDCDriver_H__
#define __BLDCDriver_H__
#include <stdint.h>
class BLDCDriver
{
private:
void (*_initDriver)();
void (*_enableDriver)(bool enable);
void (*_setPhraseVoltage)(int16_t u_a, int16_t u_b, int16_t u_c);
public:
BLDCDriver(
void (*_initDriver)(),
void (*_enableDriver)(bool enable),
void (*_setPhraseVoltage)(int16_t u_a, int16_t u_b, int16_t u_c));
void initDriver();
void enableDriver(bool enable);
void setPhraseVoltage(int16_t u_a, int16_t u_b, int16_t u_c);
};
#endif
BLDCMotor.cpp
#include "HardwareSerial.h"
#include "BLDCMotor.hpp"
#include "Arduino.h"
BLDCMotor::BLDCMotor()
{
}
void BLDCMotor::connectDriver(BLDCDriver *driver)
{
this->driver = driver;
}
void BLDCMotor::initFOC()
{
if (this->driver)
{
this->driver->initDriver();
this->driver->enableDriver(true);
this->driver->setPhraseVoltage(0, 0, 0);
}
}
/**
* 设置相电压
* @param u_d int16_t [-32768,32767] 表示 [-1,1] 精度:1/32768 = 0.0000305
* @param u_q int16_t [-32768,32767] 表示 [-1,1]
* @param e_angle uint16_t [0,65535] 表示 [0,2PI] 精度:360°/65535 = 0.00549°
*/
void BLDCMotor::setPhraseVoltage(int16_t u_d, int16_t u_q, uint16_t e_angle)
{
int16_t sin, cos;
// 计算三角函数
_sincos(e_angle, &sin, &cos);
// 帕克逆变换
int16_t u_alpha = ((cos * (int32_t)u_d) + (-sin * (int32_t)u_q)) / _INT16_ONE_;
int16_t u_beta = ((sin * (int32_t)u_d) + (cos * (int32_t)u_q)) / _INT16_ONE_;
// 克拉克逆变换(等幅值形式)
int16_t u_a = u_alpha;
int16_t u_b = (-u_alpha + _INT16_SQRT3_ * u_beta / _INT16_ONE_) / 2;
int16_t u_c = -(u_a + u_b);
// 设置相电压
driver->setPhraseVoltage(u_a, u_b, u_c);
}
实现效果
03.bldc_driver_output_pwm
#include <Arduino.h>
#include "BLDCMotor.hpp"
#include "foc_utils.h"
#include "typedef.h"
BLDCMotor motor = BLDCMotor();
BLDCDriver driver = BLDCDriver(
#define M1_En 8
#define M1_Ua 5
#define M1_Ub 9
#define M1_Uc 6
// init driver
[]()
{
pinMode(M1_En, OUTPUT); // enable
pinMode(M1_Ua, OUTPUT); // a
pinMode(M1_Ub, OUTPUT); // b
pinMode(M1_Uc, OUTPUT); // c
},
// enable or disable driver
[](bool enable)
{
digitalWrite(M1_En, enable ? HIGH : LOW); // enable
},
// set pwm to driver
[](int16_t u_a, int16_t u_b, int16_t u_c)
{
// [-32768,32767] => [0,255]
Serial.print((u_a + _INT16_N_ONE_) / 255);
Serial.print(',');
Serial.print((u_b + _INT16_N_ONE_) / 255);
Serial.print(',');
Serial.print((u_c + _INT16_N_ONE_) / 255);
Serial.print('\n');
// [-32768,32767] => [0,255]
// 大多数引脚上的 PWM 信号频率约为490 Hz
// 设置占空比
analogWrite(M1_Ua, (u_a + _INT16_N_ONE_) / 255);
analogWrite(M1_Ub, (u_b + _INT16_N_ONE_) / 255);
analogWrite(M1_Uc, (u_c + _INT16_N_ONE_) / 255);
});
void setup()
{
Serial.begin(9600);
motor.connectDriver(&driver);
motor.initFOC();
}
uint64_t t1_us, t2_us = micros(), dt_us;
uint64_t dt()
{
// 微妙us 70分钟溢出一次
t1_us = micros();
dt_us = t2_us - t1_us;
t2_us = t1_us;
// 大于1s 返回 0.1ms
return dt_us > 1000000 ? 100 : dt_us;
}
float angle = 0;
void loop()
{
angle += 1000;
motor.setPhraseVoltage(0, _INT16_ONE_, angle);
}