Motor doesn't turn in FOC mode

Hi,

Just reading the forum, I posted in the stepper thread but seems I have this exact problem with a stepper. Next week I will try with a BLDC. I’m using a nucleo 144. I also get the high pitch after it locks up.

Hey @lulezi and @Jonathan_Robson,
I have done some testing this weekend and unfortunately I was still not able to replicate the issue you are having.

Did you maybe try the guessing procedure, were you able to make your motor spin?

I am a bit concerned with this bug you are having, I would really like to get to the bottom of this :smiley:

Hi,

I have nothing left to try with the stepper, tomorrow I will have a 3 x PWM compatible inverter to test with on a BLDC motor to see how it compares.

Hey Jonathan, have you tried this?

Hi, no, but when I try it again I will. I will next try a BLDC, I have the driver, just waiting for time to come :wink:

Hi @Antun_Skuric and @Owen_Williams

I finally got around to trying the guessing of the offset. Here’s my code:

/**
 * Torque control example using voltage control loop.
 * 
 * Most of the low-end BLDC driver boards doesn't have current measurement therefore SimpleFOC offers 
 * you a way to control motor torque by setting the voltage to the motor instead hte current. 
 * 
 * This makes the BLDC motor effectively a DC motor, and you can use it in a same way.
 */
#include <SimpleFOC.h>

BLDCMotor motor = BLDCMotor(9, 10, 6, 11, 8);
MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4);

void setup() {

  // initialise magnetic sensor hardware
  sensor.init();
  // link the motor to the sensor
  motor.linkSensor(&sensor);

  // power supply voltage
  // default 12V
  motor.voltage_power_supply = 12;
  // aligning voltage 
  motor.voltage_sensor_align = 3;
  
  // choose FOC modulation (optional)
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  // set motion control loop to be used
  motor.controller = ControlType::voltage;

  // use monitoring with serial 
  Serial.begin(115200);
  // comment out if not needed
  motor.useMonitoring(Serial);

  // initialize motor
  motor.init();

  // align sensor and start FOC
  //motor.initFOC();

  Serial.println("Motor ready.");
  Serial.println("Set the target voltage using serial terminal:");
  _delay(1000);
}

float target_voltage = 1;

int i = 0;
float guess = 0;

void loop() {
  motor.loopFOC();
  motor.move(target_voltage);
  
  if (i > 2000) {
    i = 0;
    guess += 10.0;
    motor.initFOC(guess, Direction::CW);
    Serial.print("new guess: ");
    Serial.println(guess);
  }

  i++;
}

Does that look right?

The motor moves a tiny little step with every .initFOC() call, but never manages to rotate beyond that. At some points (the offset is not reliably reproducible) it starts to violently shake.

I also tried Direction::CCW, which results in the tiny steps sometimes going into one direction and other times into the other direction, so I guess Direction::CW seems to be correct for the current setup.

I was expecting you to put motor.initFOC in the setup method and manually recompile 20x times with different guess values. Your approach is a clever way to automate this - I’ve not personally called initFOC multiple times but I guess it would work. How long does each i > 2000 take? A few seconds for each guess?

I would set motor.voltage_limit to something sensible for your motor e.g. if motor.voltage_sensor_align = 3; didn’t cause a violent autotune then maybe set it also to 3.

Another experiment you could try is to add a motor.monitor() to your loop and set the target_voltage to zero. The motor shouldn’t move but if you manually turn it the motor.monitor() should print out <voltage> <shaft_angle> <shaft_velocity. If the 2nd and 3rd columns are zero or ‘weird’ then it might shed some light. e.g. sensor works when not linked to motor but stops working when linked to motor.

Hey @lulezi,

Were you able to get around this problem?
I would suggest you not to use the approach that you have shown but just use a function like this:


void changeZeroAngle() {
  
  // 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') {
      
      // chage the guess
      float guess = received_chars.toFloat()*2*_PI/360;
      motor.zero_electric_angle = guess;      
      // reset the command buffer 
      received_chars = "";
    }
  }
}

And then just add this function to your loop():

void loop(){
    ...
   changeZeroAngle();
}

Then you just send a number in between 0 and 360 through serial. This will allow you to guess quicker and more precisely.

Otherwise, since this is very strange problem and it is troubling me a bit I would be happy to sned you an additional SimpleFOCShield hoping that that might resolve the issue :smiley:

Hi @Antun_Skuric

I wanted to try your suggestion yesterday but couldn’t get good readings from the sensor anymore. I saw this post and since I got these exact same sensors I checked my magnets and it seems they are also axially magnetized. So I ordered diametrically magnetized ones and hope they’ll arrive in the next few days.

However: I have no idea how I got proper readings from the sensor last time. Do you have any explanation? Anyway, let’s put this thread on hold until I can check with the right magnets.

Hey @lulezi,

Well spoted, that would explain the behavior that you are having.
I am not really sure how were you able to read any value really :smiley:

I guess that the sensor was able to read some data but this data was no longer well aligned with the electrical rotation of the motor, making the readings still appear correct (each rotation) by eye, but the relative readings were not precise enough to spin the motor in foc mode.

I hope this will resolve this issue! :smiley:

