【花雕学编程】Arduino动手做(222)---Simple FOC Shield V2.0.4 无刷电机驱动板

37款传感器与执行器的提法,在网络上广泛流传,其实Arduino能够兼容的传感器模块肯定是不止这37种的。鉴于本人手头积累了一些传感器和执行器模块,依照实践出真知(一定要动手做)的理念,以学习和交流为目的,这里准备逐一动手尝试系列实验,不管成功(程序走通)与否,都会记录下来—小小的进步或是搞不掂的问题,希望能够抛砖引玉。

【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)

 

 

 

 

 

一、 概述

艾尔赛Arduino FOC无刷电机驱动板采用3个分立的高低边栅极驱动器和6NMOS管组成1BLDC驱动电路兼容国外开源项目Simple FOC Shield V2.0.4,可直接插入到Arduino NNO开发板作为一个Shiled来使用,并支持多种传感器接口,用户可以使用Arduino环境下的Simple FOC库来控制BLDC无刷电机平稳高精度运行

 

二、 功能特点   

1采用3IR2104栅极驱动器和6NMOS组成BLDC驱动部分,控制逻辑兼容官方原版Simple FOCL6234PD方案

2接口兼容Arduino UNOArduino MEGASTM32 Nucleo

3板载2INA240高精度电流传感器用于测量A B相电流

4用户可以通过0R电阻跳线的方式来配置GPIO控制管脚

5支持霍尔、磁传感器等多种编码器

6供电电压DC12-35V

7,板载电源指示灯。

 

三、 硬件介绍和说明

1,板子尺寸:67.8*53mm

   重量:26g

 

 

2, 接口介绍

 

 

 

1VCCGNDDC12-35V供电;

2A, B, C无刷电机接口;

3GPIO引出口,可直接插入到Arduino UNO等开发板

4IR2104供电跳线帽:因为IR2104最大只支持20V供电,故当VCC小于等于20V时此跳线帽插在左端,此时IR2104的电源电压等于VCC;当VCC20V时此跳线帽插在右端,此时IR2104的电源电压等于16V

 

 

板子背面为GPIO控制/供电 选择跳线电阻,具体的跳线方法可参考电路原理图(一般保持默认即可)

 

电原理图

 

 插入Arduino uno开发板

 

四、Arduino开发环境搭建
1、安装Arduino IDE 1.8.9或者最新的版本;

2、点击菜单栏的 工具--管理库--开发板管理器,再搜索“Simple FOC”安装2.1.0或者更新版本(备注:安装最新版本可能导致后续的电流检测程序编译通不过);

 

 

 

 

 

更多资料:
Arduino简单磁场定向控制(FOC)项目
https://docs.simplefoc.com/

 

五、基本功能测试

1、硬件准备:Arduino UNO开发板、Arduino FOC驱动板、MKS YT2804无刷电机(DC12V@7极对@带AS5600磁编码器)、DC12V直流电源、USB方口线。

2、接线方法
● 无刷电机:接到驱动板的A B C三个口上
● AS5600编码器:5V和GND接驱动板的5V和GND,SCL和SDA分别接驱动板的SCL和SDA
● Arduino开发板USB口:通过方口USB线连接至电脑USB口
● 驱动板VCC GND供电口:接DC12V电源

 

六、开环速度测试
● 打开Arduino IDE,依次点击:文件--示例-- Simple FOC--motion_control --open_loop_motor_control --open_loop_velocity_example

 

 

● 根据所用电机修改参数:
BLDCMotor motor = BLDCMotor(11) 修改为 BLDCMotor motor = BLDCMotor(7)

motor.voltage_limit = 3 修改为 motor.voltage_limit = 1

 

 

 

【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
项目程序之一:开环速度测试
开源参考程序

 

/*
【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
  实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
  项目程序之一:开环速度测试
*/

// 开环电机控制示例
#include <SimpleFOC.h>


// BLDC 电机及驱动器实例
// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(7);
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);

// 步进电机及驱动器实例
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6,  8);


//目标变量
float target_velocity = 0;

// 创建实例化对象
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }


void setup() {

  // 驱动配置
  // 电源电压[V]
  driver.voltage_power_supply = 12;
  driver.init();
  // 连接电机和驱动器
  motor.linkDriver(&driver);

  // 限制运动
  motor.voltage_limit = 1;   // [V]
  motor.velocity_limit = 5; // [弧度/秒] 约 50rpm
 
  // 开环控制配置
  motor.controller = MotionControlType::velocity_openloop;

  // 初始化电机硬件
  motor.init();

  //添加目标命令 T
  command.add('T', doTarget, "target velocity");

  Serial.begin(115200);
  Serial.println("电机就绪!");
  Serial.println("设定目标速度 [rad/s]");
  _delay(1000);
}

void loop() {

  // 开环运动速度
  // using motor.voltage_limit and motor.velocity_limit
  motor.move(target_velocity);

  // user communication 用户沟通
  command.run();
}

  

实验串口返回情况

 

 

打开“串口监视器”,等待串口输出 “电机就绪!” 信息后输入电机速度值(比如:T10),点击“发送”,电机会以设定的速度转动。比如再输入T30,电机转动速度会加快。

 

 

七、测试AS5600编码器

● 打开Arduino IDE,依次点击:文件--示例--Simple FOC --utils--sensor_test -- magnetic_sensors --magnetic_sensor_i2c_example

 

【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
 实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
 项目程序之二:测试AS5600编码器

实验开源代码

 

/*
【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
  实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
  项目程序之二:测试AS5600编码器
*/

#include <SimpleFOC.h>

// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb)
//  chip_address  I2C chip address
//  bit_resolution  resolution of the sensor
//  angle_register_msb  angle read register msb
//  bits_used_msb  number of used bits in msb register
// 
// make sure to read the chip address and the chip angle register msb value from the datasheet
// also in most cases you will need external pull-ups on SDA and SCL lines!!!!!
//
// For AS5058B
// MagneticSensorI2C sensor = MagneticSensorI2C(0x40, 14, 0xFE, 8);

// AS5600 配置示例
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);


void setup() {
  // 监控端口
  Serial.begin(115200);

  // 配置 i2C
  Wire.setClock(400000);
  // 初始化磁传感器硬件
  sensor.init();

  Serial.println("传感器就绪!");
  _delay(1000);
}

void loop() {
  // iterative function updating the sensor internal variables
  // it is usually called in motor.loopFOC()
  // this function reads the sensor hardware and 
  // has to be called before getAngle nad getVelocity
  sensor.update();
  
  // 将角度和角速度显示到终端
  Serial.print(sensor.getAngle());
  Serial.print("\t");
  Serial.println(sensor.getVelocity());
  _delay(1000);
}

  

实验场景图

 

 

点击“上传”,打开串口监视器,可以监测电机的位置和转速

用手转动电机,可以发现电机位置与转速发生改变
关于位置:正转一圈约数值增加6.28(2π),反转一圈数值减少6.28(2π),如下图:

 

实验记录视频(30秒)

{花雕动手做}Arduino FOC 无刷电机的开环速度测试

https://www.bilibili.com/video/BV1cH4y1A77x/?vd_source=98c6b1fc23b2787403d97f8d3cc0b7e5

 

 

八、INA240电流传感器测试
● 使用Arduino IDE打开资料里面的电流测试程序 ,“angle_control_current_sense_test”,点击“上传”。

位置/角度运动控制示例
*步骤:
*1)配置电机和磁传感器
*2)运行代码
*3)从串行终端设置目标角度(弧度)

运行程序,电机会来回转动,打开串口监视器,可以监测电机的A相、B相的电流以及电流幅值。用手转动电机,电流值会发生改变。


【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
项目程序之三:INA240电流传感器测试,位置/角度运动控制

实验开源代码

 

/*
  【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
  实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
  项目程序之三:INA240电流传感器测试,位置/角度运动控制
*/

#include <SimpleFOC.h>

// magnetic sensor instance - SPI
//MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
// magnetic sensor instance - MagneticSensorI2C
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
// magnetic sensor instance - analog output
//MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);

//无刷直流电机和驱动器实例
BLDCMotor motor = BLDCMotor(7);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6,  8);

// 电流传感器
// shunt resistor value
// gain value
// 引脚相位A、B(C可选)
InlineCurrentSense current_sense = InlineCurrentSense(0.01, 50.0, A0, _NC, A2);




// 角度设定点变量
float target_angle = 0;
// instantiate the commander
//Commander command = Commander(Serial);
//void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }

void setup() {
  // 初始化电流感应
  current_sense.init();

  // for SimpleFOCShield v2.01/v2.0.2
  current_sense.gain_b *= -1;

  // 初始化磁传感器硬件
  sensor.init();
  // 将电机连接到传感器
  motor.linkSensor(&sensor);

  // 驱动程序配置
  // power supply voltage [V]
  driver.voltage_power_supply = 24;
  driver.init();
  //连接电机和驱动器
  motor.linkDriver(&driver);

  // 选择FOC调制(可选)
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  // 设置要使用的运动控制回路
  motor.controller = MotionControlType::angle;

  // 控制器配置
  // default parameters in defaults.h

  // 速度PI控制器参数
  motor.PID_velocity.P = 0.2;
  motor.PID_velocity.I = 2;
  motor.PID_velocity.D = 0;
  //设置给电机的最大电压
  motor.voltage_limit = 1;

  //速度低通滤波时间常数
  //越低过滤越少
  motor.LPF_velocity.Tf = 0.01;

  // 角度P控制器
  motor.P_angle.P = 5;
  //位置控制的最大速度
  motor.velocity_limit = 20;

  // 使用串行监控
  Serial.begin(115200);
  // comment out if not needed
  //motor.useMonitoring(Serial);


  // 初始化电机
  motor.init();
  // 对齐传感器并启动FOC
  motor.initFOC();

  // 添加目标命令T
  //command.add('T', doTarget, "target angle");

  Serial.println(F("电机准备就绪!"));
  Serial.println(F("使用串行终端设置目标角度:"));
  Serial.println("电流感应就绪!");
  _delay(1000);
}


