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

Copter: Autotune performance and safety enhancements #26245

Merged
merged 18 commits into from
May 29, 2024

Conversation

lthall
Copy link
Contributor

@lthall lthall commented Feb 17, 2024

This PR attempts to address some of the long term concerns with AutoTune.

  1. Autotune now fails when it becomes clear the aircraft will probably fail to tune well.
  2. The recovery from the rate twitch makes use of the control model to reduce the severity of the ESC command. This should dramatically reduce the chance of desync.
  3. The waiting for level criteria has been adjusted to reduce the chance initial conditions cause problems with the tests.
  4. The practice of sipping a side in an attempt to save time has been removed as it causes aircraft velocity to build. I believe removing this is a net gain in both time and reliability.
  5. Base test angles on ratio's of ANGLE_MAX.

These changes are expected to dramatically reduce crashes due to desync and successful autotune with bad/dangerous tunes.

We will see an increase number of complaints and questions along the lines of "Why did autotune fail to complete" and "Autotune failed with a failed to level error".

Improvements for a future PR

  1. Make the test twitch more consistent on each test by continuing the twitch after the measurement is complete. This will keep twitches symmetrical and reduce the build up of velocity
  2. Update the twitch rate and angle target based on the results of the last four twitches to reduce the number of aborted tests and therefore the total time taken.
  3. Another protection I should add is to stop angle P term increase when negative rates are observed but angle overshoot is small. This will help prevent excessively large Ange P results.

@lthall lthall force-pushed the 20240217_Autotune branch 2 times, most recently from 218ebb2 to 272f8f8 Compare February 17, 2024 10:45
libraries/AC_AutoTune/AC_AutoTune.cpp Outdated Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune.cpp Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune.cpp Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune.cpp Outdated Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune_Multi.cpp Outdated Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune_Multi.cpp Outdated Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune_Multi.cpp Show resolved Hide resolved
Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

The only one that makes me a bit nervous is the failing to level level change. I don't think I have ever done a auto-tune without getting the old warning at least once.

@lthall
Copy link
Contributor Author

lthall commented Feb 17, 2024

The only one that makes me a bit nervous is the failing to level level change. I don't think I have ever done a auto-tune without getting the old warning at least once.

Yeh I found this was a problem when I made it fail. But then I found there was a few bugs that could make this happen when it shouldn't. So I hope both will add up to "all good". We will have to see.

I share your concern though.

@andyp1per
Copy link
Collaborator

The only one that makes me a bit nervous is the failing to level level change. I don't think I have ever done a auto-tune without getting the old warning at least once.

Somehow my reply to this got lost. Yes - I always get at least one "failing to level" error on yaw. Yaw is the problem child. I guess time will tell whether @lthall has managed to get rid of all the gremlins

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

Just some comments

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

Not really fussed with the ratio/SCALE thing, just noting we often using SCALE for the 0-1 scaling values.

libraries/AC_AutoTune/AC_AutoTune.cpp Outdated Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune.cpp Outdated Show resolved Hide resolved
libraries/AC_AutoTune/AC_AutoTune.cpp Outdated Show resolved Hide resolved
@@ -391,14 +387,20 @@ void AC_AutoTune::control_attitude()
test_run(axis, direction_sign);

