Nonsensical behavior in Torque-voltage mode with Back-EMF compensation

Hi, my motor works OK with “pure voltage” and “voltage with current estimation” mode

When I try to use “Voltage control with current estimation and Back-EMF compensation” the behavior gets really strange.

As you can see from the attached session, when I command any positive current, the motor jumps right to full speed(~350 rad/s)… When I target 0 current, nothing happens!!!. As you can see from the log, Nothing happens until I comand about -1 A.

I’m fairly confident on the resistance and K-rating for the motor.,

Sensor: 100 PPR (400CPR) optical quadrature encode
Motor: 42BLS02
Controller: ST32G431 (NUCLEO)
DRIVER: 8302

enter setup…
MOT: Monitor enabled!
MOT: Init
MOT: Enable driver.
MOT: Align sensor.
MOT: sensor_direction==CCW
MOT: PP check: OK!
MOT: Zero elec. angle: 6.22
MOT: No current sense.
MOT: Ready.
setup complete…
Warn: \r detected!
Monitor | downsample: 100000
0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0157
Warn: \r detected!
0.100 ##### TARGET 0.1 A makes MOTOR JUMPS TO FULL SPEED!!1
0.1000 1.3800 0.0000 99.9571 0.0000 47.3901 24.0175
0.1000 9.0000 0.0000 -445.6520 0.0000 349.7160 931.4980
0.1000 9.0000 0.0000 -427.3739 0.0000 349.0393 2089.3476
0.1000 9.0000 0.0000 -450.4194 0.0000 349.8926 3249.9619
0.1000 9.0000 0.0000 -484.6363 0.0000 351.1594 4412.3984
Warn: \r detected!
0.000 ##### TARGET 0 A makes does NOT stop motor!!!
0.0000 9.0000 0.0000 -477.6773 0.0000 350.9018 5575.8085
0.0000 9.0000 0.0000 -460.1956 0.0000 350.2545 6738.4653
0.0000 9.0000 0.0000 -402.7777 0.0000 348.1287 7893.1103
0.0000 9.0000 0.0000 -408.9327 0.0000 348.3566 9048.0224
Warn: \r detected!
-0.100 **##### TARGET -0.1 A has has no effect!!!
-0.1000 9.0000 0.0000 -447.4249 0.0000 349.7817 10205.9199
-0.1000 9.0000 0.0000 -492.4383 0.0000 351.4483 11369.6601
-0.1000 9.0000 0.0000 -490.0589 0.0000 351.3602 12534.5312
Warn: \r detected!
-0.200
-0.2000 9.0000 0.0000 -479.4617 0.0000 350.9678 13697.2343
-0.2000 9.0000 0.0000 -483.3966 0.0000 351.1135 14859.1992
Warn: \r detected!
-0.500
-0.5000 8.7477 0.0000 -499.9228 0.0000 342.3880 16018.5419
-0.5000 8.7095 0.0000 -500.9279 0.0000 340.9717 17152.8300
-0.5000 8.7028 0.0000 -500.8154 0.0000 340.7238 18288.3730
Warn: \r detected!
-1.000 **##### TARGET -1 A finally motor starts to spin the other way
-1.0000 5.9253 0.0000 -999.9423 0.0000 256.4022 19285.1699
-1.0000 -0.4330 0.0000 -999.6849 0.0000 20.9912 19895.7695
-1.0000 -9.0000 0.0000 -337.9717 0.0000 -320.7031 18932.4628
-1.0000 -9.0000 0.0000 -322.8493 0.0000 -321.2631 17868.2636
-1.0000 -9.0000 0.0000 -338.9483 0.0000 -320.6670 16802.1171
Warn: \r detected!
-2.000
-2.0000 -9.0000 0.0000 -340.2853 0.0000 -320.6175 15735.8457
-2.0000 -9.0000 0.0000 -319.8786 0.0000 -321.3730 14670.1542
Warn: \r detected!
0.000
0.0000 -7.9956 0.0000 -0.5326 0.0000 -296.0299 13653.8642
Warn: \r detected!
0.000
0.0000 0.0000 0.0000 0.0006 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9316
0.0000 0.0000 0.0000 0.2292 0.0000 -0.0085 13213.9316
0.0000 0.0000 0.0000 -0.2724 0.0000 0.0101 13213.9628
0.0000 0.0000 0.0000 0.0001 0.0000 -0.0000 13213.9785
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9785
0.0000 0.0000 0.0000 0.0000 0.0000 -0.0000 13213.9785
Warn: \r detected!
Monitor | downsample: 0

