Link

基于L298N和Stm32 Nucleo-64的步进电机控制例程

运行此步进电机控制例程需要用到以下硬件:

点击这里下载STL 文件 - 图片和Youtube视频中用于STEP安装在 nema17 上 amt103 支架的 solidworks 项目

连接所有硬件

这是 L298N 和 Nucleo-64 的连接范例:

L298N

  • 通道 ENAENB 连接到引脚 78
  • 通道 IN1IN2,、IN3 以及 IN4 连接到引脚 56910
  • 公共地连接于 Nucleo 和 L298N 之间
  • 12V电源直接连接到驱动器

编码器

  • 通道 AB 连接到 引脚 A0A1
  • 这个例程中没有用到I引脚,但你可以简单修改例程来支持该通道。

电机

  • 电机 A1相、 A2相、 B1相和 B2 相直接连接到 L298N 芯片的电机连接器。

完整 Arduino 代码

#include <SimpleFOC.h>

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

// 编码器实例
Encoder encoder = Encoder(A1, A2, 2048);
// 通道A和B回调
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}



// commander 接口
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }

void setup() {

  // 初始化编码器传感器硬件
  encoder.init();
  encoder.enableInterrupts(doA, doB); 
  // 将电机连接到传感器上
  motor.linkSensor(&encoder);

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

  // 电源电压 [V]
  driver.voltage_power_supply = 12;
  driver.init();
  // 将电机连接到传感器上
  motor.linkDriver(&driver);

  // 设置要使用的控制回路类型
  motor.controller = MotionControlType::torque;

  // 根据控制配置控制器
  motor.PID_velocity.P = 0.2;
  motor.PID_velocity.I = 20;
  motor.PID_velocity.D = 0;
  // 默认电压电源
  motor.voltage_limit = 12;

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

  // 角环控制器
  motor.P_angle.P = 20;
  // 角开环速度极限
  motor.velocity_limit = 50;

  // 使用串行监控电机初始化
  // 监控端口
  Serial.begin(115200);
  // 如果不需要注释掉
  motor.useMonitoring(Serial);

  // 初始化电机
  motor.init();
  // 校准编码器并启动FOC
  motor.initFOC();

  // 设置初始目标值
  motor.target = 2;

  // 定义电机id
  command.add('M', onMotor, "motor");

  // 运行用户命令来配置和电机(在docs.simplefoc.com中找到完整的命令列表)
  Serial.println(F("Motor commands sketch | Initial motion control > torque/voltage : target 2V."));
  
  _delay(1000);
}


void loop() {
  // 迭代设定FOC相位电压
  motor.loopFOC();

  // 设定外循环目标的迭代函数
  // 速度、位置或电压
  // 如果参数中没有设定目标,则使用 motor.target 变量
  motor.move();

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