Oscillation/crash after autotuning single axis

Hi, I finally got my hexacopter decked out with new motors and a new battery. It seemed to be flying fine with the default PID parameters, I had tuned the harmonic notch, and I finally even managed to get autotune (roll) to complete this morning. Happy days! It seemed sane with the new parameters while still in the air and I landed to save them.

2021-04-12 10:38:52.783 ATC_RATE_FF_ENAB 0.000000 -> 1.000000
2021-04-12 10:38:52.785 ATC_ACCEL_R_MAX 84700.000000 -> 25885.230469
2021-04-12 10:38:52.785 ATC_ACCEL_P_MAX 84700.000000 -> 0.000000
2021-04-12 10:38:52.788 ATC_RAT_RLL_P 0.110000 -> 0.027331
2021-04-12 10:38:52.791 ATC_RAT_RLL_I 0.110000 -> 0.027331
2021-04-12 10:38:52.793 ATC_RAT_RLL_D 0.003600 -> 0.001339
2021-04-12 10:38:52.805 ATC_ANG_RLL_P 4.500000 -> 3.225266
2021-04-12 10:38:52.807 MOT_THST_HOVER 0.172353 -> 0.169050

I recharged the battery and just went to launch to calibrate pitch and yaw. Unfortunately as soon as I left the ground there were huge oscillations and the copter is now busted.

I’d appreciate any suggestions please. I’m suspicious about the feedforward being enabled and the ATC_ACCEL_[PR]_MAX parameters. For instance, why did it change ATC_ACCEL_P_MAX when I only tuned roll… any why set it to zero?

Thanks in advance.

log_55_2021-4-12-12-33-08.bin (192 KB)

This isn’t going to work regardless as to how it got there:
ATC_ACCEL_P_MAX,0
And the Roll Rate P/I are certainly too low.

So you have a very bad baseline.

Thanks Dave. They are the parameters that were changed during the autotune flight.

I did expect the P&I to be reduced from default, it has 6x 14" 630Kv on a ~3.5kg total airframe. Whether it went too far… maybe? But could that cause oscillations? It behaved itself during pilot test after the autotune completed. Plot of the test attached, NB: I had only tuned roll.

Here’s the log from the autotune:
https://ozforecast.com.au/temp/log_54_2021-4-12-10-39-06.bin

Autotune wouldn’t set ATC_ACCEL_P_MAX to zero. I would guess you entered that value by mistake while updating the Initial Tuning parameters. .027 for Roll Rate P/I looks way off. You may want to start over.

I didn’t touch any of the parameters during that flight - the list above is a ‘paramschange’ from MAVexplorer for anything in the log that changed between arming and disarming.

I’ve only had a super quick look - need to run to a meeting. But it looks like it sets the accel_max to zero, but then only sets it to the new value if the axis is selected for autotune. @rmackay9

// load_tuned_gains - load tuned gains
void AC_AutoTune::load_tuned_gains()
{
    if (!attitude_control->get_bf_feedforward()) {
        attitude_control->bf_feedforward(true);
        attitude_control->set_accel_roll_max(0.0f);
        attitude_control->set_accel_pitch_max(0.0f);
    }
    if (roll_enabled()) {
  ..
            attitude_control->set_accel_roll_max(tune_roll_accel);
    }
    if (pitch_enabled()) {
..
            attitude_control->set_accel_pitch_max(tune_pitch_accel);
    }

For what its worth vibrations were slowly ramping up throughout the entire flight until they went haywire. I have had bad vibrations give me very low autotune values in the past.

Hi Manav. Do you mean the vibration in the log_55 file? That is just a couple of seconds of log when the drone was oscillating wildly, so I am not reading too much into that.

The vibration seems to have been reasonable (mostly <30) and stable during the ten minute autotuning flight.

I’m interested to hear people’s thoughts, but am not so worried by the low gains that autotune found at this stage, the drone has a 4.9:1 thrust to weight ratio (ecalc) and I expected quite low gains from autotune.

When I get it flying again I’ll reset the ATC_ACCEL_P_MAX and try turning the FF off and see how it goes.

Pretty sure 0 means no limit - so it will work but might induce more stress than you want on a larger copter.

ATC_RATE_FF_ENAB 

Is set to 1 on all my tunes, so not sure whether that is the problem.

Ahh thanks Andy.

Yes 0 is disabled - although curiously this disables the acceleration limit from being applied on all axes:

// translates body frame acceleration limits to the euler axis
Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const Vector3f &euler_accel)
{
...
    if (is_zero(euler_accel.x) || is_zero(euler_accel.y) || is_zero(euler_accel.z) || is_negative(euler_accel.x) || is_negative(euler_accel.y) || is_negative(euler_accel.z)) {
        rot_accel.x = euler_accel.x;
        rot_accel.y = euler_accel.y;
        rot_accel.z = euler_accel.z;
    } else {
...
    }
    return rot_accel;
}