#include <Arduino.h>
#include <SimpleFOC.h>
#include “DRV8301.h”
#include <SimpleFOC.h>

/*
MOTOR : 42BLS02
CTRLR : STM
ALGO : FOC-TORQU
DRIVE : DRV8302
SENS : ENCODER 100PPR
*/

#define CONTROL_TYPE (MotionControlType::torque)
#define SUPPLY_V (18)
#define DRIVER_V_LIMIT (18)
#define MOTOR_V_LIMIT (9)
#define SENSOR_ALIGN_V (2) //1

#define USE_DRV8302

//#define USE_SMOOTHSENSOR
#ifdef USE_SMOOTHSENSOR
#include “smoothsensor.h”
#endif

#define HB_IO (8)

Encoder sensor = Encoder(14, 15, 100);

#ifdef USE_DRV8301
//DRV8301 gate_driver = DRV8301(PC13, PC14, PC15, PB7, PF0, PF1); // MOSI, MISO, SCLK, CS, EN_GATE, FAULT
DRV8301 gate_driver = DRV8301(3, 4, 5, 2, 6, 7); // MOSI, MISO, SCLK, CS, EN_GATE, nFAULT
#endif //USE_DRV8301
#ifdef USE_DRV8302
DRV8302 gate_driver = DRV8302(2, 3, 4, 5, 6, 7); // nFAULT, M_PWM, M_OC, GAIN, OC_ADJ, EN_GATE
#endif // USE_DRV8302

// motor & driver instance
//BLDCMotor motor = BLDCMotor(4); // works good
//BLDCMotor motor = BLDCMotor(4, 1); // works good
BLDCMotor motor = BLDCMotor(4, 1, 250); // strange behavior

BLDCDriver3PWM driver = BLDCDriver3PWM(PC0, PC1, PC2); // DRV8301/2

void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
//void doC(){sensor.handleC();}

// commander communication instance
Commander command = Commander(Serial);
// void doMotor(char* cmd) { command.motor(&motor, cmd); }
void doTarget(char* cmd) {command.scalar(&motor.target, cmd);}
void doLimit(char* cmd) {command.scalar(&motor.voltage_limit, cmd);}
void doMotor(char* cmd) { command.motor(&motor, cmd); }
void doInduct(char* cmd) { command.scalar(&motor.phase_inductance, cmd); }

#ifdef USE_SMOOTHSENSOR
SmoothingSensor smooth = SmoothingSensor(sensor, motor);
#endif

char msgbuf[256];