// Check for failure causing reverse response
if (lean_angle <= -AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD) {
if (lean_angle <= -attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT) {
Copy link
Contributor

Choose a reason for hiding this comment

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

I wonder if we should have this:

Suggested change
if (lean_angle <= -attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT) {
if (lean_angle <= -lean_angle_max_cd()) {

Copy link
Contributor Author

Choose a reason for hiding this comment

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

No, this is where the aircraft is going in the opposite direction to what it should be going. We don't want to wait for it to get all the way out to lean angle max. This threshold can and should be small.

Copy link
Contributor

@peterbarker peterbarker Feb 20, 2024

Choose a reason for hiding this comment

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

Sorry, I wasn't clear in my comment.

I was suggesting breaking out a method:

float lean_angle_min() const {
    return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT;
}

Most of the lines touched in this patch add that multiplication, so make a method for it.

... it might be that these methods would only be used in one place, so perhaps not worth it.

Copy link
Contributor

Choose a reason for hiding this comment

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

I would offer another suggestion. Could we make this a virtual method so that heli and multi can apply different criteria to reverse response and exceeding max lean angle. I left these alone when i first implemented heli autotune but now I don't know if I can make these changes work for heli, especially the 2/3 max lean angle criteria.

libraries/AC_AutoTune/AC_AutoTune.cpp Outdated Show resolved Hide resolved
@@ -797,6 +801,8 @@ void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, floa
tune_d = tune_d_min;
counter = AUTOTUNE_SUCCESS_COUNT;
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
// This may be mean AGGR should be increased or MIN_D decreased
Copy link
Contributor

Choose a reason for hiding this comment

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

This comment should probably make the Wiki @Hwurzburg

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Feb 19, 2024
SP_UP = 4, // angle P is being tuned up
SP_DOWN = 5, // angle P is being tuned down
SP_DOWN = 4, // angle P is being tuned down
SP_UP = 5, // angle P is being tuned up
Copy link
Contributor

Choose a reason for hiding this comment

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

@lthall You shouldn't change the numbering here if you want to change the sequence of the tuning. You change that in the Set_Tune_Sequence method in AC_AutoTune_Multi.h

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I changed it here so it matches the ordering. This is really just to make it easier to read and review the logs.

@bnsgeyer
Copy link
Contributor

@lthall have you ever thought about using dynamic scaling to scale the target response. Not sure if you do this for larger vehicles. I am considering this for heli autotune as it doesn't work well with large vehicles as the requested rates are too much for larger vehicles. Dynamic scaling, like Froude scaling, would allow the user to set a characteristic length and then the code would scale the requested responses. Just thought this might be a consideration for future PRs for autotune. It is on my todo list.

@lthall
Copy link
Contributor Author

lthall commented Feb 20, 2024

@lthall have you ever thought about using dynamic scaling to scale the target response

Yes. My plan is to calculate the scale from the last X twitches. Each twitch I can measure the acceleration and rate. I hope that by using this to calculate the ideal twitch command I can get a good estimate for the next twitch for those parameters.

I would like to avoid the user having to tell me information to get the scale if I can.

@lthall lthall force-pushed the 20240217_Autotune branch 2 times, most recently from ba0a4ce to 14bef1a Compare February 23, 2024 14:26
@@ -391,14 +389,20 @@ void AC_AutoTune::control_attitude()
test_run(axis, direction_sign);

// Check for failure causing reverse response
if (lean_angle <= -AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD) {
if (lean_angle <= -attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_SCALE) {
Copy link
Contributor

Choose a reason for hiding this comment

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

@lthall you should consider moving these protections to a virtual function so that multi and heli can implement their own protections. At a minimum, all of these new defines should be have multi and heli versions.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

At the moment these are all very close to the original value for the default lean angle max of 45 degrees. I hoped this would be close enough to no change to not impact Heli.

I am not sure how much value there is in me making a copy of hash defines for heli that are identical to Multi. Would you be willing to add a commit or follow up PR to address any Heli interface issues?

Copy link
Contributor

Choose a reason for hiding this comment

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

The problem is that 45 deg is no longer the angle max default. So this could have a big impact.

@@ -873,6 +896,8 @@ void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, fl
tune_d = tune_d_min;
counter = AUTOTUNE_SUCCESS_COUNT;
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
// This may be mean AGGR should be increased or MIN_D decreased
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached");
Copy link
Contributor

Choose a reason for hiding this comment

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

we should be using GCS_SEND_TEXT() these days.

@@ -1724,6 +1732,36 @@ void AC_AutoTune_Heli::updating_max_gains(float *freq, float *gain, float *phase

}

float AC_AutoTune_Heli::target_angle_max_rp_cd() const
Copy link
Contributor

Choose a reason for hiding this comment

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

we could copy the comments from the .h to here in the .cpp. It's not a blocker of course.

@tridge
Copy link
Contributor

tridge commented May 27, 2024

failed autotune, QuadcopterX, realflight, 2kph wind, loiter:
http://uav.tridgell.net/tmp/00000034.BIN
this is pretty benign conditions. Maybe LOITER autotune no longer works?

@tridge
Copy link
Contributor

tridge commented May 27, 2024

i think if a later stage fails it shoule be able to save the earlier stage. For example, in above 34.BIN log it failed at yaw stage, it would have been nice to save the roll and pitch that completed

@lthall
Copy link
Contributor Author

lthall commented May 28, 2024

failed autotune, QuadcopterX, realflight, 2kph wind, loiter: http://uav.tridgell.net/tmp/00000034.BIN this is pretty benign conditions. Maybe LOITER autotune no longer works?

image

Yaw failed because the current tune is very close to oscillating.

@lthall
Copy link
Contributor Author

lthall commented May 28, 2024

i think if a later stage fails it shoule be able to save the earlier stage. For example, in above 34.BIN log it failed at yaw stage, it would have been nice to save the roll and pitch that completed

While I agree this would be nice, it is also potentially dangerous. Doing this would be a significant change and would need supporting code to ensure that the test on a switch functionality worked, messages were appropriate and wiki was updated.

This PR is the first simple change.

@peterbarker peterbarker merged commit 0accc61 into ArduPilot:master May 29, 2024
91 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.