void loop() {

  // 主要FOC算法功能
  // the faster you run this function the better
  // Arduino UNO loop  ~1kHz
  // Bluepill loop ~10kHz

  motor.loopFOC();

  // 运动控制功能
  // 速度、位置或电压(在电机控制器中定义)
  // this function can be run at much lower frequency than loopFOC() function
  // You can also use motor.move() and set the motor.target in the code
  motor.move(target_angle);


  // function intended to be used with serial plotter to monitor motor variables
  // significantly slowing the execution down!!!!
  // motor.monitor();

  // user communication
  // command.run();

  PhaseCurrent_s currents = current_sense.getPhaseCurrents();
  float current_magnitude = current_sense.getDCCurrent();

  Serial.print(currents.a * 1000); // milli Amps
  Serial.print("\t");
  Serial.print(currents.b * 1000); // milli Amps
  Serial.print("\t");
  Serial.print(currents.c * 1000); // milli Amps
  Serial.print("\t");
  Serial.println(current_magnitude * 1000); // milli Amps
  _delay(1000);
}

  

实验串口返回情况
串口输出截图

 

【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
项目程序之四:角度控制电流感应测试(内联电流感应类)

实验开源代码

/*
  【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
  实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
  项目程序之四:角度控制电流感应测试(内联电流感应类)
*/

#include <SimpleFOC.h>

// current sensor
// shunt resistor value
// gain value
// pins phase A,B, (C optional)
InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2);


void setup() {
  // initialise the current sensing
  current_sense.init();

  // for SimpleFOCShield v2.01/v2.0.2
  current_sense.gain_b *= -1;

  Serial.begin(115200);
  Serial.println("Current sense ready.");
}

void loop() {

  PhaseCurrent_s currents = current_sense.getPhaseCurrents();
  float current_magnitude = current_sense.getDCCurrent();

  Serial.print(currents.a * 1000); // milli Amps
  Serial.print("\t");
  Serial.print(currents.b * 1000); // milli Amps
  Serial.print("\t");
  Serial.print(currents.c * 1000); // milli Amps
  Serial.print("\t");
  Serial.println(current_magnitude * 1000); // milli Amps
  _delay(1000);
}

  

实验串口返回情况
串口输出截图

 

 九、测试开环位置控制

 

实验注意:12V先不要上电,开环控制电机会发热,上电时间过久容易烧坏。最好等到程序编译上传后再上电,上电尽快操作。开环控制的目的主要是建立对电机控制的初步认识,以及验证电机和驱动板功能是否正常,不要停留太久!

 

【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)

  实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)

  项目程序之四:测试开环位置控制

  实验开源代码

 

 

/*
  【Arduino】168种传感器模块系列实验(资料代码+仿真编程+图形编程)
  实验二百二十二:Arduino FOC无刷电机驱动板 兼容Simple FOC Shield V2.0.4(艾尔赛)
  项目程序之四:测试开环位置控制
*/

// Open loop motor control example
#include <SimpleFOC.h>


// BLDC motor & driver instance
// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(7);
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);

// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6,  8);


//target variable
float target_velocity = 0;

// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) {
  command.scalar(&target_velocity, cmd);
}
void doLimit(char* cmd) {
  command.scalar(&motor.voltage_limit, cmd);
}

void setup() {

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  // limit the maximal dc voltage the driver can set
  // as a protection measure for the low-resistance motors
  // this value is fixed on startup
  driver.voltage_limit = 6;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);

  // limiting motor movements
  // limit the voltage to be set to the motor
  // start very low for high resistance motors
  // current = voltage / resistance, so try to be well under 1Amp
  motor.voltage_limit = 2;   // [V]

  // open loop control config
  motor.controller = MotionControlType::velocity_openloop;

  // init motor hardware
  motor.init();

  // add target command T
  command.add('T', doTarget, "target velocity");
  command.add('L', doLimit, "voltage limit");

  Serial.begin(115200);
  Serial.println("电机准备就绪!");
  Serial.println("请设置目标位置");
  _delay(1000);
}

void loop() {

  // open loop velocity movement
  // using motor.voltage_limit and motor.velocity_limit
  // to turn the motor "backwards", just set a negative target_velocity
  motor.move(target_velocity);

  // user communication
  command.run();
  _delay(1000);
}

 

 实验场景图

 

 

posted @ 2024-07-02 19:38  行者花雕  阅读(7)  评论(0编辑  收藏  举报