bipropellant / bipropellant-hoverboard-firmware

OpenSource Hoverboard firmware based on Niklas Fauth's one https://github.com/NiklasFauth/hoverboard-firmware-hack
GNU General Public License v3.0
174 stars 74 forks source link

BLDC Control Optimization 2 #32

Closed btsimonh closed 5 years ago

btsimonh commented 5 years ago

New thread.....

lalalandrus commented 5 years ago

We are running closed loop. The phase advance or the commutation shouldn't be overrunning the motor. It also shouldn't be applied to low motor speed. It really does feel that the controller loops needs to be sped up a bit unless @Emanuelferu thinks different.

EFeru commented 5 years ago

Hello again :)

It almost seems like phase advance is happening based on PWML and PWMR rather than speed of the wheel

include "protocol.h"

^~~~ compilation terminated. *** [.pioenvs\genericSTM32F103RC\src\bldc.o] Error 1 In file included from src\hallinterrupts.c:23:0: inc/hallinterrupts.h:26:10: fatal error: protocol.h: No such file or directory

btsimonh commented 5 years ago

checkout git with subrepos!

I tried this morning ensuring that the hall data was read as a single word in hall interrupt, and then used in bldc (copied with irqs disabled). it made no difference.... Hall interrupts detect if a hall change is not sequencial - i have NEVER seen 'HallSkipped' (which would be an indication of misread) - so either we don't get them, or my detection is wrong (table of legal hall changes, which I use for direction).

pushed changes...

Note: changes include measure of bldc time -> 90-100us

display from ascii command 's\n' now like: Main loop interval_us 5001; lates 3, processing_us 807, interval by tick 5, bldc freq 8015, bldc_us 100

ref hall changes, see static const int increments[7][7] and its use i hallinterrupts.c

lalalandrus commented 5 years ago

https://github.com/bipropellant/bipropellant-protocol/tree/81af78b04a4f1b2428137f5964aafe38e690873e

i am not seeing ticks but it is definitely motor slipping as once phase advance kicks in, the torque decreases and the e angle leads the m angle too much. could we do phase advanced limited by pwm but a multiple of speed i.e. min(speed*advance angle, advance_angle[pwm])

EFeru commented 5 years ago

Ok. I manged to ride for the first time the hoverboard with the new control! It is more silent, indeed..

Good thing is that I can reproduce the issues you mentioned:

EDIT: @lalalandrus @btsimonh Since we a have lower frequency, the speed calculation is off. So the switching to sinusoidal control is not ok. So what you need to do is this:

  1. cf_speedCoef = 5333 -- in BLDC_controller_data.c This comes from the formula: cf_speedCoef = round(f_ctrl a_mechAngle (pi/180) * (30/pi)), where f_ctrl = 8000 Hz in this case, and a_mechAngle = 4 deg

  2. Update speed thresholds (they were off anyway, because we were not running the algorithm at 100 kHz) -- in config.h update

    define COMM_DEACV_HI 80

    define COMM_ACV_LO 70

This should eliminate or mitigate the ticking behavior for now.

btsimonh commented 5 years ago

will give them a try :). Do we need to take into account the time from start of routine to end of routine, measured on my board as ~100us?

EFeru commented 5 years ago

The time needed is the Delta time between two BLDC_controller_step() calls. And frequency will be then: f_ctrl = 1/Delta_time.

btsimonh commented 5 years ago

ok, testing. With the new values, it's much better. It is noticeably more 'grindy' at low speed (I think) - maybe it was switching to sinusoidal to early previously? Almost can't fault low speed in terms of misses/ticks. Generally misses/ticks are about the same as our original firmware. If you pick a wheel up, it is quite noisy at higher speed (no load), especially changing speed, as though it's not coping with the wheel inertia. Also, ticks/misses evident even at 'constant' higher speed (probably no change from before)

Notably, I tried it at 16khz, and it's not any different really.

Added commits which set the values in main based on initial measured DMA rate - and also return to 16khz (commented out the return).

lalalandrus commented 5 years ago

New values are better but the slippage is still there at high loads. This behaviour is there with or without phase advance enabled. The old STM uC cannot run at 16khz thats why my first implementation wasnt working and @btsimonh worked, i had to re-introduce the return.