By the way I’ve raised a github issue for this:

Cheers.

I think you have misread the code - it merely copies the values across if any are 0, it does not set to 0 ones that are not 0

If any are zero, it copies the accelerations without applying limits to any axes… yeah?
I see my comment above was ambiguous, I have just edited it.

Interesting - I have had bad oscillations lead to a crash before and vibration levels only increased slightly. If you are sure the oscillation lead to the vibrations - then it shouldn’t be a problem.

I really don’t understand why that parameter was set to 0 by autotune (if autotune did indeed set that).

Well, as Dave and others suggested, the very low gains determined by autotune certainly played a role in yesterday’s crash.

I repaired the copter last night, set ATC_ACCEL_P_MAX to be ~25000 as per R_MAX, and I disabled feedforward. However it started to oscillate from the moment of launch. Graph attached. No damage.

I’ve now set the roll and pitch P & I terms to 0.1 as a test and it is flying again. I’ll need to tune the parameters the old way I guess :slight_smile:

The phase relationship of Des/actual Roll looks bad. Filter settings?

Yeah there’s a big lag and overshoot! I assume that’s because of the low gain and a bit of integral wind-up. Apart from the harmonic notch, the filters were all set according to the spreadsheet someone provided here on the forum. It flies okay now restoring PI&D gains without changing anything else.

The main thing that’s doing my head in now is why the performance during the “pilot test” after auto-tune looked good (ie it seems that auto-tune found values that gave a good response), but after a reboot I had the big oscillations. I might need to RTFS on that one.

I would set the RAT P and I terms back to 0.11 and the RAT D terms to .006, for both pitch and roll.
And that ATC_ANG_RLL_P is back to 4.5, or maybe as high as 6 to start with. Set ATC_ANG_PIT_P the same.
See if you can get airborne with that and let’s see the log.

Thanks Shawn. I set the param’s as you suggested, with ATC_ANG_* = 5. There was a light nose-on wind.

So if anything it looks like the P&I terms should increase further? Full log here:

https://ozforecast.com.au/temp/log_64_2021-4-13-13-09-44.bin

There’s more vibration today - the props had some damage in yesterday’s crash and I don’t currently have any spares.

What ESCs do you have?

Attitude control needs a bit of work, but it’s not the worst.


There was a couple of departures there, particularly at 13:09:53

Y axis vibrations indicate either the antivibration mounting is not equal in all directions, or something is touching or pulling on the flight controller. X axis is OK.
Z axis vibrations are poor too and will need to be fixed. Maybe a better flight controller mounting??
Don’t fly until you’re sure the Z axis vibrations are improved, or you risk a fly-away. Stay in Stabilise mode for tests until you are more confident the vibrations are under control.

Motor 6 has higher than average output and motor 5 is lower than average, indicating a weight imbalance. Not a big deal, but just something to check.

I would set these and run Autotune on pitch and roll when you have the props sorted and vibrations fixed:
AUTOTUNE_AGGR,0.1
ATC_ACCEL_P_MAX,60000
ATC_ACCEL_R_MAX,60000
INS_HNTCH_BW,35
INS_HNTCH_ATT,40
INS_HNTCH_REF,0.17
BATT_FS_CRT_ACT,1
ATC_THR_MIX_MAN,0.5
PSC_ACCZ_I,0.34
PSC_ACCZ_P,0.17