Choosing a correct microcontroller for FOC_current torque controll and Arduino IDE

Hello everyone!
I’m developing a bldc motor controller and looking for a reliable microcontroller to run FOC_current mode, and to be able to program it through Arduino IDE. Preferebly, the size of the microcontroller should be the size of a Arduino Nano, or STM32 Nucleo 32, becouse my board has a layout that fits this size. I have seen the Supported Hardware section on the web site, but i am looking for something that was already tried out, to be as sure as possible, that it is going to work smoothly.

In the beggining i was using a basic Arduino Nano, but it didn’t have enough Flash memory available.
Then i wanted to use an STM32 L432KC nucelo32, but there are problems with communication with Arduino IDE. I am runnnig short on time to finish the project and i cant spend another week or two looking what the problem is.
That’s why i want to ask the community to help me pick one that is going to work well.
If you have experience with a microcontroller, and you already tested that it is going to work with Arduino IDE please give me a hint.

Take care everyone !

Hey,

In the Nano shape we would support, out of the box, also any of the newer Arduino Nanos, like the Nano 33 BLE, the Nano 33 IoT or the Nano 33 Sense.
We would also support the Nucleo 32 boards… while the STM32L series might give you some trouble, the STM32F4 or STM32G4 should be well supported.

Note also that with some effort we can probably get the L432 to work. It sounds like you were having problems with the flash memory size, which is usually something that can be fixed with options, or in the worst case by creating your own board description files…

A list of small boards I have personally tested and they work and will cover your use case:

Blue Pill
Black Pill
NUCLEO-G431KB

For the Nucleo-G431KB to make the 6pwm work you need to jump-solder one of the pin shunt leads (#8). If you do 3PWM no need to solder.

Problem with Blue Pill and Black Pill, is flashing with SWD debugger, if you don’t have one, just go for Nucleo-G431KB. Cheap and in stock.

What sensors do you need to use? Is your motor sensored? The only problem with that board is the limited number of pins, depending on your angle sensoring scheme.

Cheers,
Valentine

@runger @Valentine Thank you so much for all your help
@Valentine The position feedback on the motor are Hall sensors, and i am planning to use in-line current sensing.

You will have enough free analog and IO pins for that.

When you get to that point if you decide to use the G431KB please come back here and ask, I will post the pin mappings that would work in your case. I was going to do this anyways because I’m in the process of mapping the G431KB board to make it work with the SimpleFOC Power Shield but I may speed it up if your needs are urgent.

Cheers,
Valentine

Hey @Valentine thanks for the offer, i ordered the STM32G431KB T6U, so if you would like to help me with the pin mappings that would be great. I am planning to connect 6PWMbldc driver to 3 high/low N-mosfet drivers with hall sensors and 2 in-line curent sensors. If hardware interrupts possible then would be cool to use them. Thanks again!

This is the open loop code. I will post the analog current sense and hall sensors later, I’m traveling and will be back next week.

image


Below is the open loop code for testing. We have to re-write the code because I commented out a bunch of stuff you won’t need, but may need later. The way I posted it, it will work well for testing as is.

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

// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(1);

BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PA7, PA9, PB0, PA10, PF0, PA4);

//target variable
float target_velocity = 3.0;
float target_voltage = 3.0;

int analog_read_A0 = 0;
int analog_read_A1 = 0;

// instantiate the commander
//Commander command = Commander(Serial);and.scalar(&target_velocity, cmd); }

//void doTarget(char* cmd) { comm
void setup() {

  //pinMode(PA15, OUTPUT);
  //digitalWrite(PA15, LOW);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  //driver.enable_active_high = false; // INFINEON ELICE DRIVER
  // pwm frequency to be used [Hz]
  driver.pwm_frequency = 10000;

  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);

  // limiting motor movements
  motor.voltage_limit = 12;   // [V]
  motor.velocity_limit = 100; // [rad/s] cca 50rpm
 
  // open loop control config
  motor.controller = MotionControlType::velocity_openloop;

  // init motor hardware
  motor.init();

  // add target command T
  //command.add('T', doTarget, "target velocity");

  //Serial.begin(115200);
  //Serial.println("Motor ready!");
  //Serial.println("Set target velocity [rad/s]");
  _delay(1000);
}

void loop() {

  //analog_read_A0 = analogRead(PA3);
  //analog_read_A1 = analogRead(PA4);

  //target_velocity = float(map(analog_read_A0, 0, 4096, 0, 10000))/100.0;

  //target_voltage = float(map(analog_read_A1, 0, 4096, 0, 1200))/100.0;

  motor.voltage_limit = target_voltage;

  // open loop velocity movement
  // using motor.voltage_limit and motor.velocity_limit
  motor.move(target_velocity);

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

Hey @Valentine!
I was wondering if you might have some time to post the hall sensor - closed loop code and maybe also the current sensors code. I’ve got the open loop going and it works perfectly. The commander interface in open-loop also works the way it should.

I also tried to get the closed loop - velocity control going but there is a problem.
The code loads and everytghing seems to be ok, the driver.init(), sensor, motor.init(), FOC functions load correctly. Then when i try to use a commander command in the serial monitor/commander, it also seems to be working and the commander responds to setting target velocity in the serial monitor window.
The problem is, there is completely no PWM signal form the microcontroller no matter what the set target velocity is. I tried out multiple code configurations and nothing helps.
Also, when i add commander command for Full motor configuration:

command.add('M',onMotor,"full motor config");

the driver(), sensor() and rest of the functions stop loading and the code breaks, basically everything stops responding.
I tested the Hall sensors and they give out correct signals, and i have no further idea what the problem might be becouse the open loop works exactly the way it should.

Take care and thanks for all the help so far!

Could you post your code please? I haven’t tested this MCU with closed loop but I can try loading your code on mine and test.

Cheers,
Valentine

The 4th iteration of the code :

#include <SimpleFOC.h>

// Hall sensor instance
// HallSensor(int hallA, int hallB , int hallC , int pp)
//  - hallA, hallB, hallC    - HallSensor A, B and C pins
//  - pp                     - pole pairs
BLDCMotor motor = BLDCMotor(15);
HallSensor sensor =  HallSensor(PB7, PA15, PB6, 15);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PA7, PA10, PF0, PA9, PB0);

// Interrupt routine initialization
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

Commander command = Commander(Serial);
void onTarget(char* cmd) { command.target(&motor, cmd); }
void onMotor(char* cmd)  { command.motor(&motor, cmd); }

void setup() {
  // monitoring port
  Serial.begin(115200);

  // check if you need internal pullups
  sensor.pullup = Pullup::USE_EXTERN;
  
  // initialize sensor hardware
  sensor.init();
  // hardware interrupt enable
  sensor.enableInterrupts(doA, doB, doC);
  motor.linkSensor(&sensor);

  Serial.println("Sensor ready");
  _delay(1000);

  driver.voltage_power_supply = 14;
  driver.pwm_frequency = 20000;
  
  Serial.print("Driver init ");// init driver
  if (driver.init()) 
  Serial.println("success!");
  else{Serial.println("failed!");
  return;}
  motor.linkDriver(&driver);

  motor.controller = MotionControlType::velocity;
  motor.init();
  motor.initFOC();
  Serial.println("Motor ready.");

  command.add('T', onTarget, "target velocity");
  //command.add('M', onMotor,  "motor");
  //command.motor(&motor,"E0");
  _delay(1000);
}

float target_velocity = 0;

void loop() {
  // IMPORTANT - call as frequently as possible
  // update the sensor values 
  sensor.update();
  motor.loopFOC();
  motor.move(target_velocity);
  // display the angle and the angular velocity to the terminal
 //Serial.print(sensor.getAngle());
  //Serial.print("\t");
  //Serial.println(sensor.getVelocity());
  command.run();
}

I believe the problem is that you are accessing the default Serial. Please remove all references to serial and commander (comment them out) and try running a slow fixed speed. The default Serial conflicts with some of the other pins.