B-G431-ESC1 Unable to Spin Motor in Closed Loop Velocity or Position

Hello,

I am getting started with using PlatformIO and SimpleFOC to operate a BLDC motor with the B-G431-ESC1 and an AS5600. I currently am using this motor (BrotherHobby Avenger 2812 V3 Motor(CW)) that is 900kV, 14 P, and 87mohms of internal resistance.

I have been following the SimpleFOC tuning guide videos from the official Youtube (https://youtu.be/ENGGh0ajE2M?si=XkhZx6LyVNI1wkKv) and have currently gotten the open-loop velocity mode to work.

However, when I try to run the closed-loop velocity controller, the motor never spins or may jolt a slight movement like it is stalling and then proceed to not move either. I am pretty lost on what is so different in implementing the velocity controller that it completely prevents the motor from moving.

Here is the code I have been using to test:

#include "Arduino.h"
#include "SimpleFOC.h"
// #include "motorSetup.h"

#define CONSTANT_VELOCITY             5.00f
#define GOAL_POSITION                -2.50f
float target = 0.00;

// Init Motor
BLDCMotor motor(14, 0.087, 900);                                                               
BLDCDriver6PWM driver(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL); 
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);

// Init Encoder
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);

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

void serialLoop() {
    static String received_chars;

    while (Serial.available()) {
        char inChar = (char) Serial.read();
        received_chars += inChar;

        if (inChar == '\n'){
            target = received_chars.toFloat();
            Serial.print("Target = "); Serial.println(target);
            received_chars = "";
        }
    }
}

void setup() {
    // Set up Serial + I2C
    Serial.begin(115200);
    Wire.setClock(400000);

    // // Set up encoder
    sensor.init();
    Serial.println("Sensor Ready!");

    // // Link Motor and Encoder
    motor.linkSensor(&sensor);
    Serial.println("Motor and Sensor Linked!");

    // // Set up motor driver
    driver.voltage_power_supply = 12;   // Voltage Supply
    driver.init();
    motor.linkDriver(&driver);
    Serial.println("Driver Ready!");

    // link current sense and the driver
    currentSense.linkDriver(&driver);

    // // Set up Current Sensing
    // currentSense.init();
    // currentSense.skip_align = true;     // no need for aligning
    // motor.linkCurrentSense(&currentSense);

    // // Set up system limits
    motor.voltage_limit = 6.0;            // Volts
    motor.velocity_limit = 20;          // rad/s
    motor.voltage_sensor_align = 1;     // Limits volts during FOC calibration
    motor.current_limit = 8.0;          // Amps
    motor.PID_velocity.output_ramp = 1000;

    // // Set up Velocity PID Coefficients
    motor.PID_velocity.P = 0.20f;
    motor.PID_velocity.I = 20.0f;
    motor.PID_velocity.D = 0;
    motor.LPF_velocity.Tf = 0.01f;

    // // Set up Motor
    // motor.torque_controller = TorqueControlType::voltage;
    motor.controller = MotionControlType::velocity;      // For position control test
    motor.useMonitoring(Serial);                            // Target | Voltage | Current | Velocity | Angle
    motor.monitor_variables = _MON_TARGET | _MON_VOLT_Q | _MON_ANGLE | _MON_VEL | _MON_CURR_Q ;

    // command.add('T', doTarget, "target angle");
    
    motor.init();
    motor.initFOC();
    Serial.println("Motor Ready!");


    delay(1000);
}

void loop() {

    // Update system
    serialLoop();
    // sensor.update();

    motor.loopFOC();
    motor.move(target);

    // Print statements
    motor.monitor();
    // command.run();


}

I have been trying to chase this issue for multiple days and would appreciate any guidance!!
Thanks all!

Are you confident you have the pole pairs correct?

Have you done a sensor test on its own e.g

Manually turning the motor 360deg should show 2xpi radians in the output for above test.

If you’ve done that then it would be good to post the output from your code, the initFOC method prints a bunch of info that might help you/us work out what is going on.

I did that video 3 years ago and it could probably do with being replaced by someone with more experience than me i.e i think the recommended 1st step for closed loop is ‘torque mode using voltage’ as it is simplest (no PIDs to tune). See step 3:

Hi Owen, I forgot to reply to this thread but your input was very helpful! The error I was having with the number of Pole Pairs I had specified in my code (14 instead of 7 yikes).