void setup() {
Serial.begin(921600); // WARNING: low value like 115200 cause distorted FOC
// for timer analysis
//SimpleFOCDebug::enable(&Serial);
//delay(5000);
Serial.printf(“enter setup…\n”);

sensor.pullup = Pullup::USE_INTERN;
sensor.init();
sensor.enableInterrupts(doA, doB /, doC/);
// link the motor to the sensor

#ifdef USE_SMOOTHSENSOR
smooth.phase_correction = -_PI_6; // FOR HALL SENSOR
motor.linkSensor(&smooth);
#else // USE_SMOOTHSENSOR
motor.linkSensor(&sensor);
#endif

// driver config
// power supply voltage [V]
driver.voltage_power_supply = SUPPLY_V;
driver.voltage_limit = DRIVER_V_LIMIT;
driver.init();
#ifdef USE_DRV8302
gate_driver.begin(PWM_INPUT_MODE_3PWM, SHUNT_GAIN_10);
_delay(100);
#endif // USE_DRV8302

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

motor.voltage_sensor_align = SENSOR_ALIGN_V;

//motor.controller = MotionControlType::torque;
motor.controller = CONTROL_TYPE;
// default voltage_power_supply
motor.velocity_limit = 200;
motor.voltage_limit = MOTOR_V_LIMIT;
motor.current_limit = 1000.0;

// velocity loop PID
motor.PID_velocity.P = 0.1;
motor.PID_velocity.I = 0.05;
motor.PID_velocity.D = 0.0;
motor.PID_velocity.output_ramp = 1000;
motor.PID_velocity.limit = 1000.0;
// Low pass filtering time constant
motor.LPF_velocity.Tf = 0.1;
// angle loop PID
motor.P_angle.P = 5.0;
motor.P_angle.I = 0.0;
motor.P_angle.D = 0.0;
motor.P_angle.output_ramp = 1000.0;
motor.P_angle.limit = 1000.0;
// Low pass filtering time constant
motor.LPF_angle.Tf = 0.0;
// motor.motion_downsample = 10;

// set the inital target value
motor.target = 0;
// comment out if not needed
motor.useMonitoring(Serial);
motor.monitor_downsample = 0; // disable intially
motor.monitor_variables = _MON_TARGET | _MON_VOLT_Q | _MON_VOLT_D | _MON_CURR_Q | _MON_CURR_D | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle

//motor.foc_modulation = SpaceVectorPWM;
// initialise motor
motor.init();
// align encoder and start FOC
motor.initFOC();

// subscribe motor to the commander
command.add(‘T’, doTarget, “target”); // ssss space
command.add(‘L’, doLimit, “voltage limit”);
command.add(‘I’, doInduct, “phase_inductance”);
command.add(‘M’,doMotor,“motor”);

Serial.printf(“setup complete…\n”);
_delay(1000);

pinMode(HB_IO, OUTPUT);
}

void loop() {

// iterative setting FOC phase voltage
motor.loopFOC();

// iterative function setting the outter loop target
motor.move();

// motor monitoring
motor.monitor();

// user communication
command.run();
digitalWrite(HB_IO, 0);

#if defined(USE_DRV8301) || defined(USE_DRV8302)
if (gate_driver.is_fault())
{
sprintf(msgbuf, “gate driver faulted”);
}

#endif // USE_DRV8302

}

*/

Sounds like you may have it close to tuned well…

I’d say the BEMF voltage, as well as friction of course, oppose the motion of the motor. So if you set a target current of 0A, the BEMF compensation will mean there is a slight current in opposition to the BEMF, and the motor would tend to “coast”, slowly stopping due to its bearing friction. The more weight on the rotor, the longer it would coast.

Of course if you set -1A current then you want to move in the other direction, so after the remaining inertia is overcome it begins to rotate the other way.

If you just want to stop the motor in this scenario, you can set the phase state to OFF or LOW, to brake the motor, or use velocity control, where you can set the target velocity to be 0.

But (when I set it to target 0) it doesn’t even slow down, even if I wait a long time.

The other thing just as odd is that it doesn’t act proportional wrt setting a target. Setting 100ma makes it go all the way to full voltage/full speed

But this can have to do with tuning, I think - since it is only estimated current, and not measured, then if the values you use for KV, resistance, etc diverge even slightly from the real ones then the calculation will be off. So while you think you’re setting 0A actually the BEMF compensation turns out slightly positive and you have a current.
So the way I read it, the values are slightly off, and if you adjust them (if that’s possible, the dynamics of the system may make it impossible, not sure) a bit you might find the point where it just coasts to a stop.

But if actually stopping the motor is the objective, then you could do this differently in this mode - either via active control from a higher layer, or by “applying the brakes” - e.g. switching the FETs into Hi-Z or opening the low sides.

Setting a higher current should make it reach full speed faster… the point is with current control + BEMF compensation, the controller will raise the voltage to keep the current at 100mA - even in the presence of BEMF.
So since there is always 100mA current, there is always torque, and the motor always accelerates (until it hits the voltage limit). Setting higher currents just makes this happen faster, but in theory even if you set just 0.1mA of current in this mode, it should gradually get faster and faster until it hits the max voltage.

I ended up not worrying about this too much because the motor works great in velocity and angle mode… I guess those controllers are better at controlling the torque than I am :slight_smile:

1 Like