Hello
Yes it is a very basic setup and easily working with the Arduino Uno, it’s quite baffling.
I think I may have some generic stepper motors around. I have a 230V PMSM, I don’t think I can test it with the DRV8301 lol.
Yes, the ground of the DRV and the MCU are connected.
I’ll try the dead_zone trick, maybe it works.
Here, are the velocity_openloop, 6PWM mode codes for the both the Bluepill and the Nucleo:
Bluepill
#include <SimpleFOC.h>
#include <DRV8301.h>
#define INH_A PA8 // TIM1 Ch1
#define INH_B PA9 // TIM1 Ch2
#define INH_C PA10 // TIM1 Ch3
#define INL_A PB13 // TIM1 CH1n
#define INL_B PB14 // TIM1 CH2n
#define INL_C PB15 // TIM1 CH3n
#define nFAULT PB8
#define EN_GATE PB9
#define SCLK PB3 // SCK1: SPI Sync Clock
#define nSCS PA15 // NSS1: SPI Chip Select (SS - Slave Select)
#define SDI PB5 // Serial Data Input (SPI MOSI)
#define SDO PB4 // Serial Data Output (SPI MISO)
BLDCMotor motor = BLDCMotor(4);
BLDCDriver6PWM pwm_driver = BLDCDriver6PWM(INH_A, INL_A, INH_B, INL_B, INH_C, INL_C, EN_GATE);
// DRV8301 gate_driver = DRV8301(MOSI, MISO, SCLK, CS, EN_GATE, FAULT);
DRV8301 gate_drv = DRV8301(SDI, SDO, SCLK, nSCS, EN_GATE, nFAULT);
float target_velocity = 2; // [rad/s]
// utility function enabling serial communication with the user to set the target values
// this function can be implemented in serialEvent function as well
void serialReceiveUserCommand()
{
// a string to hold incoming data
static String received_chars;
while (Serial.available())
{
// get the new byte:
char inChar = (char)Serial.read();
// add it to the string buffer:
received_chars += inChar;
// end of user input
if (inChar == '\n')
{
// change the motor target
target_velocity = received_chars.toFloat();
Serial.print("Target velocity ");
Serial.println(target_velocity);
// reset the command buffer
received_chars = "";
}
}
}
void setup()
{
Serial.begin(115200);
SimpleFOCDebug::enable(&Serial);
// driver config
// power supply voltage [V]
pwm_driver.pwm_frequency = 20000;
pwm_driver.voltage_power_supply = 24;
pwm_driver.init();
gate_drv.begin(PWM_INPUT_MODE_6PWM);
motor.linkDriver(&pwm_driver); // link the motor and the driver
// limiting motor movements
motor.voltage_limit = 1; // [V]
// motor.current_limit = 2;
// motor.velocity_limit = 20; // [rad/s]
// open loop control config
motor.controller = MotionControlType::velocity_openloop;
// init motor hardware
// motor.initFOC();
motor.init();
Serial.println("Motor ready!");
_delay(1000);
Serial.print(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG1));
Serial.print("\t");
Serial.println(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG2));
}
void loop()
{
// open loop velocity movement
// using motor.voltage_limit and motor.velocity_limit
// motor.loopFOC();
motor.move(target_velocity);
// Serial.print(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG1));
// Serial.print("\t");
// Serial.print(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG2));
// int allFaults = gate_drv.read_fault();
// Serial.print("\t");
// Serial.println(allFaults);
// receive the used commands from serial
serialReceiveUserCommand();
}
I have configured the Bluepill according to this pin-diagram:
Nucleo F410RB
#include <SimpleFOC.h>
#include <DRV8301.h>
#define INH_A PA_10 // TIM1_CH3 | D2
#define INH_B PA_8 // TIM1_CH1 | D7
#define INH_C PA_9 // TIM1_CH2 | D8
#define INL_A PB_1 // TIM1_CH3N | CN10 - 24
#define INL_B PB_13 // TIM1_CH1N | CN10 - 30
#define INL_C PB_0 // TIM1_CH2N | A3
#define EN_GATE PB_5 // D4
#define nFAULT PB_3 // D3
#define SCLK PA_5 // D13 | SPI Sync Clock
#define nSCS PB_6 // D10 | SPI Chip Select (SS - Slave Select)
#define SDI PA_7 // D11 | Serial Data Input (SPI MOSI)
#define SDO PA_6 // D12 | Serial Data Output (SPI MISO)
BLDCMotor motor = BLDCMotor(4);
BLDCDriver6PWM pwm_driver = BLDCDriver6PWM(INH_A, INL_A, INH_B, INL_B, INH_C, INL_C, EN_GATE);
// DRV8301 gate_driver = DRV8301(MOSI, MISO, SCLK, CS, EN_GATE, FAULT);
DRV8301 gate_drv = DRV8301(SDI, SDO, SCLK, nSCS, EN_GATE, nFAULT);
float target_velocity = 2; // [rad/s]
// utility function enabling serial communication with the user to set the target values
// this function can be implemented in serialEvent function as well
void serialReceiveUserCommand()
{
// a string to hold incoming data
static String received_chars;
while (Serial.available())
{
// get the new byte:
char inChar = (char)Serial.read();
// add it to the string buffer:
received_chars += inChar;
// end of user input
if (inChar == '\n')
{
// change the motor target
target_velocity = received_chars.toFloat();
Serial.print("Target velocity ");
Serial.println(target_velocity);
// reset the command buffer
received_chars = "";
}
}
}
void setup()
{
Serial.begin(115200);
SimpleFOCDebug::enable(&Serial);
// driver config
// power supply voltage [V]
pwm_driver.pwm_frequency = 20000;
pwm_driver.voltage_power_supply = 24;
pwm_driver.init();
gate_drv.begin(PWM_INPUT_MODE_6PWM);
motor.linkDriver(&pwm_driver); // link the motor and the driver
// limiting motor movements
motor.voltage_limit = 2; // [V]
// motor.current_limit = 2;
// motor.velocity_limit = 20; // [rad/s]
// open loop control config
motor.controller = MotionControlType::velocity_openloop;
// init motor hardware
motor.init();
Serial.println("Motor ready!");
_delay(1000);
Serial.print(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG1));
Serial.print("\t");
Serial.println(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG2));
}
void loop()
{
// open loop velocity movement
// using motor.voltage_limit and motor.velocity_limit
motor.move(target_velocity);
// Serial.print(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG1));
// Serial.print("\t");
// Serial.print(gate_drv.drv8301_read_reg(DRV8301_CONTROL_REG2));
// int allFaults = gate_drv.read_fault();
// Serial.print("\t");
// Serial.println(allFaults);
// receive the used commands from serial
serialReceiveUserCommand();
}
Timer pins taken from the Alternate Funtion Mapping in the MCU datasheet, page : 40/142
Hope you are able to reproduce the issue! Thanks!
Edit: This is the stepper motor I have. Is it possible to test the algorithm on it?