Also @EmanuelFeru a couple things to make hoverboard life easier. 1) Change pwms[i] = CLAMP(dirs[i](sensor_data[i].complete.Angle - sensor_data[i].Center)/3, -FlashContent.HoverboardPWMLimit, FlashContent.HoverboardPWMLimit); to pwms[i] = CLAMP(dirs[i](sensor_data[i].complete.Angle - sensor_data[i].Center)^2/2, -FlashContent.HoverboardPWMLimit, FlashContent.HoverboardPWMLimit);

2) Picture speaks for itself... image

btsimonh commented 5 years ago

haha... @EmanuelFeru asked about my 'hoverboard control' - it really WAS that simple - just driving PWM directly from scaled angle.... :). Will try squaring the angle - have to say did not ride the hoverboard much with the factory firmware.... @lalalandrus - what measured BLDC interrupt time do you get on the original STM32? (i.e. display from ascii command 's\n' now like: Main loop interval_us 5001; lates 3, processing_us 807, interval by tick 5, bldc freq 8015, bldc_us 100)

btsimonh commented 5 years ago

@EmanuelFeru - 1/ did you see the other issue? - @ does not seem to work for you there :(.

2/ actual PWM drive. Whilst investigating the static drive of PWM for slow control, i'm confused about what we are doing. we generate values -1000 -> 1000, which creates a number 10-1990 as a PWM drive. As I understand it, a PWM drive of 1000 into e.g. LEFT_TIM->LEFT_TIM_U produces zero drive on either FET? Numbers below 1000 activate the 'low' fet, numbers above 1000 activate the 'high' fet. My code is driving straight sine values down the PWM for the three windings. I believe your is too.... The windings are Wye connected: picture.

so; when we are near zero crossing, no current will flow into or out of that pin, because it's effectively floating; but are we not assuming it's GND at that point, and can sync current (+ve or -ve}?

found this application note by NXP which describes using saddle waveforms in detail, uses the same PWM style, and Wye connection; will read more and try to understand :). br, s

EFeru commented 5 years ago

1/ did you see the other issue? - @ does not seem to work for you there :(.

Whilst investigating the static drive of PWM for slow control.... a PWM drive of 1000 into e.g. LEFT_TIM->LEFT_TIM_U produces

so; when we are near zero crossing, no current will flow into or out of that pin, because it's effectively floating; but are we not assuming it's GND at that point, and can sync current (+ve or -ve}?

PS: I am about to test the new motor control. I hope the issue at low speed will be fixed.

btsimonh commented 5 years ago

https://github.com/bipropellant/bipropellant-hoverboard-firmware/issues/31

was hoping you saw it and read the bit about separating left & right :). (I did separate them manually, and it worked fine).

EFeru commented 5 years ago

Yes, I saw but I did not have time to answer. I just answered there #31

EFeru commented 5 years ago

