Problem with B-G431B-ESC1 Current Sensing

I am using the B-G431B-ESC1, and I’ve been able to get closed-loop control to work decently well. While trying to make it better, I wanted to implement current sensing and the foc_current torque controller. Here is my code:

#include <SimpleFOC.h>

// C:\Users\[user name]\AppData\Local\Arduino15\packages\STMicroelectronics\hardware\stm32\2.5.0\platform.txt
// Changed build.extra_flags= to build.extra_flags=-D HAL_OPAMP_MODULE_ENABLED

MagneticSensorI2C as5600 = MagneticSensorI2C(0x36, 12, 0x0E, 4);
BLDCMotor motor = BLDCMotor(7);
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.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
float targetSpeed = 0;

Commander command = Commander(Serial);
void doMotor(char* cmd) { command.motor(&motor, cmd); }

void setup() { 
  // init magnetic sensor hardware
  as5600.init();

  motor.linkSensor(&as5600);

  driver.voltage_power_supply = 16;
  driver.init();
  motor.linkDriver(&driver);

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

  // current sensing
  currentSense.init();
  // no need for aligning
  currentSense.skip_align = true;
  motor.linkCurrentSense(&currentSense);

  // aligning voltage [V]
  motor.voltage_sensor_align = 3;
  // index search velocity [rad/s]
  motor.velocity_index_search = 3;

  // Control loop setup
  motor.controller = MotionControlType::angle;
  motor.torque_controller = TorqueControlType::foc_current;
  //motor.motion_downsample 
  
  // velocity PI controller parameters
  motor.PID_velocity.P = 0.2;
  motor.PID_velocity.I = 20;
  // default voltage_power_supply
  motor.voltage_limit = 8;
  // 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 time constant
  motor.LPF_velocity.Tf = 0.01;

  // angle P controller
  motor.P_angle.P = 20;
  //  maximal velocity of the position control
  motor.current_limit = 30; // Amps
  motor.velocity_limit = 4; // [rad/s] 5 rad/s cca 50rpm

  Serial.begin(115200);
  command.add('M',doMotor,"motor");
  motor.useMonitoring(Serial);

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

  Serial.println(motor.zero_electric_angle);

  Serial.println("Motor ready!");

  _delay(1000);
}

void loop() {
  as5600.update();
  float pot = (float)analogRead(A_POTENTIOMETER);
  float target = ((-(pot-(1023/2))/100)*3)/5;

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

  motor.monitor();
  command.run();
}

Even when I comment out everything besides the initialization line LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT); , I still get the following error:

c:/users/jb1ds/appdata/local/arduino15/packages/stmicroelectronics/tools/xpack-arm-none-eabi-gcc/12.2.1-1.2/bin/../lib/gcc/arm-none-eabi/12.2.1/../../../../arm-none-eabi/bin/ld.exe: C:\Users\jb1ds\AppData\Local\Temp\arduino\sketches\B5591D0D06726E0579F61F27F8B05ECE\libraries\Simple_FOC\current_sense\hardware_specific\stm32\b_g431\objs.a(b_g431_mcu.cpp.o): in function `_configureOPAMP(OPAMP_HandleTypeDef*, OPAMP_TypeDef*)':
b_g431_mcu.cpp:(.text._Z15_configureOPAMPP19OPAMP_HandleTypeDefP13OPAMP_TypeDef+0x22): undefined reference to `HAL_OPAMP_Init'
c:/users/jb1ds/appdata/local/arduino15/packages/stmicroelectronics/tools/xpack-arm-none-eabi-gcc/12.2.1-1.2/bin/../lib/gcc/arm-none-eabi/12.2.1/../../../../arm-none-eabi/bin/ld.exe: C:\Users\jb1ds\AppData\Local\Temp\arduino\sketches\B5591D0D06726E0579F61F27F8B05ECE\libraries\Simple_FOC\current_sense\hardware_specific\stm32\b_g431\objs.a(b_g431_mcu.cpp.o): in function `_configureADCLowSide(void const*, int, int, int)':
b_g431_mcu.cpp:(.text._Z20_configureADCLowSidePKviii+0x68): undefined reference to `HAL_OPAMP_Start'
c:/users/jb1ds/appdata/local/arduino15/packages/stmicroelectronics/tools/xpack-arm-none-eabi-gcc/12.2.1-1.2/bin/../lib/gcc/arm-none-eabi/12.2.1/../../../../arm-none-eabi/bin/ld.exe: b_g431_mcu.cpp:(.text._Z20_configureADCLowSidePKviii+0x6e): undefined reference to `HAL_OPAMP_Start'
c:/users/jb1ds/appdata/local/arduino15/packages/stmicroelectronics/tools/xpack-arm-none-eabi-gcc/12.2.1-1.2/bin/../lib/gcc/arm-none-eabi/12.2.1/../../../../arm-none-eabi/bin/ld.exe: b_g431_mcu.cpp:(.text._Z20_configureADCLowSidePKviii+0x74): undefined reference to `HAL_OPAMP_Start'
collect2.exe: error: ld returned 1 exit status