The new magnets arrived — everything works great!

Thanks a lot @Antun_Skuric and @Owen_Williams for your support and sorry for wasting your time on this non-issue.

1 Like

Cool!
I was starting to get worried about this issue :smiley:
I am happy you found your solution!

Hello @Antun_Skuric and @Owen_Williams I have been having the same problem. I have read and worked through this post at least twice and have double checked that I have the correct encoder magnet that was the problem for the other user; with no success. I am using GBM110-150T with AS5048A in both SPI and PWM modes attached to SimpleFOCShield V2.0.3 and Arduino Due, running SimpleFOC Library version 2.1.1

Hello @Antun_Skuric and @Owen_Williams I have been working through your getting started page. at step 2 velocity open loop, the motor starts stuttering at speeds over 3rads/sec and stops spinning at 6rads/sec.

with step 3 voltage closed loop: the motor does not spin at all.
If I rotate the motor by hand I can see the motor signal change on an oscilloscope, when I let go the waveforms and motor return to the position before it moved it; as if it is under angle control.
If I unscrew the encoder and rotate it by hand the motor follows; again as if is under angle control.

the motor moves fine in the initialisation/calibration section of the program. apart from they keep saying the motor has 15 pole pares, when the motor is a 24N22P motor.

Any thoughts on how to get the motor to spin?

Hi @Peter_S,

Welcome to the forum!

Lets first focus to get open loop control working! Are you using this motor? From the specs it looks like that this motor has 14 pole pairs. Does the motor work better when you configure the motor for 14 pole pairs?

Also for open loop control. Have you tried open loop position control? Does giving the motor the command to turn one time also result that the motor turns exactly 360 degrees?

If that does not help, can you share your code for the open loop part?

Hi @Wittecactus,
Thanks for getting bask to me.

Yes that is the motor I have, all be it from a different supplier.
Changing to 14 poles has no significant effect on open loop velocity program (now jerky from 3.6 rad/sec).
Only with 14 poles the open loop position does one full turn when commanded
the code is the example with only the hardware config changed. here it is any way:

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


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

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


//target variable
float target_velocity = 3;

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

void setup() {

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 20;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);

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

  // init motor hardware
  motor.init();

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

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

void loop() {

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

  // user communication
  command.run();
}

Hi @Wittecactus, increasing the supply voltage to 24V it will spin smoothly up to 4.3 rad/sec.
What is the max I can take the Simple FOC Shield to?

Hey @Peter_S!

Welcome to the community!
Let’s slow down a bit, try to get few things straight first.

  1. Your sensor works well? Does is show exactly 6.28 rad when you turn it one rotation?
  2. So I see you have found that your motor has 14 pole pairs since it did rotate one full irritation in openloop position mode when you set 6.28 target.
  3. For the velocity open loop the maximum velocity limit will depend of the voltage limit you set. In your code it’s set to 3V.
  motor.voltage_limit = 3;   // [V]

If you increase it your motor will have more power and be able to reach higher velocities, but will consume more power (what might not be a big deal for your motor). Also make sure to change the power supply voltage variable once you change it, it’s 12 Volts by default.

  motor.voltage_power_supply = 12;   // [V]

The shield will go up to 24 Volts, but most of the components are rated for up to >30Volts. But I would not recommend going above 25V.

  1. If you input a wrong pole pair number your closed loop control will not work at all. So make sure to set 14 as your pp number. If your sensor works well and the open-loop works well then you should have no issues running the closed loop.

The biggest and the sneakiest issue we have had so far, are the poorly polarized magnets. This issue arises after the sensor and open loop testes. They both work reasonably well but once when we try to run the motor in the closed loop magnet polarization issue makes for a really bad measurement and the FOC does not work. So make sure you do not have one of those, I think that was the original issue of this thread as well. :smiley:
Here is one of many threads with this issue

Hi @Antun_Skuric,
Thanks for the reply,
I have gone back to the begining and double checked every thing,
I am using the sensor in PWM mode, checked the min max values using that program (3 and 896) and these match the oscilloscope.
putting these values into the magnetic sensor PWM example gives 0.0 to 6.28 rad over one rotation with smooth flow to next rotation.

for the motor drive velocity open loop I double checked all values

BLDCMotor motor = BLDCMotor(14,17.8);
driver.voltage_power_supply = 24;

// limiting motor movements
motor.voltage_limit = 20; // [V]
motor.velocity_limit = 20; // [rad/s] cca 50rpm
with no improvements.
using the sensor in PWM mode removes SPI/I2C errors.

If you provide the phase resistance value to the BLDCMotor you’ll need to se the current limit not the voltage limit.

motor.current_limit = 1; \\ Amps - default is 0.2 Amps

But I advise you that in the beginning you do not use phase resistance and remove it from the constructor.

// Only pole pair number
BLDCMotor motor = BLDCMotor(14);

driver.voltage_power_supply = 24;

// limiting motor movements
motor.voltage_limit = 20; // [V]
motor.velocity_limit = 20; // [rad/s] cca 50rpm

It does remove the potential communication issues but it does not resolve the magnet problem if one exists. Because even the PWM sensor uses the magnet to read the position. And if the magnet has issues the PWM mode will not work well either.