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

AP_Control: change autotune I determination for Roll axis #21027

Merged
merged 1 commit into from
Jul 25, 2022

Conversation

Hwurzburg
Copy link
Collaborator

@tridge as discussed.....autotuning all my planes showed that for flying wings, often the P value will be small (1/10 to 1/4 of FF) compared to the resulting FF, leading to I being set too high and slow oscillations in roll occuring....since is probably due to the roll axis not having any inherent damping like the pitch and yaw axes do in a plane....and flying wings typically have larger FF terms compared to normal aileron equipped planes...lowering I to equal P or 2xP reduces the wobble to levels not excessive in FPV views...

anyway, here is the PR so you and Leonard can discuss...

@Hwurzburg Hwurzburg requested review from lthall, tridge and priseborough and removed request for lthall June 23, 2022 20:04
@priseborough
Copy link
Contributor

@Hwurzburg I'm confused by the following comment in your description

"probably due to the roll axis not having any inherent damping like the pitch and yaw axes do in a plane"

In my experience, flying wings usually have similar roll damping to conventional planes with the same sweep, span and aspect ratio once the elevon mixer gain is taken into account. It is the pitch axis that is usually more lightly damped.

It is possible the effect you are seeing is due to the combination of wing sweep and lack of yaw static margin (yaw weather vaning) resulting in a lightly damped dutch roll motion. I would be interested to see a log.

@Hwurzburg
Copy link
Collaborator Author

Hwurzburg commented Jul 12, 2022

@priseborough sorry, poor wording....just that the roll axis has no inherent attitude stability but the pitch does...just figured that is why its more susceptible to this 1-2hz roll I got after using the new autotunes on my flying wings, but did not on my conventionals....maybe the dutch roll tendency is the culprit..does not seem to be much yawing during the roll oscillations...but the fix was to lower the I gain closer to P than FF, if FF was large and P low....

here is a log of an autotune, after I had done a crude manual tune on one of my flying wing TVBS which started me on the hunt for solutions: https://www.dropbox.com/s/3ci3m3tsq94ff1i/log_9_2022-6-19-07-54-26.bin?dl=0 the decreased P and increased I resulted in a big slow roll oscillations

after many autotune attempts (with FF results varying from .3 to .1 ) I finally just lowered I and acceptable wobble resulted...

https://www.dropbox.com/s/1lapyliqyy5z0p3/2022-06-21%2007-40-26.bin?dl=0

did this for other flying wings and it improved roll enough not to be a major distraction in FPV video, although still not perfect

whatever the reason, it seems pretty consistent ....I did not notice this with the previous autotune method on any of my 15 or so planes except one which did have noticeable dutch roll after conversion to a flying wing TVBS, which I had cured with additional fins

autotuning my conventional wing planes did not result in roll oscillations with the new scheme so it might be dutch roll related, or that they have a little dihedral and some positive roll attitude stability...dont know ...the reason isnt important to me, just the results

@priseborough
Copy link
Contributor

priseborough commented Jul 15, 2022

@Hwurzburg Thanks, that makes sense TXS. With wing sweep, even small amounts of yaw can produce a significant rolling moment that is out of phase to the aileron input and produces a loss of phase margin in the aileron control for roll loop. The I term also reduces phase, so reducing I will recover phase margin.

I don't see a problem with reducing the default I on the roll loop for most vehicles, but here are some instances where a low I can result in the vehicle being very slow to un-bank. I have a log for a believer airframe which was presented at the ardupilot conference - see https://www.youtube.com/watch?v=wa1ueapC37U at 54 minutes from start - where this contributed to a crash. The vehicle that crashed was using the following roll parameters:

PTCH2SRV_RLL 1.100000
RLL2SRV_RMAX 120.000000
RLL2SRV_TCONST 0.300000
RLL_RATE_D 0.000000
RLL_RATE_FF 0.345000
RLL_RATE_FLTD 12.000000
RLL_RATE_FLTE 0.000000
RLL_RATE_FLTT 3.000000
RLL_RATE_I 0.150000
RLL_RATE_IMAX 0.666000
RLL_RATE_P 0.080000
RLL_RATE_SMAX 150.000000
TECS_RLL2THR 10.000000
YAW2SRV_RLL 1.100000

@Hwurzburg
Copy link
Collaborator Author

@priseborough so if I understand the case you show, it was badly tuned (which would not be the case after the autotune that this PR applies to), and the non-control resulted from I term build up that prevented control surface reversal to stop the bank, unless I misunderstood what you said....wouldn't having a lower I gain helped in this situation? reduced the I term windup due to sideslip and been easier to overcome?

@priseborough
Copy link
Contributor

No, higher I gain would have re-trimmed faster after releasing stick.

@priseborough
Copy link
Contributor

priseborough commented Jul 23, 2022

I've had a further look at your log and the log I analysed at the conference and think this change is probably safe because if I gain becomes too low and the vehicle loses directional control, the user can abort auto-tune.

In the log you supply the autotune is estimating an excessive FF gain requirement due to the lag from demanded to achieved roll rate in combination with a small roll angle loop time constant. This is vulnerability of the exisiting auto-tune algorithm @tridge FYI.

The graphs below show how the combination of a high FF gain and lagged roll response result in a loss of phase margin in the roll angle loop. The phase lag caused by the FF term is similar to the I term so if FF is increased, the then I needs to be decreased or vice versa to maintain the same phase margin.

Screen Shot 2022-07-24 at 9 49 15 am

Roll rate response is laggy and gain from demanded to achieved roll rate is >1 which destabilises the angle loop. The angle loop time constant RLL2SRV_TCONST was too small given the phase lag.

Screen Shot 2022-07-24 at 9 51 28 am

This figure shows the phase lag between roll and yaw rate that is typical of dutch roll and this is typical of flying wings with sweepback due the high sideslip induced rolling moment combined with adverse yaw.

Screen Shot 2022-07-24 at 9 45 11 am

There are some options for detecting and compensating for dutch roll during auto-tune.

Copy link
Contributor

@priseborough priseborough left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This doesn't address the root cause of the auto-tune failure for the supplied log, but does eliminate the possibility of an I gain that is not supported by sufficient P gain.

@tridge tridge merged commit dcde718 into ArduPilot:master Jul 25, 2022
@Hwurzburg Hwurzburg deleted the autotune branch July 25, 2022 23:40
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

Successfully merging this pull request may close these issues.

4 participants