FOC Current Mode

Hi all,

when I try the foc current mode, I get a strage behavior of my motor. My setup is:

  • Motor: iPower Motor GM3506 Motor
  • Sensor: AS5048A with SPI interface
  • Driver: SimpleFOCShield v2.0.3
  • MCU: Arduino Uno
  • I am running the Driver with a 2 Cell Lipo Battery

My Code:

        #include <SimpleFOC.h>

    // BLDC motor & driver instance
    BLDCMotor motor = BLDCMotor(11);
    BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);

    // encoder instance
    MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
    // channel A and B callbacks

    // current sensor
    InlineCurrentSense current_sense = InlineCurrentSense(0.01, 50.0, A0, A2);
    float target_current = 0.1;
    // instantiate the commander
    Commander command = Commander(Serial);
    void doTarget(char* cmd) { command.scalar(&target_current, cmd); }

    void setup() { 
      
      // initialize encoder sensor hardware
      sensor.init();
      // link the motor to the sensor
      motor.linkSensor(&sensor);

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

      // current sense init hardware
      current_sense.init();
      // link the current sense to the motor
      motor.linkCurrentSense(&current_sense);
      current_sense.gain_b *= -1;
      current_sense.skip_align = true;
      // set torque mode:
      motor.torque_controller = TorqueControlType::foc_current; 
      // set motion control loop to be used
      motor.controller = MotionControlType::torque;

      // foc current control parameters (Arduino UNO/Mega)
      motor.PID_current_q.P = 3;
      motor.PID_current_q.I= 300;
      motor.PID_current_d.P= 3;
      motor.PID_current_d.I = 300;
      motor.LPF_current_q.Tf = 0.01; 
      motor.LPF_current_d.Tf = 0.01; 

      // 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();

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

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

    void loop() {

      // main FOC algorithm function
      motor.loopFOC();

      // Motion control function
      motor.move(target_current);

      // user communication
      command.run();
    }

If I do not use current_sense.skip_align = true, the current sense alignment fails and I do not know why. However, when I skip it, I can not stop my motor spinning when I type in T0. Do you know why?
And my second question is: How can I controll velocity and torque separately? Such as, change the torque with constant velocity?
Sorry I am very new in FOC but the torque controll with voltage worked.

Thank you for your answers!

I’m not sure about your issue, but I have one remark: you say you’re using a 2-cells lipo, whereas the SimpleFOCShield doc says that “recommended power supply voltage is from 12V to 24V”.

Hey guys,

@quentin you have a good remark! I would suggest using the 12V+ wit the shield but it will work on 2 lipo cell as well. The only constraint is that you cannot use the LDO.

@Alexander992

What is your motor monitor saying, can you dump the serial output and show it to us?

Have you tried using the voltage control, can you control your motor?
Is your sensor working right, have you tested it with the code examples?

I’d suggest you not to use the FOC current mode with Arduino UNO, it will work but the performance is not the best. I’d suggest you to get an arduin DUE, nucleo 64 board or esp32 based board. They are all very cheap (except maybe due) also and you can have much much better performance.

You will be using the limiting variables. So you will be running your motor in velocity mode and you will be setting the target velocity and the torque limit.

T1      # target velocity 1rad/s
LC2   # limit current 2 amps

Thank you for your helpful answer! I have ordered an arduino DUE and will try it again.
While I am waiting for my DUE, I tried it again with my UNO and used 12V to power up my setup. Now the current sensor alignment worked. However, I am not able to stop the motor: When I am typing T0, the motor is still running fast. Is there a problem in my source code or do I have to type something else in the command line?
Current mode using voltage is running fine and also the sensor test shows good results:
Velocity
BTW: Is this velocity noise in the sensor test too high?

Thank you!

Hi all,

the Arduino DUE arrived and the torque controll using voltage is working fine. However with the FOC current mode, I have the same problem as descrived above. Also limiting the voltage via code is not working “motor.current_limit = 0.5”. Typing T0 do not stop the motor. Any ideas what the problem is?

Thank you!

Hey @Alexander992,

Are you sure you are measuring the current well?
Can you verify that the pads on the bottom of the board are well soldered.

In your PID settup I’d say that motor.LPF_current_q.Tf = 0.01; is too much, lower it to 0.005 or even lower for starters. Also motor.PID_current_q.I= 300; is too high maybe you can go with 10 to start with.

Can you verify that the motor gets the command?
If you send the ? command does it return the list of devices connected?

Thank you Antun for your reply! You were right with the pads on the board, I forgot to solder them (stupid me). But now I have soldered the A0, A2 and the 3.3V Pin because of the Arduino Due. However, the code is still not working :frowning:
I tried to measure the current in torque voltage mode and got this result:

I think there is a lot of noise? This was measured with target volt = 2V. Increasing it to 4V does increase the blue values, if I try to stop the motor.
However, trying the following code, the motor is doing strange things, although I set target_current to 0.
Here is the latest code:

   #include <SimpleFOC.h>

    // BLDC motor & driver instance
    BLDCMotor motor = BLDCMotor(11);
    BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);

    // encoder instance
    MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
    // channel A and B callbacks

    // current sensor
    InlineCurrentSense current_sense = InlineCurrentSense(0.01, 50.0, A0, A2);
    float target_current = 0.0;
    // instantiate the commander
    Commander command = Commander(Serial);
    void doTarget(char* cmd) { command.scalar(&target_current, cmd); }

    void setup() { 
      
      // initialize encoder sensor hardware
      sensor.init();
      // link the motor to the sensor
      motor.linkSensor(&sensor);

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

      // current sense init hardware
      current_sense.init();
      // link the current sense to the motor
      motor.linkCurrentSense(&current_sense);
      current_sense.gain_b *= -1;
      //current_sense.skip_align = true;
      // set torque mode:
      motor.torque_controller = TorqueControlType::foc_current; 
      // set motion control loop to be used
      motor.controller = MotionControlType::velocity;

      // foc current control parameters (Arduino UNO/Mega)
      motor.PID_current_q.P = 3;
      motor.PID_current_q.I= 10;
      motor.PID_current_d.P= 3;
      motor.PID_current_d.I = 300;
      motor.LPF_current_q.Tf = 0.01; 
      motor.LPF_current_d.Tf = 0.005; 

      motor.PID_velocity.P = 0.2;
      motor.PID_velocity.I = 20;
      motor.PID_velocity.D = 0.001;
      // jerk control using voltage voltage ramp
      // default value is 300 volts per sec  ~ 0.3V per millisecond
      motor.PID_velocity.output_ramp = 1000;
      
      // velocity low pass filtering
      // default 5ms - try different values to see what is the best. 
      // the lower the less filtered
      motor.LPF_velocity.Tf = 0.01;
      
      // setting the limits
      motor.current_limit = 0.5; // Amps - default 0.2Amps
      
      // 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();

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

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

    void loop() {

      // main FOC algorithm function
      motor.loopFOC();

      // Motion control function
      motor.move(target_current);

      // user communication
      command.run();
}
    ```
Any ideas what I can change?
Thanks a lot!

Hi all,

I solved the problem by switching A0 and A2 in:
InlineCurrentSense(0.01, 50.0, A0, A2)
Now everything works fine :slight_smile:

Thank you all,
Alex

@Alexander992 , do you mean even with current_sense.skip_align = true commented out, you needed to invert A0 and A2 in InlineCurrentSense(0.01, 50.0, A0, A2)?

You might want to take a look at this topic.

Hello quentin,

yes, even without current_sense.skip_align = true I had to invert A0 and A2. I saw this topic and seem that I had the same problem. Very strange.

1 Like