I am still experimenting with the SimpleFOC library and have been stumped at getting closed-loop velocity and position to work properly. Some notes:

  • I have gotten torque with voltage mode working but it is very sensitive to target inputs. For example, I can give it ‘0.4’ as an input in Serial command and it won’t spin, but if I give it ‘0.7’ it spins roughly 60 rads/s. After initially getting it to spin I can bring it to ‘0.3’ before it stops spinning. My issue with voltage control is not having very fine speed control and not having low speed control with much torque at all.
  • To get my velocity reading to be less noisy I increased the minimum elapsed time that the velocity updates to roughly 0.2 seconds and have verified both position and velocity readings to be steady and accurate.

I currently want to get closed-loop position and velocity working but whenever I try to run my code, any PID gains result in the motor spinning up and then oscillating between positive and negative velocities. I have tried looking through other threads but have yet to find any solution how to solve this problem. My motor is relatively small and more geared toward drone applications but want to get fine position control. Any help would be amazing as it has been pretty frustrating trying to get my setup working properly.

This is my current code for closed loop velocity:

void closedLoopVelocitySetup(){

    Serial.begin(115200);
    Wire.setClock(40000);

    sensor.init();
    motor.linkSensor(&sensor);

    driver.init();
    motor.linkDriver(&driver);

    // currentSense.init();
    // motor.linkCurrentSense(&currentSense);

    driver.voltage_power_supply = 12;
    motor.voltage_sensor_align = 1;
    // motor.voltage_limit = 4;
    motor.current_limit = 1.5;
    motor.velocity_limit = 20;
    motor.useMonitoring(Serial);

    motor.controller = MotionControlType::velocity;
    motor.PID_velocity.P = 2.0;          // need to play with this
    motor.PID_velocity.I = 0.0;          // need to play with this
    motor.PID_velocity.D = 0;
    motor.PID_velocity.output_ramp = 1.0; // need to increase this 
    // motor.PID_velocity.limit = 0.5;

    motor.LPF_velocity.Tf = 0.01 ;
    // motor.motion_downsample = 1000;

    motor.init();
    motor.initFOC();

    command.add('T', doTarget, "Target Closed Loop Position = ");
    command.add('M', doMotor, "Enable = ME 1, Disable ME 0");
    command.add('P', doP, "P = ");
    Serial.println("Motor Setup Complete!");

    delay(1000);

}

void closedLoopVelocityLoop(){

    motor.loopFOC();

    motor.move();

    motor.monitor();

    command.run();

}

Tuning the velocity PID can be tricky.

Here is what I’d try.

  1. Focus on P and tf first (Set I and D to zero).
    Set a target velocity to something that isn’t too slow e.g 10 rad/s. Reduce P to 0, then increase it in 0.05 increments. Probably at about 0.1 to 0.5 it might start to move. Keep increasing P until velocity is about 6 rad/s i.e. the P term is giving you 60% of your target velocity. If you increase much beyond this you risk oscillation.
  2. At this time I’d try to play with tf. If the above didn’t work out well you might have to tune tf and P at the same time (yikes!). If you start at 0.01 then try increasing or reducing this value. I might try these values [ 0.3, 0.1, 0.06. 0.03, 0.01, 0.06, 0.03, 0.01, 0.006, 0.003, 0.001] starting at 0.01 and moving up and down. So you are looking to see if there is better or worse velocity ripple.
  3. Now that you are happy with P and Tf, try configuring I. maybe start at 0.5 and increase to 10 or beyond. This integral term will increase you from you 60% or target to 100% of target.
  4. Keep D term as 0 - it rarely helps.
  5. Once you have a stable velocity PI then you can switch to angle mode. For this you typically only set the P term - this is far easier and often just works on default value (I think its 10 or 20).

Thanks for the feedback!! I followed a similar approach by making P very small (~0.01) and then requesting a target velocity of ~20 rad/s and greater to get the closed loop velocity to work.

My main issue was only trying to achieve very low velocities which resulted in either no movement or oscillations when increasing my P term. Also, good to note that I used the serial monitor to track the minimum velocity the motor was capable of achieving when in voltage control mode to know what the minimum target should be in PID control (i.e. setting different target voltages until the motor moves and using the current velocity from the sensor as the PID target velocity).