exit status 1

Compilation error: exit status 1

As noted in the comment in the third line of my code, I went to C:\Users\jb1ds\AppData\Local\Arduino15\packages\STMicroelectronics\hardware\stm32\2.5.0\platform.txt and changed build.extra_flags= to build.extra_flags=-D HAL_OPAMP_MODULE_ENABLED.

Any help is greatly appreciated, thank you,
Joseph

Hey,

so the compile error is definitely caused by the missing -DHAL_OPAMP_MODULE_ENABLED flag. If you’ve added it, its not in the right file or otherwise not being read. It may also help to update the STM32 platform to the newest version if you haven’t already.

But you should also remove the as5600.update();, the sensor update is already done in the loopFOC function. You should not update the sensor more than once per loop iteration or the interval will be too short.

Also, I don’t think you can use analogRead(A_POTENTIOMETER); together with current sensing. On the B-G431-ESC1 I think you can read the board voltage and the potentiometer using the current sensing code. There should be some examples in the other B-G431-ESC1 related threads in this forum.

Thank you! I realized that in the file directory for my arduino project I needed to create a file named build_opt.h. I just put the -DHAL-OPAMP_MODULE_ENABLED flag in there and it worked. I removed the as5600.update() from the loop and that definitely helped. Also, I confirmed you are correct about the analogRead(A_POTENTIOMETER) and current sensing not working together. I have it successfully set up with SimpleFOCStudio, and now I’m in the process of tuning. Tuning is going well, I think I’ve found good values for the velocity and angle PID’s, but I’m getting 2 weird behaviors. Firstly, when the motor is spinning at a low speed, it the velocity seems to oscillate between slower and faster. I am counting 14 times in a full rotation, and my motor is a 7 pole-pair motor, which leads me to believe it is something related to the poles. Secondly, when I am running the motor in either angle or velocity control, the motor almost always makes a clicking sound at any multiple of 2pi. This happens less at faster speeds but is still present. What exactly is causing these two behaviors, and what parameters can I tune to remove or mitigate these behaviors?

Thanks!

The clicking sounds are quite hard to track down, in my experience. If it’s not a problem for you I wouldn’t mess with it. I discovered several clicks and pops of different origin and posted about them elsewhere. The velocity at low speed is always prone to going faster or slower for various reasons in torque mode. One of the reasons is beat frequencies, the program runs at a certain speed and thus samples the angle at a certain rate, but the angular error between the actual position and sensor changes depending on the position of the rotor. Thus, the interaction between the two can affect the average apparent difference between the electrical and physical angle, for instance.

I see, thank you! It seems that the oscillating velocity at low speeds is possibly related to another problem. after some further testing, I’m seeing that I can’t quite run the motor at a target velocity lower than 0.8. At a target velocity of 0.8, the motor’s velocity varies substantially, almost stopping 14 times throughout a rotation. One thing I haven’t tuned yet is Current q PID and Current d PID. Could the solution be here? When it comes to these PID controllers, I’m not quite sure what to look for when tuning.

