Open byDagor opened 4 months ago
Hey @byDagor , I'm having trouble reproducing this behavior, what is the arduino-esp32 version that you're using?
So I've done some testing on this issue today and I'm having trouble understanding where the problem comes from and why this new code solves it. :D
Basically, as the phases A,B and C of the motor (both 3pwm and 6pwm) are synced, there is no need to do interrupt for every one of them separately, one is enough. Additionally, eve if you enable interrupts on all of them they are just gonna fire at the same time (but they are gonna fire the same interrupt calling the same function only once).
I've tested this in my code and both in case of enabling one or two phases the interrupt is called only once per pwm cycle, but the status flags mcpwm_intr_status_0
and mcpwm_intr_status_1
are both in 1 if both phase interrupts are enabled.
I've so far only tested on my scope. So what I can see in my scope, both your new implementation and the old one have exactly the same behavior. Updating the same registers and at the same time.
Here is the comparison on by scope
mcpwm0_isr_handler
is called. adcRead
for phase current 1adcRead
for phase current 2
Old code:
New code:
The adcRead
function takes around 10us to read the current value which ic pretty terrible. For the pwm frequencies above 20kHz the low-side current sensing will not work well. So if you've been using it with more than that the current readings have probably been done in some part during the part of the PWM where the high side is on.
Here is the 20kHz PWM - for 0.5 duty cycle (the center) its already almost entering the high-side active part of the duty cycle - this is not good. For any non-zero phase voltage the adcRead
will enter this period.
And 25kHz PWM, it is even worse. Even for 0 phase voltage the adcRead
enters the high-side active PWM period.
I have no idea why the new code has solved the issue though. This issue will need further investigation.
Describe the bug Sometime after SimpleFOC2.2 a bug was introduced that made the phase current reading bad, the symptoms were bad stability and noisy FOC Torque mode. The phase currents looked discontinued instead of a smooth sinusoidal wave.
Describe the hardware setup For us it is very important to know what is the hardware setup you're using in order to be able to help more directly
Narrowed down the bug to this function:
Different from the previous implementation, timer1 does not appear to be used. This produces discontinuous current measurements in a center aligned PWM 3 or 6 driver because all readings will only be synced to phase A.
I wrote a simple patch that works for my two phase system, it's MISSING the logic to understand if a third phase is being used.
And changing the following function to ensure we use timer1: