Hi,
I have a similiar design based on EVLSPIN32G4 it have STSPIN32G4 MCU. My hardware is almost identical with EVLSPIN32G4 board schematic. I just removed CANBUS support on hardware and changed MOSFET’s with some other brand.
I am having trouble to drive motors with my design but i am not sure if its simple foc or hardware related.
My main.cpp code on Platformio is like this:
#include <Arduino.h>
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "drivers/stspin32g4/STSPIN32G4.h"
#include "stm32g4xx_hal.h"
#include "HardwareSerial.h"
STSPIN32G4 driver = STSPIN32G4();
BLDCMotor motor = BLDCMotor(7);
HallSensor sensor = HallSensor(PB6, PB7, PB8, 7); //THESE ARE MY HALL SENSOR PINS
LowsideCurrentSense currentSense = LowsideCurrentSense(0.0020, 10, PA2, PB1, _NC); //THESE ARE MCU INTERNAL OPAMP OUTPUTS, IF I USE PA6 INSTEAD OF PB1 IT GIVES THIS ERROR "STM32-CS: ERR: Analog pins dont belong to the same ADC!"
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
Commander commander = Commander(Serial1); //"NORMAL "Serial" DOESN'T WORK. "Serial1" WORKS WITH "-DSERIAL_UART_INSTANCE=1" ON PLATFORMIO.INI FILE.PA10 AND PA9 ARE SERIAL CONNECTION PINS
void onMotor(char* cmd){ commander.motor(&motor,cmd); }
void setup() {
Serial1.begin(115200);
motor.useMonitoring(Serial1);
pinMode(PC14, OUTPUT); //PC14 IS ONBOARD LED FOR JUST FOR VISUAL FEEDBACK IF MCU EXECUTES CODE.
digitalWrite(PC14, HIGH);
delay(1000);
sensor.init();
sensor.enableInterrupts(doA, doB, doC);
motor.linkSensor(&sensor);
driver.voltage_power_supply = 12; //I HAVE 12V PSU
driver.pwm_frequency = 32000;
driver.init();
motor.linkDriver(&driver);
motor.voltage_sensor_align = 1;
motor.controller = MotionControlType::velocity;
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
motor.init();
currentSense.linkDriver(&driver);
currentSense.init();
motor.linkCurrentSense(¤tSense);
Serial1.println(sensor.getVelocity());
motor.initFOC();
commander.add('M',onMotor,"my motor motion");
}
void loop(){
motor.loopFOC();
motor.move(5);
}
My platformio.ini file as follows:
[env:genericSTM32G431CB]
platform = ststm32
board = genericSTM32G431VB
framework = arduino
lib_deps =
askuric/Simple FOC@^2.3.4
simplefoc/SimpleFOCDrivers@^1.0.8
Wire
SPI
board_build.ldscript = ./variant/ldscript.ld
monitor_speed = 115200
monitor_eol = LF
build_unflags = -Os
build_flags =
-Ofast
-DSIMPLEFOC_STM32_DEBUG
-DPIO_FRAMEWORK_ARDUINO_ENABLE_CDC
-DUSBD_USE_CDC
-DUSBCON
-DSERIAL_UART_INSTANCE=1
-DHAL_CORDIC_MODULE_ENABLED
-DHAL_LPTIM_MODULE_ENABLED
-D PIO_FRAMEWORK_ARDUINO_ENABLE_CDC
-D PIO_FRAMEWORK_ARDUINO_NANOLIB_FLOAT_PRINTF
Serial output of above code:
MOT: Monitor enabled!
TIM1-CH1 TIM1-CH1N TIM1-CH2 TIM1-CH2N TIM1-CH3 TIM1-CH3N score: 1
STM32-DRV: best: TIM1-CH1 TIM1-CH1N TIM1-CH2 TIM1-CH2N TIM1-CH3 TIM1-CH3N score: 1
STM32-DRV: Syncronising timers! Timer no. 1
STM32-DRV: Restarting timer 1
MOT: Init
MOT: Enable driver.
STM32-CS: Using ADC: 1
STM32-DRV: Stopping timer 1
STM32-DRV: Stopping timer 1
STM32-DRV: Stopping timer 1
STM32-DRV: Stopping timer 1
STM32-DRV: Stopping timer 1
STM32-DRV: Stopping timer 1
STM32-DRV: Syncronising timers! Timer no. 1
STM32-DRV: Restarting timer 1
0.00
MOT: Align sensor.
MOT: Failed to notice movement
MOT: Init FOC failed.
My bench PSU is set to 12V and 3A limit, when i reset ESC it draws about 390mA for some time and doesn’t rotate motor.It halts on Init FOC failed.
Current sense thing was a bit complex so i tried it also on openloop with below code:
#include <Arduino.h>
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "drivers/stspin32g4/STSPIN32G4.h"
STSPIN32G4 driver = STSPIN32G4();
BLDCMotor motor = BLDCMotor(7);
void setup() {
driver.voltage_power_supply = 12.0f;
driver.init();
motor.voltage_limit = driver.voltage_limit / 2.0f;
motor.controller = MotionControlType::velocity_openloop;
motor.linkDriver(&driver);
motor.init();
}
void loop(){
motor.move(5.0f); // 5 rad/s open loop
delayMicroseconds(100); // STM32G4 is very fast, add a delay in open loop if we do nothing else
}
In openloop configuration it draws about 138mA on PSU and doesn’t rotate also. Motor can be rotated with hands with soft ressistance, i can feel the pole points.
Another thing that i want to point that if i start a new project on platformio and upload same FOC code above serial output complains about this:
MOT: Monitor enabled!
MOT: Init not possible, driver not initialized
ERR: Low-side cs not supported!
0.00
MOT: Align sensor.
MOT: Failed to notice movement
MOT: Init FOC failed.
ERR: Low-side cs not supported! i searched web and forum but i cannot find anything related with it.
If i clone this repo and use above FOC code this Low-side error thing doesn’t happen. But as i described above it draws about 390mA for some time and doesn’t rotate motor.
I am pretty confused and puzzled about this. In past i used B-G431B-ESC1 with Simple FOC which i expect this board behavior should be similiar.
Could someone point me right direction?
Thanks in advance.