DRV8302——用于Arduino UNO的高性能无刷电机驱动器
DRV8302 是一款高性能的无刷电机驱动板,能够支持持续放电电流15A,瞬间峰值电流27A。此外,它具有温度和过流保护,反电势和三相电流检测。它还可以使用3 相 PWM 信号驱动,这使得它于 SimpleFOC 库兼容。
注意📢
截止到现在(版本1.4.1 ),本库没有补充用于8302的电流环。电机力矩目前是直接由电压控制的。更多信息
以下是本例程所需硬件:
以下是 Arduino UNO 的接线示意图:
DRV8302
- 像其他基于本库的无刷电机驱动板一样,此驱动板能接收3路PWM信号: 分别是 pwm
a
、b
和c
。这三路信号可以在INHA
、INHB
和INHC
三个引脚引入 - 此外,连接使能引脚至引脚
EN-GATE
- 配置无刷电机驱动板我们需要到三个引脚(图中左边紫部分色)
M_PWM
:高电平为3PWM模式,低电平为6PWM模式M_OC
: 设置低电平使能过流保护OC_ADJ
:可以通过模拟输入信号来调节过流保护的限幅值,如果你不需要此功能,可以将这个引脚拉成高电平
- 可以从以下两个引脚读取错误信息
nFAULT
:驱动板故障状态时为高电平nOCTW
:达到过流限制时为高电平
编码器
- 通道
A
和B
连接到外部中断引脚2
和3
- 如果你的编码器有
index
信号,可以连接到任何可用的支持数字信号传输的引脚。这儿我们将其连接到引脚4
电机
- 电机
a
相、b
相和c
相直接连接到驱动板端子OUTA
、OUTB
和OUTC
。
连接示例
Arudino 3PWM 代码
运行3路PWM输出的 DRV8302 板的代码与其他低功耗无刷直流电机驱动器的代码几乎完全相同。唯一的区别是 DRV8302 配置的过程。
因此,让我们首先从定义驱动板所使用的引脚开始:
// DRV8302 引脚定义
// 勿忘共地
#define INH_A 9
#define INH_B 10
#define INH_C 11
#define EN_GATE 8
#define M_PWM 6
#define M_OC 5
#define OC_ADJ 7
变量 INH_A
、 INH_B
、 INH_C
和 EN_GATE
直接用于 BLDCDriver3PWM
类:
// 驱动实例
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
另外的一些和基础配置不同是你需要增加以下代码在 setup() 函数中
// 用于DRV8302 的特定代码
// M_OC - 使能过流保护
pinMode(M_OC,OUTPUT);
digitalWrite(M_OC,LOW);
// M_PWM - 使能 3PWM 模式
pinMode(M_PWM,OUTPUT);
digitalWrite(M_PWM,HIGH);
// OD_ADJ - 设定最大允许电流值
// 最好用电压因数计算准确的值
pinMode(OC_ADJ,OUTPUT);
digitalWrite(OC_ADJ,HIGH);
其他部分都是常规运行无刷直流电机的 SimpleFOClibrary 代码。
完整例程代码为:
#include <SimpleFOC.h>
// DRV8302 引脚定义
// 勿忘共地
#define INH_A 9
#define INH_B 10
#define INH_C 11
#define EN_GATE 8
#define M_PWM 6
#define M_OC 5
#define OC_ADJ 7
// 电机极对数设置
BLDCMotor motor = BLDCMotor(11);
// 驱动实例
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
// 编码器实例
Encoder encoder = Encoder(2, 3, 8192);
// 通道A和B的回调函数
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
// 设定控制指令
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }
void setup() {
// 初始化编码器
encoder.init();
encoder.enableInterrupts(doA, doB);
// 连接编码器和电机
motor.linkSensor(&encoder);
// 用于DRV8302 的特定代码
// M_OC - 使能过流保护
pinMode(M_OC,OUTPUT);
digitalWrite(M_OC,LOW);
// M_PWM - 使能 3PWM 模式
pinMode(M_PWM,OUTPUT);
digitalWrite(M_PWM,HIGH);
// OD_ADJ - 设定最大允许电流值
// 最好用电压因数计算准确的值
pinMode(OC_ADJ,OUTPUT);
digitalWrite(OC_ADJ,HIGH);
// 配置驱动器
driver.voltage_power_supply = 12;
driver.init();
motor.linkDriver(&driver);
// 选择FOC调制方式
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// 设定控制类型:力矩
motor.controller = MotionControlType::torque;
// 设定速度PI
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 20;
// 设定速度低通滤波器时间常数
motor.LPF_velocity.Tf = 0.01;
// 角度环P
motor.P_angle.P = 20;
// 角度环速度限制
motor.velocity_limit = 50;
// 默认供电电压
motor.voltage_limit = 12;
// 通过串口在线监测电机状态
// 在线检测用串口
Serial.begin(115200);
// 如果不需要,可以注释掉
motor.useMonitoring(Serial);
// 初始化电机
motor.init();
// 校准编码器并且启动FOC算法
motor.initFOC();
// 设定初始目标值
motor.target = 2;
// 设定电机ID值
command.add('M', onMotor, "motor");
_delay(1000);
}
void loop() {
// 循环以设定FOC各相电压
motor.loopFOC();
// 用于设定外环 目标值
// 速度,位置和电压
// 如果没有设定具体参数可以用motor.target在循环外设置目标值
motor.move();
// 用户在线检测通讯
command.run();
}
Arudino 6路PWM 代码
6路PWM输出情况下用 DRV8302 板,我们需要注意根据我们使用的微型控制板,正确的配置引脚。
下列为用于 Arduino uno 的引脚配置示例:
// DRV8302 引脚定义
// 勿忘共地
#define INH_A 5
#define INH_B 9
#define INH_C 11
#define INL_A 6
#define INL_B 10
#define INL_C 3
#define EN_GATE 8
#define M_PWM 6
#define M_OC 5
#define OC_ADJ 7
上述引脚不适用于 stm32 Nucleo 驱动板。下列是针对该驱动板的引脚:
// DRV8302 引脚定义
// 勿忘共地
#define INH_A 7
#define INH_B 6
#define INH_C 5
#define INL_A 2
#define INL_B 3
#define INL_C 4
#define EN_GATE 8
#define M_PWM 9
#define M_OC 10
#define OC_ADJ 11
变量 INH_A
、 INH_B
、 INH_C
、INL_A
、 INL_B
、 INHL_C
和 EN_GATE
直接用于 BLDCDriver6PWM
的类:
// 驱动实例
BLDCDriver6PWM driver = BLDCDriver6PWM(INH_A, INL_A, INH_B,INL_B, INH_C, INL_C, EN_GATE);
另外的一些和基础配置不同是你需要增加以下代码在 setup() 函数中:
// 用于DRV8302 的特定代码
// M_OC - 使能过流保护
pinMode(M_OC,OUTPUT);
digitalWrite(M_OC,LOW);
// M_PWM - 使能 6PWM 模式
pinMode(M_PWM,OUTPUT);
digitalWrite(M_PWM,LOW);
// OD_ADJ - 设定最大允许电流值
// 最好用电压因数计算准确的值
pinMode(OC_ADJ,OUTPUT);
digitalWrite(OC_ADJ,HIGH);
其他部分都是常规运行无刷直流电机的 SimpleFOC库 代码。
这是本例程的完整代码:
#include <SimpleFOC.h>
// DRV8302 引脚定义
// 勿忘共地
#define INH_A 5
#define INH_B 9
#define INH_C 11
#define INL_A 6
#define INL_B 10
#define INL_C 3
#define EN_GATE 8
#define M_PWM 6
#define M_OC 5
#define OC_ADJ 7
// 电机极对数设置
BLDCMotor motor = BLDCMotor(11);
// 驱动实例
BLDCDriver6PWM driver = BLDCDriver6PWM(INH_A, INL_A, INH_B,INL_B, INH_C, INL_C, EN_GATE);
// 编码器实例
Encoder encoder = Encoder(2, 3, 8192);
// 通道A和B的回调函数
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
// 设定控制指令
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }
void setup() {
// 初始化编码器
encoder.init();
encoder.enableInterrupts(doA, doB);
// 连接编码器和电机
motor.linkSensor(&encoder);
// 用于DRV8302 的特定代码
// M_OC - 使能过流保护
pinMode(M_OC,OUTPUT);
digitalWrite(M_OC,LOW);
// M_PWM - 使能 6PWM 模式
pinMode(M_PWM,OUTPUT);
digitalWrite(M_PWM,LOW);
// OD_ADJ - 设定最大允许电流值
// 最好用电压因数计算准确的值
pinMode(OC_ADJ,OUTPUT);
digitalWrite(OC_ADJ,HIGH);
// 配置驱动器
driver.voltage_power_supply = 12;
driver.init();
motor.linkDriver(&driver);
// 选择FOC调制方式
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// 设定控制类型:力矩
motor.controller = MotionControlType::torque;
// 设定速度PI
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 20;
// 设定速度低通滤波器时间常数
motor.LPF_velocity.Tf = 0.01;
// 角度环P
motor.P_angle.P = 20;
// 角度环速度限制
motor.velocity_limit = 50;
// 默认供电电压
motor.voltage_limit = 12;
// 通过串口在线监测电机状态
// 在线检测用串口
Serial.begin(115200);
// 如果不需要,可以注释掉
motor.useMonitoring(Serial);
// 初始化电机
motor.init();
// 校准编码器并且启动FOC算法
motor.initFOC();
// 设定初始目标值
motor.target = 2;
// 设定电机ID值
command.add('M', onMotor, "motor");
_delay(1000);
}
void loop() {
// 循环以设定FOC各相电压
motor.loopFOC();
// 用于设定外环 目标值
// 速度,位置和电压
// 如果没有设定具体参数可以用motor.target在循环外设置目标值
motor.move();
// 用户在线检测通讯
command.run();
}