Reading the current using the IC INA4181A2 with a gain of 50 connected to pins W, U, V using a resistor value of 0.001 ohms. Is there a recommended method for reading the total current, or are there any recommended functions? Also, if the current exceeds a certain limit, is there a suggested approach to stop the operation?
Hey @tumelecza , welcome to SimpleFOC!
If you have current sensing configured, you can get the bus current using
current_sense.getDCCurrent(motor.electrical_angle)
This will compute the bus current from the phase currents.
Current limiting is usually implemented in hardware for speed and reliability. A typical solution might use a comparator to compare the amplified shunt signal to a reference voltage. If the reference voltage is exceeded, the comparator switches off the driver. Many drivers have this functionality built-in, while other have break or enable inputs to support it.
On the MCU side, if you’re not working with a dedicated driver, many MCUs support a Break-In input to interrupt the PWM in hardware.
SimpleFOC currently does not support this, you would have to configure it yourself with dedicated code for your MCU.
Implementing this protection based on the current sensing is not the recommended way, because the software is quite slow compared to the hardware, and for sudden current spikes the board may already be destroyed by the time the software gets around to regulating the current down.
But of course you can set a limit in the current PID which will limit current on the software side, just using the normal regulation.
I found the current measurement system very useful, I just implemented a checkwhere it shuts the voltage to 0 if there is excessive current, very useful! Thanks team :). I think it responds within a pretty short time. There is a low pass filter. I can post my code if anyone wants it.
I also used a thermal circuit breaker on the actual motor, they can be had from digikey for $2 or so. Just in case something goes wrong, like a crash or something. I really don’t like rolling my own like this on something that is a basic component. It’s really hard to make reliable stuff. This is one reason I am a big fan of a flagship board, getting everything working and tested on it, which does not exclude by any means other boards etc. of course.
A PTC thermistor is a device commonly used for overcurrent protection, again it is a thermal device so it will not have instant response, however I assume neither will the mosfets be instantly damaged. They reset automatically and are unaffected by power cycling, very simple devices etc. I don’t know how well they work as circuit breakers, they are common on battery packs to shut things down in the event of short circuit.
Here is my code, which includes current sensing and conversion to mA on the b-g431b-esc1 board. It is all open loop, it does not use a sensor. I used it for testing and running a fan motor with a gimbal motor. It takes commands over the serial port and gives info back over serial. The commands have to be a certain numbe of characters or things get complicated. See the code for details.
It implements acceleration and deacceleration as well as ramping the voltage with rpm.
#include <SimpleFOC.h>
// NUMBER OF POLE PAIRS, NOT POLES, specific to the motor being used!
BLDCMotor motor = BLDCMotor(7);
//this line must be changed for each board
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003, -64.0/7.0, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
LowPassFilter diff_filter = LowPassFilter(0.05);
float goal_speed =0;
float v=2;
float v_diff=1;
float accel = 92;// in rads per second per second
float v_per_radsPS = 0.0232;
float accel_v_boost = 0.5;// voltage is increased during acceleration and deacceleration by this amount
bool voltage_override = 0;
float power_figure = 1.5;
float power_coeff = 0.00043;// the serial communicator could actually use an extra digit for this one.
float A, B, C;
float currentlf_now =0;
float prop_V= 0;
float min_V = 1;
float v_limit = 19;
float current_limit_slope = 1.6;// this is in milliamps pre rad per second
float current_limit_o_term = 200;//this is the current limit at zero rps, it may not trip with stall
float maybe_o = 1;
void SerialComm(){
if (Serial.available() > 0){
switch(Serial.peek()){
case 't': Serial.read(); Serial.print("t"); Serial.println(goal_speed); break;
case 'c': Serial.read(); Serial.print("c"); Serial.println(accel); break;
case 'v': Serial.read(); Serial.print("v"); Serial.println(motor.voltage_limit, 4); break;
case 'n': Serial.read(); Serial.print("n"); Serial.println(v_diff); break;
case 'p': Serial.read(); Serial.print("p"); Serial.println(v_per_radsPS, 4); break;
case 'b': Serial.read(); Serial.print("b"); Serial.println(accel_v_boost); break;
case 'o': Serial.read(); Serial.print("o"); Serial.println(voltage_override); break;
case 's': Serial.read(); Serial.print("s"); Serial.println(motor.target); break;
case 'f': Serial.read(); Serial.print("f"); Serial.println(power_coeff, 6); break;
case 'g': Serial.read(); Serial.print("g"); Serial.println(currentSense.getDCCurrent(), 5); break;
case 'i': Serial.read(); Serial.print("i"); Serial.println(get_mA(), 4); break;
case 'j': Serial.read(); Serial.print("j"); Serial.println(min_V); break;
case 'w': Serial.read(); Serial.print("w"); Serial.println(driver.voltage_power_supply); break;
case 'k': Serial.read(); Serial.print("k"); Serial.println(v_limit); break;
case 'y': Serial.read(); Serial.print("y"); Serial.println(current_limit_slope); break;
case 'u': Serial.read(); Serial.print("u"); Serial.println(current_limit_o_term); break;
case 'e': Serial.read(); Serial.print("e"); if (motor.shaft_angle >= 0){
Serial.println(motor.shaft_angle, 3);
}
if (motor.shaft_angle < 0){
Serial.println((_2PI-(-1*motor.shaft_angle)), 3);
}
break;
case 'T': break;
case 'C': break;
case 'V': break;
case 'P': break;
case 'B': break;
case 'Y': break;
case 'U': break;
case 'O': break;
case 'F': break;
case 'J': break;
case 'W': ;break;
case 'K': ;break;
default: Serial.read(); break; //if anything we don't recognize got in the buffer, clear it out or it will mess things up.
}
}
if (Serial.available() >= 9){
switch(Serial.read())
{
case 'T': goal_speed = Serial.parseFloat();break;
case 'C': accel = Serial.parseFloat();break;
case 'V': v_diff = Serial.parseFloat(); break;
case 'P': v_per_radsPS = Serial.parseFloat(); break;
case 'K': v_limit = Serial.parseFloat(); break;
case 'B': accel_v_boost = Serial.parseFloat(); break;
case 'Y': current_limit_slope = Serial.parseFloat(); break;
case 'U': current_limit_o_term = Serial.parseFloat(); break;
case 'O':
maybe_o = Serial.parseFloat(); // just in case the wrong data gets in somehow we don't want the voltage going crazy
if (maybe_o < 1){
voltage_override = 0;
}
if (maybe_o >= 0.999){
voltage_override = 1;
}
break;// if it's not one of these, ignore it.
case 'F': power_coeff = Serial.parseFloat();break;
// case 'W': driver.voltage_power_supply = Serial.parseFloat();break;
// case 'J': min_V = Serial.parseFloat();break;
}
}
}
void overcurrent_trip(){// if it stalls this won't help except at higher powers, probably. Just helps prevent disaster
float current_cap = current_limit_o_term + fabs(motor.target)*current_limit_slope;
if (get_mA() > current_cap){
voltage_override = 0;
}
}
void setup() {
Serial.begin(1000000);
Serial.println("test serial2");
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 24;
// driver.dead_zone = 0.1;
driver.init();
// driver.dead_zone = 0.1;
// link the motor and the driver
motor.linkDriver(&driver);
currentSense.linkDriver(&driver);
currentSense.init();
currentSense.skip_align = true;
FOCModulationType::SinePWM;
motor.voltage_limit = 1; // [V]
motor.velocity_limit = 255; // [rad/s]
motor.controller = MotionControlType::velocity_openloop;
// init motor hardware
motor.init();
motor.voltage_limit = 2;
goal_speed = 2;
}
unsigned long int ticks_diff(unsigned long int t2,unsigned long int t1){ //t2 should be after t1, this is for calculating clock times.
if (t2<t1){//t2 must have wrapped around after t1 was taken
return (4294967295-(t1-t2));
}
return (t2-t1);
}
float get_mA(){// this is the estimated current being drawn from the power supply, not the actual motor current which is a bit different
float x =0;
x = currentlf_now*motor.voltage_limit/24;
return 1000*((4.0384440932900223e-002)+3.4514090071108776e-002*x*30);// this is off by like 12 percent in some cases a polynomial of third order fits the data better but might flake out at higher than 500 mA so I didn't try it.
}
void loop() {
static unsigned long int loop_clock_in = millis();
unsigned long int loop_time = 0;
float loop_time_s = 0;
// unsigned long int inner_loop_time = 0;
loop_time = ticks_diff(millis(), loop_clock_in);
loop_clock_in=millis();
loop_time_s = float(loop_time)/1000;
if (motor.target < goal_speed-(accel*loop_time_s*1.5)){//rps not positive enough
if (motor.target < 0){//counterclockwise rotation, deaccelerating
motor.target = motor.target+accel*loop_time_s*0.7;
motor.move();
prop_V = (v_diff+accel_v_boost+fabs((motor.target*v_per_radsPS))+(power_coeff*pow(fabs(motor.target),power_figure)))*voltage_override;
}
if (motor.target >= 0){ //clockwise rotation, accelerating
motor.target = motor.target+accel*loop_time_s;
motor.move();
prop_V = (v_diff+accel_v_boost+fabs((motor.target*v_per_radsPS))+(power_coeff*pow(fabs(motor.target),power_figure)))*voltage_override;
}
}
if (motor.target>=goal_speed-(accel*loop_time_s*1.5)){//steady run phase
if (motor.target<=goal_speed+(accel*loop_time_s*1.5)){
motor.move();
prop_V = (v_diff+fabs((motor.target*v_per_radsPS))+(power_coeff*pow(fabs(motor.target),power_figure)))*voltage_override; //constant run
}
}
if (motor.target > goal_speed + (accel*loop_time_s*1.5)){ //rps too positive
if (motor.target > 0){ //clockwise rotation, deaccelerating
motor.target = motor.target-accel*loop_time_s*0.7;
motor.move();
prop_V = (v_diff+accel_v_boost+fabs((motor.target*v_per_radsPS))+(power_coeff*pow(fabs(motor.target),power_figure)))*voltage_override;
}
if (motor.target <= 0){
motor.target = motor.target-accel*loop_time_s; //counterclockwise rotation, accelerating
motor.move();
prop_V = (v_diff+accel_v_boost+fabs((motor.target*v_per_radsPS))+(power_coeff*pow(fabs(motor.target),power_figure)))*voltage_override;
}
}
if (prop_V < min_V){
motor.voltage_limit = min_V*voltage_override;
}
else {
motor.voltage_limit = prop_V;
}
if (prop_V > v_limit){
motor.voltage_limit = v_limit;
}
for (int i=0;i<10;i++){ // shouldloop at about 37 khz on b-g431 board
for (int q=0;q<5;q++){
motor.move();
motor.move();
motor.move();
motor.move();
motor.move();
}
// Serial.println(micros()-inner_loop_time);
// inner_loop_time = micros();
SerialComm();
}
currentlf_now = currentSense.getDCCurrent();
currentlf_now = diff_filter(currentlf_now);
overcurrent_trip();
}
Can you draw where did you put this? if these are in between driver and motor it can be bad for the driver if the breaker opens while the driver is driving the motor.
Thank you very much.
I’ve been trying to get the total motor current draw from the G431B board but I can’t get the results to match what I measure with a multimeter.
The code I used is the one @Anthony_Douglas suggested above, with filtering. Thank you for the help already!
currentlf_now = currentSense.getDCCurrent();
currentlf_now = diff_filter(currentlf_now);
My measurements show the following:
Which seems like it would just be off by a factor, but looking at the ratio between the measures, it’s not:
Does anyone have any suggestions of what I could try to debug this?
Thank you very much !!
Motor Current is different than Power Supply or Battery Current.
Thank you! Very interesting! Is there a way to get power supply current?
I think it’s supposed to be something like that:
battery current = (vdid + vqiq) / vbat
Thanks for the suggestion! I’ve had a chance to try that in 2 modes (all in SVPWM voltage control):
Torque FOC
Here, the calculation seems to almost work out, except for some scaling issue. The motor is not allowed to spin and the torque setpoint gradually increased. The term VdId is always 0 in this test.
Velocity FOC
Here, the motor was spinning in no-load conditions. Things are clearly off.
I except that in reality, the motor will be driving a load at speed, therefore I should be getting a combination of both conditions, and the measurement will be off too.
I was thinking more about it yesterday.
The concept behind this formula is the current measured on the motor doesn’t take the PWM duty cycle % into account.
So Vq divided by the power supply voltage * ~0.60 (I missed this factor yesterday) should give you a kind of percentage, that you mutiply by the Iq.
Vd*Iq can be ignored in our case because we aim for 0 Iq.
Also one small discrepancy to take into account is that with your multimeter you are measuring the overall consumption (e.g. buck converter, mcu, … ).
With FOC we measure only the current in the phases.
Where does this come from? I would have expected some kind of time-averaged constant to come out to 0.5
The formula I red came from a discord and is 3 (Vd*Id + Vq * Iq) / 2 Vbat.
Which means 0,6666 of your power supply. I couldn’t find any proper formula anywhere else.
Here you can read that maximum Vq is 0.50 for SinePWM (1/2), 0.58 for SVPWM (1/ √3), but you can reach 0.70 if you overmodulate.
But I thought you cannot reach 0.70 because of the deadtime. (came across about this nice document just now)
So I invented 0,60 lol. Could be anything between 0.6 and 0.7 I guess.
They also have a nice animation:
https://microchipdeveloper.com/motor:overmodulation-viewer
Microchip!
@RaphZufferey Would you be able to compare 3(Vd*Id+Vq*Iq)/2Vbus
to what you get from current_sense.getDCCurrent(motor.electrical_angle)
?
I have the feeling what getDCCurrent returns is the total motor current, not the DC current.
Here are my measurements! I added also Ibus/6 as that seemed to match well in velocity control, but it’s not physically founded. The suggested formula seems to work very well in torque control mode now, but it struggles with no-load velocity control condition.
Ibus is current_sense.getDCCurrent(motor.electrical_angle)
in those plots
But are you comparing Torque mode with load and Velocity mode without load ?
Exactly! That should get me the 2 extremes of no-load and stall behavior.
BTW, I did substract the current draw from the MCU, so these measures capture current draw from the BLDC only.