F*** one condenser blow-up and caught in fire! It smells like potatoes now. I am not sure if I have such condenser. It will take some time to fix my board :((((

Picture1

EFeru commented 5 years ago

I was just about to test the new control :(((( I just wanted to turn the board on and booom!!

EDIT: Damage:

btsimonh commented 5 years ago

wow! Not seen one quite so destroyed. bitch though.... Were you running different/new firmware, or unmodified at the time? I thought it was not possible to get it wrong if we did not change the low level PWM configuration.... The most basic danger is turning both FETs on at the same time, no? The next after that is just putting full power through the motors.... but it should survive that for a bit. At power on, the PWM should actually be disabled as well.

EFeru commented 5 years ago

yeah, I also don't understand what happened, It I had your firmware on it, but I did ride it yesterday it was all ok and today at the first start boom. I did not have time to do anything else.

lalalandrus commented 5 years ago

You blew c04 which is tied to the 3v3. The way it blew suggest gross OV. You are lucky nothing else broke but I would suggest turning it on with a current limited supply so test if there is something else going on.

btsimonh commented 5 years ago

All my blowups have been my own stupid fault - e.g. putting 36v into a CPU pin, or having a floating bare wire touch something. Check all your cables are secure :).

lalalandrus commented 5 years ago

Also I noticed that there are 4 wires going into the debug header. The read me on nikalaus firmware says don't connect the 3v3 or boards will blow.

EFeru commented 5 years ago

A lot of components blew up actually:

@lalalandrus The 4 wire you see, I only use 3 for programming. the 3.3V I did not connect to the programmer, I just use it for as a power supply for the potentiometers.

btsimonh commented 5 years ago

after looking at control of the wheel, i have realised something. If any of ul/vl/wl are < ~20, the drive for that phase is DISABLED. i.e. every 120 degrees, at a zero crossing, the current on one phase drops to zero, so the other two phases (wye connection) carry equal current, and the motor is attracted to that angle only. This MAY/Probably has an impact on sinusoidal drive, even at speed....

btsimonh commented 5 years ago

hmm, if anyone can interpret the STM32 config in setup.c for the PWM, and tell us why this would be the case. I'm looking at deadtime, but I'm not sure that's it. Surely deadtime just limits the duty cycle to <100%, but does not disable the outputs completely below a certain value?

EFeru commented 5 years ago

If any of ul/vl/wl are < ~20, the drive for that phase is DISABLED.

Could this be the reason of the strange noise? And is there a way to check that the BLDC_controller_step() does output a nice sine wave? PS: I am working on simplifying the algorithm where I can, to get faster calculations.

btsimonh commented 5 years ago

yes, I think so; basically, when it hits near a zero crossing, things will go bad. Still investigating. Really need a 'scope on the PWM signals to understand it. I only found it because I'm driving static values into ul/vl/wl, and not getting the results I expect. I think the step function output is most likely correct.

p.s. I'm trying a saddle waveform, seems to work. p.p.s. bug in sensor read, i think. Rather than do{ ... }while(remaining);, we should while(remaining > 0){ ... }

lalalandrus commented 5 years ago

I might have some time to scope it today.

EFeru commented 5 years ago

That would be nice.

btsimonh commented 5 years ago

I think we may see something like in https://www.st.com/content/ccc/resource/technical/document/application_note/54/0f/67/eb/47/34/45/40/DM00042534.pdf/files/DM00042534.pdf/jcr:content/translations/en.DM00042534.pdf Section 4.2, page 27.

But then this seems to indicate that putting a pedestal on the values would fix it. However, I've tried it, and although it does make some improvement, it's not right. Maybe we have this, but not on all phases? Looks like we have pins for current measurement on U&V +'DC' only?

lalalandrus commented 5 years ago

@btsimonh i think it is right that there is no dead time in the pwm. also this issue is encountered in lots of uC and typically a pedestal both at the top and bottom end for '1' and '0'.

The second zoomed in plot shows blue phase decreasing and increasing (should be zero at the line two squares left of the center mark @ -1ms) without ever hitting zero but the time frame is really short. I have CSV values saved too if someone wants.

The other thing to note that i just noticed is that either yellow or green should be hitting max at some point in this plot but it fails to do so either.

scope_3 scope_4

EFeru commented 5 years ago

Hi @lalalandrus , I think is correct not to see full 100 % pwm in the sinusoidal method. This is because the saddle shape. What you have I think corresponds to what I see in simulation. What I don't see is the 0 % regions as in simulation. Do you show the phases or the pwm commands on the mosfets? (in the plot below from simulation I show the mosfet pwm).If those are the Phases not the mosfet pwm then is correct. All the phases are always powered.

image

lalalandrus commented 5 years ago

I scoped the three power leads to the motor directly. Each channel is a phase. The blue should have been having a zero crossing. I did tie the probes to - batt. I have scope plots where the probes were tied to each other but left floating and there is a sine wave but the plot is hard to follow

scope_1 scope_2

btsimonh commented 5 years ago

@lalalandrus -

I've got test branches here: https://github.com/btsimonh/bipropellant-protocol and https://github.com/btsimonh/hoverboard-firmware you need both...

look at bldc.c & table generation in ascii_proto_funcs.c It's currently using the true sinusoidal, not my saddle values. See bldc.c it you want to change this. It made little difference to the examination of this particular issue, except saddle has a faster rise time, so the issue was reduced.

Ascii commands: if\n - takes you into an immediate mode called 'fine posn' w/s - increment/decrement fine_posn_360 by degrees. a/d - increment/decrement fine_ampl (note that A/D increment/decrement fine_base - play if you want, but It's not the solution :( - but be awar you should be using lower case).

If you want to play with automated motion: ig\n - takes you into an immediate mode called 'fine speed' w/s - increment/decrement fine_speed - number of degrees added to fine_posn_360 every 40ms. a/d - increment/decrement fine_ampl

Suggest: use command 'if' increase with 'd' to amplitude ~50-60. examine the PWM inputs to the FETs at zero crossing points, using 's' to move through the angles. Note that pressing 'c' will print the actual ul/vl/wl, read back from the timer (-1000). 's' prints the LAST ul/vl/wl values (0-2000). BOTH wheels should rotate. What we want is for the rotation to be smooth and linear, but it is not... Reducing amplitude makes it significantly worse (at about 50-60, the wheels will actually rotate, but the motor will not get hot).

I THINK what we WANT is that a: ul of 1000 will produce a PWM equal on upper and lower, not a off on both. ul of 1001 will produce an unequal PWM equal on upper and lower (may be difficult to detect).

I THINK what we may see is that we have 'off' on both lines for ~980 < ul < 1020.

I did confirm last night that right and left behave the same (was starting to suspect hardware issue!).

ok, I 'scoped it this morning.

Can't see anything strange. All FETS are actively driven all the time. So, it must be down to the pulse widths themselves. I can't measure these accurately on my old 'scope.

But what would be really good would be to measure the pulse widths for inputs to ALL the fets at: fine_ampl = 100 0 degrees, (very little movement at this point) 2 degrees, (very little movement at this point) 4 degrees, (started to move) 30 degrees, (maximum movement per degree?) 32 degrees, (maximum movement per degree?) 60 degrees, (very little movement at this point) 62 degrees, (very little movement at this point) note the ul/uv/uw values for each, and compare?

now I'm thinking it may be down to the deadtime implementation?

p.s. the number of sensor misreads changes significantly as I change the angle. This makes me think that the noise in the system varies.

btsimonh commented 5 years ago

p.p.s. more 'scoping with signal ground rather than chassis... much cleaner. Looks to me like it might be GPIO output configuration. Running 'ig', 1 degree speed, fine_ampl of 6. One FET is given a signal whose duty cycle definately moves. The other FET's signal is not as crisp, and it looks like the drive signal is not getting to where it needs to be fast enough to cause the FET to switch - the duty cycle does not change.

lalalandrus commented 5 years ago

i dont have a serial port to test with as i disconnected all the wires i soldered onto it

but in the code you do clamp the output to within +/-pwm_res-10, i never understood why

LEFT_TIM->LEFT_TIM_U = CLAMP(ul + pwm_res / 2, 10, pwm_res-10); LEFT_TIM->LEFT_TIM_V = CLAMP(vl + pwm_res / 2, 10, pwm_res-10); LEFT_TIM->LEFT_TIM_W = CLAMP(wl + pwm_res / 2, 10, pwm_res-10);

RIGHT_TIM->RIGHT_TIM_U = CLAMP(ur + pwm_res / 2, 10, pwm_res-10); RIGHT_TIM->RIGHT_TIM_V = CLAMP(vr + pwm_res / 2, 10, pwm_res-10); RIGHT_TIM->RIGHT_TIM_W = CLAMP(wr + pwm_res / 2, 10, pwm_res-10); }

btsimonh commented 5 years ago

That just limits the maximums - does not affect the center point, which is 1000. Am about to try with GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; on the drive pins.
was GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;

lalalandrus commented 5 years ago

pwm 0 is not 0% but rather 50% duty cycle if we want one phase to be actually zero LEFT_TIM->LEFT_TIM_V = 0 which it will never get

also i dont know how it affects the pwm but the fast comparator mode is disabled sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;

btsimonh commented 5 years ago

50% duty = 1/2 voltage -> 'relative' zero, able to sync and source current.

lalalandrus commented 5 years ago

i forget that they gpio is configure to be complimentary pairs, but it still isnt completely off during the zero crossing

why is the output clamped max btw? is this just a copy of nikalus' code?

btsimonh commented 5 years ago

yes, did not want to change anything which could result in smoke.

ok, thoughts required:

I created a new table:

    for (int i = 0; i < 360; i++){
        table_360[i] = (int)(sin((( ((double) i))/180.0)*MY_PI) * 1000);
        if (table_360[i] > 0) {
            saddle_sqrt_360[i] = (int)(sqrt(((double)table_360[i])/1000.0) * 1000);
        } else {
            saddle_sqrt_360[i] = -(int)(sqrt(((double)-table_360[i])/1000.0) * 1000);
        }
    }

this produces more equal movement per degree than pure sine. This is not based on any science on my part; just on the observation that there was little movement near zero crossing. So I looked for a logical table which would produce more movement near to zero crossing points and came up with this. Thoughts?

btsimonh commented 5 years ago

@EmanuelFeru - maybe you could produce a formula for the ideal saddle waveform? I guess my sqrt-sine is approximating this. My previous saddle had a flat bottom and was based on two sines combined, but I'm sure it was not right. (it was:

        int a = (int)(sin((((double) i)/180.0)*MY_PI) * 2000.0);
        int b = (int)(sin((((double) i+60.0)/180.0)*MY_PI) *2000.0);
        if (a < 0) a = 0;
        if (b < 0) b = 0;
        if (b > a) a = b;
        saddle_360[i] = a-1000;

) I think saddle is required for Wye connected motors, so that the current is sinusoidal?

EFeru commented 5 years ago

This is the script I used to create the Sine wave with saddle shape:

% Create main armonic sine wave a_sinElecAngle_XA = 0:10:360; omega = a_sinElecAngle_XA(pi/180); pha_adv = 30; % [deg] Phase advance to mach commands with the Hall position r_sinPhaA_M1 = sin(omega + pha_adv(pi/180)); r_sinPhaB_M1 = sin(omega - 120(pi/180) + pha_adv(pi/180)); r_sinPhaC_M1 = sin(omega + 120(pi/180) + pha_adv(pi/180));

% Create the 3rd armonic sine wave A = 1.15; % Sine amplitude (tunable to get the Saddle sin maximum to value 1000) sin3Arm = 0.22sin(3(omega + pha_adv*(pi/180))); % 3rd armonic

% Create the saddle sine wave r_sin3PhaA_M1 = sin3Arm + Ar_sinPhaA_M1; r_sin3PhaB_M1 = sin3Arm + Ar_sinPhaB_M1; r_sin3PhaC_M1 = sin3Arm + A*r_sinPhaC_M1;

% Final rounding for representation on integer data type sca_factor = 1000; % [-] scalling factor (to avoid truncation approximations on integer data type) r_sin3PhaA_M1 = round(sca_factor r_sin3PhaA_M1); r_sin3PhaB_M1 = round(sca_factor r_sin3PhaB_M1); r_sin3PhaC_M1 = round(sca_factor * r_sin3PhaC_M1);

This produces: image

btsimonh commented 5 years ago

thankyou! Now I understand the third harmonic involvement! Will try later:
saddle_3rd_harm_360[i] = round((1.15*sin((( ((double) i))/180.0)*MY_PI) + 0.22*sin((( ((double) i*3))/180.0)*MY_PI))* 1000);

EFeru commented 5 years ago

yes, that is indeed in C code. Nicely written!

lalalandrus commented 5 years ago

https://www.digikey.ca/en/articles/techzone/2017/jan/why-and-how-to-sinusoidally-control-three-phase-brushless-dc-motors

Their saddle is a lil sharper. Lookup table included in the code they provide.

Also found this that st provides to generate motor code for our uc https://www.st.com/content/dam/technology-tour-2017/session-2_track-6_advanced-bldc-motor-drive.pdf

EFeru commented 5 years ago

@lalalandrus , yes the saddle shape can be sharper if we sum the main sine wave with a 2nd harmonic (not the 3rd harmonic), i.e.,

saddle_sine2Harmonic = main_sine + (sign(main_sine ) * abs(sine_2ndHarm)) , whereas saddle_sine3Harmonic = main_sine + sine_3rdHarm

image

I was considering using 2nd harmonic as well, but I found that the 3rd harmonic offers more area bellow saddle sine wave (so more torque) and is smooth everywhere. This was my main motivation.

EFeru commented 5 years ago

@btsimonh @lalalandrus There will be a nice update of the controller in aprox. 2-3 days ;) :) In beta testing and calibration these days. Just did:

btsimonh commented 5 years ago

@EmanuelFeru good to hear that you have working hardware again! Question: does anyone else interpret #define PWM_FREQ 16000 // PWM frequency in Hz as meaning our PWM freq is 16khz - only double the rate we're currently changing the values at? This is something I would not like to change in case of smoke - so any STM32 experts out there got any comments? Does this freq DRIVE our ADC DMA freq (to synchronise ADC reading with PWM?), by the ADC sample trigger being slaved off the PWM trigger? (makes sense if we wanted to read BEMF current....)?

EFeru commented 5 years ago

I had a back-up hoverboard and I took the motherboard out :) I am still waiting for the parts to fix the broken one. About the PWM_FREQ 16kHz is it double or the same?

btsimonh commented 5 years ago

(half because we're just returning every other DMA interrupt to reduce us to 8khz.... - yes the DMA interrupt is 16khz.)