Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Inav 8.0 RC3 Airplane bumpiness #10536

Open
kasatka60 opened this issue Dec 15, 2024 · 152 comments
Open

Inav 8.0 RC3 Airplane bumpiness #10536

kasatka60 opened this issue Dec 15, 2024 · 152 comments

Comments

@kasatka60
Copy link

Copied the settings (diff all) from inav 7.1.2 and pasted them into inav 8.0 RC3.
In navigation modes the plane flies unstably.
https://youtu.be/n69w9CDaM8Q
(OSD is a little out of sync)
There is no SD card on board.
Maybe I configured something incorrectly when transferring the settings?
INAV_7.1.2_cli_DOLPHIN_20241215_124916.txt
INAV_8.0.0_cli_DOLPHIN_20241215_150820.txt

@kasatka60 kasatka60 changed the title Inaм 8.0 RC3 Airplane bumpiness Inav 8.0 RC3 Airplane bumpiness Dec 15, 2024
@breadoven
Copy link
Collaborator

breadoven commented Dec 15, 2024

Try adjusting the following settings which may be affected by changes in 8.0:

set nav_fw_pos_z_p = reduce to 30 or lower
set nav_fw_pos_z_i = probably OK as default
set nav_fw_pos_z_d = probably OK as default
set nav_fw_alt_control_response = new setting, could be increased closer to 40

See also #9471.

@kasatka60
Copy link
Author

Okay. I'll try to check in a week, weather permitting.

@kasatka60
Copy link
Author

It would be nice to add this description when switching from previous versions to the new one.

@kasatka60
Copy link
Author

Are these universal settings or do have to select the settings for each aircraft yourself?

@breadoven
Copy link
Collaborator

breadoven commented Dec 16, 2024

It would be nice to add this description when switching from previous versions to the new one.

Yes, it seems to have been missed and should be added, probably to the Important Changes section @mmosca.

Are these universal settings or do have to select the settings for each aircraft yourself?

Hard to say. I've used the same settings as yourself for PID on a conventional plane and flying wing and not really noticed any pitch instability. I also increased nav_fw_alt_control_response to 50 without issues, just better altitude change response. Others have had bad instability like yourself. It might depend on other setting affecting pitch as discussed in #9471.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Dec 18, 2024

Before we merge the changes in #10541 I would really like to see a blackbox log of that flight.
The frequency of the oscillation looks to me like a too high FF on pitch, that can be the result of a bad autotune or too much control surface throw resulting in a stall during autotune. Especially the Dolphin with its swept forward wings is sensitive to that.

I am hesitant to change the altitude PIDs too low as usually no one tunes them afterwards and too soft values can result in issues with WP missions or Autoland.

@breadoven
Copy link
Collaborator

Before we merge the changes in #10541 I would really like to see a blackbox log of that flight. The frequency of the oscillation looks to me like a too high FF on pitch, that can be the result of a bad autotune or too much control surface throw resulting in a stall during autotune. Especially the Dolphin with its swept forward wings is sensitive to that.

I am hesitant to change the altitude PIDs too low as usually no one tunes them afterwards and too soft values can result in issues with WP missions or Autoland.

The current altitude PIDS are for altitude control based on position though whereas the altitude control in 8.0 is now based on vertical velocity instead. It uses the same PID controller but with velocity error rather than position error. The basic PID tuning factors:

navPidInit(&posControl.pids.fw_alt, (float)pidProfile()->bank_fw.pid[PID_POS_Z].P / 100.0f,

were corrected to take account of this by changing them from 10 to 100. This is based on the technical difference in required values that falls out from switching from position to velocity and also on what seemed to work from testing. The basic tuning factors weren't fine tuned any further. So it's likely the current default PIDs could be better tuned compared to previously. Reducing P fits in with what @Jetrell found from testing and others so it shouldn't be too much of an issue. It would be useful if @kasatka60 could test with lower P values to see if it helps fix the issue in this case confirming this is what's wrong. Is the Dolphin a bit pitch sensitive, seems to be the plane that others have had issues with ?

@kasatka60
Copy link
Author

kasatka60 commented Dec 18, 2024

Before we merge the changes in #10541 I would really like to see a blackbox log of that flight. The frequency of the oscillation looks to me like a too high FF on pitch, that can be the result of a bad autotune or too much control surface throw resulting in a stall during autotune. Especially the Dolphin with its swept forward wings is sensitive to that.

I am hesitant to change the altitude PIDs too low as usually no one tunes them afterwards and too soft values can result in issues with WP missions or Autoland.

Inav 7.1.2
set fw_p_pitch = 15
set fw_i_pitch = 5
set fw_d_pitch = 5
set fw_ff_pitch = 231
Flight on version 7.1.2. No problems with pitch.
https://youtu.be/BA9YSCzN8ro (no osd)
I'll try to fly with the black box this weekend. Weather permitting.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Dec 18, 2024

Alright guys in this case lets see the blackbox and @kasatka60 ideally you fly with current values one more time, then with the changed values as breadoven said. Just to 100% exclude any PIDFF tuning issue. Its the fast oscillation in your clip above that throws be off a bit. Especially as no one else noted that issue so far.

If the new defaults for vertical velocity pids work well and don't lack of precision (it would be bad if we have a 5m altitude error that takes 1km to correct), I am fine. I wish I had known about the necessary default changes to do more focus testing beforehand.

@Jetrell
Copy link

Jetrell commented Dec 18, 2024

@kasatka60 Just inquiring. Did this value fw_ff_pitch = 231 come from an Autotune ? I'd be interested to know the setting value you have for pitch_rate. My Dolphin's FF is nothing like that high... What @b14ckyy has said does have validity.. Incorrectly tuned pitch FF and rate will certainly add to the effect.

it would be bad if we have a 5m altitude error that takes 1km to correct

@b14ckyy Lets not loose track of the fact this controller operates on a different method.. No need for the sarcasm. Its disrespectful towards @breadoven's work.
When tuned correctly, It acquires the target more quickly and doesn't experience the same initial altitude overshoot the Z position controller did.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Dec 18, 2024

Sorry it was not meant to be sarcastic. Just somewhat exaggerated. I understand that the method needs new values. I just want to mess these defaults up based on a plane that is completely out of tune elsewhere and make it worse for everyone else.

I am all in for good values but they should be flown and tested on at least well autotuned planes. Then we can still tweak them somewhat conservative from there. But they should not cover up a completely messed setup.

@kasatka60
Copy link
Author

@kasatka60 Just inquiring. Did this value come from an Autotune ?

Values ​​obtained as a result of autotune.

@Jetrell
Copy link

Jetrell commented Dec 19, 2024

Thanks @kasatka60
The pitch feedforward on my two Dolphins are 90 and 110. Derived from autotune...
But our control throws would have to be different, as would have been the airspeed/throttle the autotune was conducted at, to see such a large difference between our two settings.

Being that autotune can set such a drastic difference in feedforward and likely rates too, on the same model, is interesting to see. That would mean any small oscillations from over tune of the nav_fw_vel_z controller gain, would be essentially increased by the stabilization controller with a less than optimal feedforward and rate tune.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Dec 19, 2024

Is that like a pat on the back, then a slap in the face towards Breadoven and myself. In saying we know nothing about testing and tuning aircraft ?

Mate you are interpreting too much into here. I am talking about the Setup of the poster that apparently has a completely out of tune setup. Such a case should not be the reference.

So my question here is, if not answered already. Have all your tests in the last 12 months been stable and precise on the current defaults or did you have to reduce them to values close to here: #10541 ?

The main reason why I wanna know that is, because for years we set nav_fw_pos_z_p based on the old controller type to 25 for Fixed wing without a tail and 35 for fixed wing with elevator.
So if you tell me that the new default would work great for both plane types in the new velocity control, then we also need to remove that part from the defaults presets and stick with the firmware defaults.

The bigger problem is also, that everyone who Upgrades from 7.1 with a diff, will keep the values from the old preset, even if you change the firmware defaults. As a result, imho this parameter should have been renamed to nav_fw_vel_z_p in the first place if it is important, as this might cause a lot of questions or issue feedback from users.

PS: I skipped through the video posted above. I can't tell for sure what FM was active most of the time but I see possibly a lot of flying in Angle mode and a swinging pitch axis. So after pitch changes the plane waves up and down a few times and then settles. This is an indicator of a overtuned FF. Can only say for sure with the logs.

I had that phenomenon myself especially on my Dart250 since a speed stall due to angle of attack from strong pitch authority can sometimes be unnoticed on a swept forward. So the control output is high but the actual resulting pitch rate stays low in that stall situation. This tunes rates too low and FF too high resulting in what we see.

@Jetrell
Copy link

Jetrell commented Dec 19, 2024

Mate you are interpreting too much into here.

Fair enough.. I just figured you would have read about it all. There is plenty of conversation between breadoven and myself in that PR.. But you must not have. No problems then 👍

So my question here is, if not answered already. Have all your tests in the last 12 months been stable and precise on the current defaults or did you have to reduce them to values close to here: #10541 ?

Many things changed over the year, as we become more aware of possible causes. That was why its merge was held off for so long.
But the answer to your question is yes to it all.. I couldn't have flown my test planes like that in other 8.0 development tests, without lowering the velocity P gain.
Breadoven also made a change in another PR, that altered its P and I correction factor. Which had a noticeable effect on the way nav_fw_alt_control_response worked.. But the P-gain still required lowering.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Dec 19, 2024

@mmosca OK mate I think based on Jetrells report and based on the fact that I also had no issues in my tests with the Configurator preset values of 25 and 35 (the new default would be in the middle) on 5 different planes, I think we can merge the default value change in #10541

I will also remove that value from the presets in configurator. We should add a Upgrade note to the release notes that in case of Oscillation issues, the pilot should reduce that value. Alternatively we rename it as mentioned above?

@breadoven
Copy link
Collaborator

breadoven commented Dec 19, 2024

You're right that adding new nav_fw_vel_z_pid settings would have been the better way to go but I was surprised how much work was needed to make this change so laziness got the better of me and so instead it was decided to leave it as was and work on the basis that the basic PID tuning factors mentioned above could be adjusted so the existing PID settings for nav_fw_pos_z_pid would work OK without retuning. As far as users are concerned these settings affect altitude control which is essentially position control whether it's done using position or velocity derived from position. The old method did control vertical velocity also even though it was using position derived from velocity to do it so that wasn't entirely technically correct either.

And don't forget that if you add nav_fw_vel_z_pid it will have to be retuned anyway so the only benefit would be that it highlights the change and the possible need to retune.

I don't think this is too big an issue so long as people are aware the PID settings might need adjusting if copied across from a previous version.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Dec 19, 2024

Fair enough. In the end only No-Tail Planes are 5 points above firmware default after the change and I guess in most cases it won't even be a problem if the plane is overall tuned well. Planes with tail are 5 points below FW default. I edit the preset, add a note to the release notes and we are good to go.

And for the @kasatka60: When you fly your dolphin again to create a blackbox log, reduce the FF value for pitch to 160 (just a guess on my end based on past experiences) for the second flight and see if its better. We can then compare the logs with your current values and with reduced FF to see if the tune gets better.

@kasatka60
Copy link
Author

PS: I skipped through the video posted above. I can't tell for sure what FM was active most of the time but I see possibly a lot of flying in Angle mode and a swinging pitch axis.

I spent most of my time flying on cruis mode.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Dec 19, 2024

Good to know, so the bumpiness shown above was just occasionally then? Probably after a "harsh" correction?

@kasatka60
Copy link
Author

I haven't adjusted anything yet. I transferred the diff settings.

@kasatka60
Copy link
Author

I ordered a memory card. I'll try flying in rain and snow and write down the logs. Just don't swear.

@kasatka60
Copy link
Author

@kasatka60
Copy link
Author

@kasatka60
Copy link
Author

@breadoven
Copy link
Collaborator

OK so reducing P to 30 doesn't fix the issue. Also I assume the 3rd test was using a nav_fw_pos_z_p of 40 which appeared to initially delay the onset of instability in CRUZ which isn't what you might expect. Unfortunately I can't open any of the log files, they all appear corrupted so it's not possible to understand the PID behaviour.

I did notice though that you have fw_d_pitch = 5 whereas I have it always set to the default of 0. Don't know if this makes much of a difference. You'd think it might help damp the oscillation but maybe not, D seems a little unpredictable sometimes.

And a value for FF of 160 still seems a little high perhaps. The defaults are 70 for a wing without a tail and only 50 for the general setting.

@kasatka60
Copy link
Author

I'll try to flash the firmware again and set it up again. After all, others fly fine, but I'm the only one with glitches.

@kasatka60
Copy link
Author

And a value for FF of 160 still seems a little high perhaps. The defaults are 70 for a wing without a tail and only 50 for the general setting.

Maybe I'm not using autotune correctly?

@kasatka60
Copy link
Author

I tested the mini talon on default settings, so far it flies stably. I haven't done autotune yet.

@kasatka60
Copy link
Author

I haven't noticed any problems at high speed on other planes, but I'll try to double check.

@kasatka60
Copy link
Author

kasatka60 commented Jan 6, 2025

Gusty wind.
-4°
Recovered Reptile Harrier-S1100 after takeoff and collision with tree. No problems with default settings and high FF.
There are no problems at high speeds.
S1100_log.TXT
S1100_diff.txt
https://youtu.be/OGXwen4ErsA

@kasatka60
Copy link
Author

kasatka60 commented Jan 6, 2025

@lowknifedge Can you check my PID settings?
(for wing without tail)
set nav_fw_pos_z_p = 30
set nav_fw_pos_z_i = 5
set nav_fw_pos_z_d = 5
or
(for wing with tail)
set nav_fw_pos_z_p = 25
set nav_fw_pos_z_i = 5
set nav_fw_pos_z_d = 8

@CrunkleFloop
Copy link

CrunkleFloop commented Jan 9, 2025

I'm still getting this issue too on my Crosswind Mini.

Acro fine - Nav modes have violent pitch oscilation.

My settings are:

Pitch rate 100
FF Pitch 125

nav_fw_pos_z_p = 30
nav_fw_pos_z_i = 5
nav_fw_pos_z_d = 5
nav_fw_alt_control_response = 40

I've attached a log from my most recent flight.

LOG00003.TXT

@CrunkleFloop
Copy link

Here's a flight video:

https://youtu.be/9B7iSOMJR6o

@b14ckyy
Copy link
Collaborator

b14ckyy commented Jan 9, 2025

Additional info to @CrunkleFloop's flight:
He did an autotune a while ago that significantly overtuned the plane. But I checked the logs and found the sweetspot when autotune passeed it and we took the FF and Rate values from that sweet spot. So actually the plane is tuned pretty well in normal flying. Not sure why it looks slighly overtuned in the oscillations but I think thats because of the frequency and inertia.

@breadoven
Copy link
Collaborator

breadoven commented Jan 9, 2025

I'm still getting this issue too on my Crosswind Mini.

Acro fine - Nav modes have violent pitch oscilation.

My settings are:

Pitch rate 100 FF Pitch 125

nav_fw_pos_z_p = 30 nav_fw_pos_z_i = 5 nav_fw_pos_z_d = 5 nav_fw_alt_control_response = 40

I've attached a log from my most recent flight.

LOG00003.TXT

You need to reduce nav_fw_pos_z_d, probably 3 or lower. Also reduce nav_fw_pos_z_p if that doesn't help. I'd also increase nav_fw_control_smoothness to 5 or higher if it's still set to the default of 2. If nothing else it makes control inputs so much nicer and smoother. Testing in HITL with a setting of 2 looks completely unrealistic with every manoeuvre an abrupt snap change.

Can you also post a Diff so other settings can be checked. Can't help but think there's too much pitch/throttle coupling with these twin motor planes which is part of the problem, i.e. nav_fw_pitch2thr too high for the thrust available.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Jan 9, 2025

Can't help but think there's too much pitch/throttle coupling with these twin motor planes which is part of the problem

I have doubts about that. Due to throttle smoothing, in his log. the throttle just changes by about +/-5% during the oscillations.

I saw you have a PR open with a potential fix. Can we test that or is there still stuff to do?

@breadoven
Copy link
Collaborator

Can't help but think there's too much pitch/throttle coupling with these twin motor planes which is part of the problem

I have doubts about that. Due to throttle smoothing, in his log. the throttle just changes by about +/-5% during the oscillations.

I saw you have a PR open with a potential fix. Can we test that or is there still stuff to do?

The output to the motor goes from 57% to 86% during the oscillations from the log. Although it is pitching almost +-20 degs so maybe this is to be expected. I take it this is a twin motor plane ? It's odd how this pitching issue affects some planes and not others especially so with this plane given it's a conventional T tail.

The PR can be tested. Should be able to use the last run output https://github.com/iNavFlight/inav/actions/runs/12679674437/artifacts/2404155623

It's mainly setting changes, adjustment has been added for nav_fw_alt_control_response and I've also added nav_fw_pos_z_ff although I'm not sure if that'll help with the pitch instability, mainly helps with the overall response when things are stable.

@CrunkleFloop
Copy link

I'm still getting this issue too on my Crosswind Mini.
Acro fine - Nav modes have violent pitch oscilation.
My settings are:
Pitch rate 100 FF Pitch 125
nav_fw_pos_z_p = 30 nav_fw_pos_z_i = 5 nav_fw_pos_z_d = 5 nav_fw_alt_control_response = 40
I've attached a log from my most recent flight.
LOG00003.TXT

You need to reduce nav_fw_pos_z_d, probably 3 or lower. Also reduce nav_fw_pos_z_p if that doesn't help. I'd also increase nav_fw_control_smoothness to 5 or higher if it's still set to the default of 2. If nothing else it makes control inputs so much nicer and smoother. Testing in HITL with a setting of 2 looks completely unrealistic with every manoeuvre an abrupt snap change.

Can you also post a Diff so other settings can be checked. Can't help but think there's too much pitch/throttle coupling with these twin motor planes which is part of the problem, i.e. nav_fw_pitch2thr too high for the thrust available.

Thanks for looking into. I'll drop nav_fw_pos_z_d to 3. Yes control smoothness was set at 2 so I'll increase that to 5.

I should add that my DVR footage is through a gimbal so there's an element of damping in the footage which is why it looks a little odd.

Diff all attached
INAV_8.0.0_cli_20250109_111227.txt

@CrunkleFloop
Copy link

Yes it's a big twin, 1600mm and weighing about 2.8kg AUW

@breadoven
Copy link
Collaborator

Thinking about it again there may be issues on twin motor planes possibly because they fly faster. I noticed that there is no tpa_rate set up on these planes which isn't going to help at higher speeds. By default it's 0 but it's probably needed when flying faster. See the following for a vague description of it which isn't entirely helpful:

https://github.com/iNavFlight/inav/blob/master/docs/INAV_Wing_Tuning_Masterclass.pdf

The description in the settings is plain confusing but I use values of 20 to 40. You also might need to set tpa_breakpoint .

@Jetrell
Copy link

Jetrell commented Jan 10, 2025

The description in the settings is plain confusing but I use values of 20 to 40. You also might need to set tpa_breakpoint .

@breadoven Fixedwing uses PID throttle attenuation and boost, either side of the breakpoint.
https://github.com/iNavFlight/inav/wiki/PID-Attenuation-and-scaling#airplanes.

@CrunkleFloop Its noticeable from the log, that its producing considerable vibrations. Which is normal to a degree for twins over singles.. And yours being 8 or 9" props at a guess, is more expected.. But the vibrations seen by the (nav)acc and the gyro, for props that size, appear to be at least second order, from the frequency they are appearing at.. And are inducing considerable harmonics on the accelerometer.. More than I see on many 7" copters.
Just asking.. Have you balanced the motors and props on this plane ? And even dynamically balancing both motor and prop together, makes a huge difference.
I'm not saying its the core problem. But it appears to be making it worse in your case.

Also, because the H743 now uses HAL for SDIO card logging. It should be able to handle debugging.. Before your next flight, can you set debug_mode = ALTITUDE

@CrunkleFloop
Copy link

The description in the settings is plain confusing but I use values of 20 to 40. You also might need to set tpa_breakpoint .

@breadoven Fixedwing uses PID thrust attenuation and boost, either side of the breakpoint. https://github.com/iNavFlight/inav/wiki/PID-Attenuation-and-scaling#airplanes.

@CrunkleFloop Its noticeable from the log, that its producing considerable vibrations. Which is normal to a degree for twins over singles.. And yours being 8 or 9" props at a guess, is more expected.. But the vibrations seen by the (nav)acc and the gyro, for props that size, appear to be at least second order, from the frequency they are appearing at.. And are inducing considerable harmonics on the accelerometer.. More than I see on many 7" copters. Just asking.. Have you balanced the motors and props on this plane ? And even dynamically balancing both motor and prop together, makes a huge difference. I'm not saying its the core problem. But it appears to be making it worse in your case.

Also, because the H743 now uses HAL for SDIO card logging. It should be able to handle debugging.. Before your next flight, can you set debug_mode = ALTITUDE

Funny you should mention that as I was noticing the Jello in the footage which it's never done before.

The props were balanced (on a Du-Bro balancer) a while ago so I'll re-check them as something has certainly changed.

@breadoven
Copy link
Collaborator

breadoven commented Jan 10, 2025

OK that Wiki properly describes how the tpa settings work. Not entirely sure boosting the PIDS below the breakpoint would benefit things in this case but it doesn't affect the planes I've tested that have breakpoints of 1400 and tpa_rate of around 30.

I think the main issue here is simply the D term. Not entirely sure why it seems to be so much more sensitive using velocity rather than position other than velocity, and therefore the error, fluctuates much more rapidly than position .

I'm thinking that it makes sense to increase the D term correction factor from 200 to 300 and also increase the default D term setting accordingly for #10541, back to the previous default of 10 which would give an equivalent setting of around 3 with the 8.0 RC3 build. At least that will give reasonable headroom for useful adjustment.

@breadoven
Copy link
Collaborator

@kasatka60 If you test again using 8.0 RC4 can you do it using 7.1.2 settings. It would be useful to check that this issue is fixed for anyone copying across a 7.1.2 Diff to 8.0.

@jaroszmm
Copy link

jaroszmm commented Jan 14, 2025

So, here are three (log #3) is corrupted logs from today.
I flashed RC4, then used diff all from 7.1.2 and the first two logs are from two flights on 7.1.2 settings.
Before, using these settings made RC3 oscillate in cruise a lot.
The other two logs (one seems corrupted but maybe....) are when I used profile part from clean RC3 after a very big autotune, after which in RC3 plane had some oscillations, mostly in turns, but during level flight it was smoothing out after a while. Actually I could not see any difference in performance.
It was a bit windy today, up to 8m/s so this could impact the test but overall it felt okay.

LOG00009.TXT - diff all from 7.1.2
LOG00010.TXT - diff all from 7.1.2 second flight
LOG00011.TXT - this one is corrupted for me, used rates and FF after redoing autotune in RC3
LOG00012.TXT - second flight with new rates and FF from RC3

@b14ckyy
Copy link
Collaborator

b14ckyy commented Jan 14, 2025

I looked at log 9 and 10 so far and that looks great already. on log 10 during loiter it holds altitude with less than 1m error. And that was before the re-tune.

Edit: Log 12 also looks very solid. would be nice to have the DVR as well if you have. But from the log i just see very small fluctuations that seem to be air current changes.

@kasatka60
Copy link
Author

@breadoven I'll try this weekend if the weather doesn't get worse.

@breadoven
Copy link
Collaborator

The last logs for 8.0 RC4 look pretty good. No obvious instability and the altitude drift looks pretty limited also, possibly even better than before using position although that did depend on how well tuned it was.

Still think this can be improved further with improvements to the estimated vertical velocity and better filtering to reduce overcontrol in response to rapid vertical velocity changes. But that can be for a later release.

@CrunkleFloop
Copy link

CrunkleFloop commented Jan 15, 2025

Here are logs from this morning's flight on RC4 using a 7.1.2 Diff all. Much much better however it still goes into oscillation at higher throttle so I'm guessing TPA still required here. Still seems to have vibration despite balanced props so I need to look further into that.

Interestingly the flight behaviour after the oscillation was very unsettling and unstable, it may be that the battery shifted during the roller-coaster section of the flight though. I'm currently making a new arrangement to hold the battery firmly in place in all flying styles.

https://drive.google.com/file/d/1nNUap7gjIcSJQDwsJSj8VYyeHb4cPvQp/view?usp=sharing

@b14ckyy
Copy link
Collaborator

b14ckyy commented Jan 15, 2025

Yeah thats mostply TPA in this case. The normal cruise looks great.

the Plane is slighly overtuned but nothing that matters in cruise but when the oscillations happen the actual rate is more than double of the setpoint at high speed. The Vertical Speed controller is very gentle with its commanded correction but the PIDFF over corrects here.
image

If you see P counter-acting like in this screenshot the red line, this is the main indicator of a overtuned FF. In a perfect world FF would stay 0 when the setpoint is not 0.
image

Also very nice to see here how P fights against FF on every oscillation. But as P by default is very low and additionally gets attenuated by the new I-Term-Lock change, it can't do much anymore :D

image

@CrunkleFloop
Copy link

Wow thanks for the detailed explanation Marc, you're very clever at all this stuff!

I'm trying to learn it as I go.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Jan 15, 2025

Based on your tune I suggest to reduce FF on pitch down to 110, that should be fine. for TPA try a Breakpoint Throttle value of 1600 as you have a high cruise throttle value and a TPA value of 50%, You can then go either higher in 10% steps if it still oscillates or lower of it does not oscillate or feels over-aggressive at low throttle.

@CrunkleFloop
Copy link

CrunkleFloop commented Jan 15, 2025

Went out again, much much better, still oscillates at higher airspeed but nothing like before.

I'll bump up the TPA value to 60%

https://drive.google.com/file/d/1I5KzqUy9grIV_kHIpO7cSaZhxxhFAOid/view?usp=sharing

@b14ckyy
Copy link
Collaborator

b14ckyy commented Jan 15, 2025

Can you for another flight please reduce the log rate to 25%?
I am not sure why your Flight controller is running at 500uS (2kHz) loop time on fixed wing. It should be 1000uS for FW.
But with 50% logging rate that is 1000Hz log rate right now and the SD Card can't keep up. The first log had a few errors but this one now is in a really bad shape. All these boxes are missing data points and the header is also broken.

image

regarding your tune. From the start it looks much better. Setpoint and gyro are on track very very close. At high speed its still quite a bit off. I would suggest to go directly to 70% TPA.

image

Edit:

btw fly also in acro a bit with just a few pitch and roll maneuvers at different speeds.
Just to make sure the TPA does not take away your authority if its actually a pos_z controller tune issue.

@breadoven although the last log is a bit harder to read due to the damage, I think the new velocity based altitude controller can't handle high speeds very well. After his autotune it was also much better with the setpoint/gyro tracking even with the 50% TPA but still starts to oscillate.

Nothing that can't be tuned out but maybe something to consider in the future as higher speeds also result in higher vertical speed on the same AoA change.

@CrunkleFloop
Copy link

Thanks for your help.

No idea why looptime was set to 500, I've now set it to 1,000 and dropped logging rate to 25%

TPA set at 70 now. On to the next flight!

@b14ckyy
Copy link
Collaborator

b14ckyy commented Jan 15, 2025

my concern is just that even after the H7 and F765 SD card fixes, 1000Hz logging rate is right on the edge and might not work with some or many SD cards. 500Hz should be more reliable but now you have 250Hz that should be just fine on any card. And is sufficient for what we want to analyze.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

9 participants