Hi,

So the velocity variations are almost certainly due to what is called “cogging”, which is due to the fact that the magnets can’t align perfectly - throughout a full rotation there are areas where the magnetic fields interact more strongly and more weakly. That fact that you see 14 such effects on a 7PP motor is almost certainly down to cogging.

You can do a certain amount of tuning with the PID and LPF settings, and adding a load to the motor usually helps too (inertia). Cogging is generally worse on an unloaded motor.

But if a motor exhibits strong cogging it’s usually down to the design of the motor, and there’s only so much you can do.
You could write some calibration code to compensate for cogging, but it’s currently not something we offer in the library…

The clicking is another story… can it be due to physical reasons (often the culprit is a screw which has been screwed too far into the motor, and touches against some moving part once per rotation)?

I ordered a new motor a while ago and I should have it soon. It’s still a 7PP, but I’ll see if it still exhibits the cogging and clicking. I’m in the process of designing a 3D printed gearbox for the motor, so hopefully that load helps out with the cogging as well. I experimented with adding a load, and I noticed the motor behaved quite a bit differently. Would it make sense to require different PID tunings for the motor under load?

Yes, you may find you need to adjust the PID tuning when you load the motor… generally though it should be ok with the original values.

Let us know if the new motor improves things!

I’ll update when I get and test out the new motor. Thanks!

Regarding the clicking noise I have it also using FOC Current… If I use voltage it’s not there. Sometimes it disappears and other times it returns. I noticed if I drop the current q and d PIDs down to 0.5 and 50 it’s almost gone. It’s being introduced from the controller. On the scope measuring the supply each time it makes a clicking noise it shows up. If I make the board busy, such as using motor.monitor(); it becomes worse. My next plan is to lower my encoder resolution and see how it goes. I’m also going to try measure the speed of the loop and see where I’m at. It’s not good as the click creates small vibrations.

That’s interesting. I assume then it also does not happen in velocity or position mode? That, along with your PID tuning test would indicate it is caused by the current PID.
But I would say it is not unlikely that the problem is on the input side to the PID - the B-G431-ESC1(that’s what you’re using, right?) has a complex analog in setup using the op-amps. Perhaps there is something not quite right with the configuration there. Clicking sounds like there is perhaps a discontinuity in the current measurement, thereby leading to a sudden, large response in the PID? Is it possible there is a 0-reading mixed in with the actual readings every so often, for example because the duty cycle is too low to permit the low-side measurement to be taken?

I noticed the same thing, that in voltage mode the clicking did not happen. When I get the time I’ll work on tuning the current PIDs and see if I can have any success. I’m using SimpleFocStudio, which uses the motor.monitor() function in the main loop, so I’ll see if not running that function also helps. What sensor are you using? I’m using the AS5600 over I2C, which already has relatively low performance. When you had the clicking, did it take place at the sensor’s zero point?

@runger it happens in both velocity and angle. For me it’s at higher rev, anywhere from 100 rad/s and it get’s louder as revs are higher. I thought it might be missed encoder counts because it’s at higher RPM, but if it’s missed counts this would mean the electrical angle would become incorrect since the sensor has to be synced at all times. Yes I’m using the B-G431-ESC1.

For me the duty cycle is not low as this is happening at higher speeds. What can I check to see if there is bad current measurement?

I don’t need motor.monitor() to use SimpleFocStudio ( when not using the graph )

I gave up on the I2C was to slow for my application… currently using AMT102 which has adjustable PPR. I have no clicking at zero point, only at higher revs.

For some reason I can’t go faster than 200rad/s or it becomes unstable and then will go out of control

Is the B-G431B-ESC1 using the hardware timers for the encoder?

In the data sheet under encoder frequency the max is 42.5MHZ?

For example I run my motor at 2000RPM and my Encoder set to 2048PPR that’s only 68Khz which is well within limits or have I got this wrong? Just try to work if lowering encoder counts will fix the clicking noise because processor busy counting the encoder with interrupts instead of hardware.

Update… I lowered my encoder to 500 PPR and the clicking noise basically went away completely. I have now got the hardware timer encoder working from the driver dev branch and have set encoder back to 2048 PPR and it works perfect, no clicking noises and I can get to 400 rad/s ( was limited to 200 before ) could go more but reached my voltage limit. My Q and D PIDs are now at 0.5 P and 150 I. I think the timer approach for encoder is vital for anything high speed

@Matt303 I’ve seen/heard the same noises when using current control to run a BLDC out runner motor with the B-G431 too. How hard is it to test out your hardware encoder code changes? I’m using amt102 sensor as well.

Also, FWIW, every motor I’ve tried with current sensing active ends up using Iq and Id gains around 2-3 for P, and 150-300 for I.

Hi @wrcman555 It’s all done in the drivers library.

You have to uncomment PB_6 and PB_7_ALT1 in the PeripheralPinsB_G431B_ESC1.c under the timer map section lines 147 and 151

add to your main:

#include "SimpleFOCDrivers.h"
#include "encoders/stm32hwencoder/STM32HWEncoder.h"

//Hardware Encoder for STM32
STM32HWEncoder encoder = STM32HWEncoder(2048, A_HALL1, A_HALL2); // TIM4

Add to your setup:

 //Hardware Encoder Pins
  encoder._pinA = PB_6;
  encoder._pinB = PB_7_ALT1;
  // initialize encoder sensor hardware
  encoder.init();
  // link the motor to the sensor
  motor.linkSensor(&encoder);

In your platformio.ini add to lib dep:

https://github.com/simplefoc/Arduino-FOC-drivers.git#dev

That should get you going using the hardware timer 4 for the encoder

You may also have todo a clean all and then build and upload

2 Likes

Oh wow, lots of progress here! Glad to hear it is now working better!

So I would say the current hypothesis is that the clicks were caused by interrupt/concurrency problems of the interrupt-based encoder? Deku has actually solved the concurrency problems in the dev branch, but the performance problems remain - interrupt processing takes away time from the main loop.

Very glad to hear the HWEncoder is working well for you, I will try to release this tonight so its easier for others to use. Thanks a lot for trying it out!

1 Like

Same happened to me (and we had a discussion on making the HW encoder work properly for this board). The HAL interrupt handling code plus all the Arduino core abstractions create way too much overhead for the interrupt-based encoder to work at high frequencies. I also had cogging above a certain speed, and the motor could not reach its max speed no matter what

Unless one uses the new STM32 HW encoder in the dev branch, the speed on a G431B ESC is limited when using an ABZ encoder

Hi @runger ,
Thank you for the quick action on pushing the new version last night.
I just tried it using the B-G431B-ESC1 and AS5047P (ABI mode). For some reason the encoder is not initialized and the whole setup fails.

This is my code setup:

#include <SimpleFOC.h>
#include "SimpleFOCDrivers.h"
#include "encoders/stm32hwencoder/STM32HWEncoder.h"

BLDCMotor motor = BLDCMotor(21);
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.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
//Encoder encoder = Encoder(A_HALL1, A_HALL2, 1000);
STM32HWEncoder encoder = STM32HWEncoder(1000, A_HALL1, A_HALL2);

float targetSpeed = 0;
//void doA(){encoder.handleA();}
//void doB(){encoder.handleB();}

Commander command = Commander(Serial);
void doMotor(char* cmd) { command.motor(&motor, cmd); }

void setup() { 
  // init magnetic sensor hardware
  // encoder._pinA = PB_6;
  // encoder._pinB = PB_7_ALT1;
  encoder.init();
//  encoder.enableInterrupts(doA, doB); 

Am I off on anything?
Thank you for all you do.