Heavy Lift Octorotor Oscillations on Landing

To address the problem at hand. There have been a lot of good points made and some good advice. I will try to give a concise overview of the problems and some tools to address it.

We have a reasonably lightly loaded aircraft. A frame that is pretty decent but with the normal challenges to nicely mount flight controller. Alpha ESC’s have worked well for me in the past but in general I don’t like T-Motor equipment. There is no reason why this aircraft should not tune up nicely.

The trick with turning large propellers is breaking torque and low inertia propellers. As I have tuned 40 inch props using alpha ESC’s I think it is unlikely that you have a power system problem. So that leaves tuning.
Decent wobbles and vortex ring state (I realise that @mboland did not mention vortex ring state) . While multirotors do suffer from their own turbulence during a fast descent this is not the same as vortex ring state. There are a number of factors that make it difficult if not impossible for a multirotor to enter vortex ring state. The first is the twist on the propeller producing a more uniform load along the length of the blade preventing the central up going airflow from developing. The second is the multiple propellers constantly changing thrust that disrupts the airflow preventing the outer vortex from forming properly.

We do suffer during decent but it is for a number of reasons.

  • We are descending into our own turbulent air placing a higher load on the controllers
  • We are at minimum or low throttle showing up tuning problems associated with MOT_THST_EXPO and MOT_SPIN_MIN.
  • The ESC is working very hard at low RPM and very close to where sync issues become a problem.

So that brings us to our first two parameters MOT_THST_EXPO and MOT_SPIN_MIN. These address two issues.

MOT_SPIN_MIN sets the minimum PWM level commanded to the ESC during flight. This is a very important factor as it defines how slow the ESC will let the motor go under load. When set way too low we risk loosing sync and the esc going back into its restart state or worse shutting down. As we get a little higher we see problems where under load the motor gets into a hole and there is an increased delay as the ESC works hard to increase the rpm back up again. This can cause issues like the one shown here but tends to be only part of the problem. MOT_SPIN_MIN should be set high enough to get strong rotation but only a small amount of lift.

MOT_THST_EXPO is the linearization of thrust vs PWM. If this is set too high we see an increase in gain at the lower end of the thrust range and a decrease in gain at the upper end. Therefore when set to high you can see instability at low throttle and if set too low you can see instability at high throttle. In this case both very high or very low values could cause this problem through different mechanisms but this parameter is pretty forgiving and you have not set it too far from where I would expect.

These have not been set:
MOT_PWM_MAX,0
MOT_PWM_MIN,0

I can’t remember if alphas have fixed pwm ranges but you should check and set them appropriately. I use 1000 to 2000 for calibratable ESC’s and the range specified in the instructions for fixed range ESC’s.

The rest of your motor setup looks ok.

Tuning:

The first step to tuning is defining the filter parameters. Here is where I think you may get the most benefit. Generally there are three types of tune:

  • Performance limited
  • Noise limited
  • Reliability limited

The lower the filter settings the slower the control loops are to respond to disturbances. If you have a really well built airframe with low noise then you can set your filters higher and your tune is limited only by your power system and aircraft dynamics. This is a performance limited tune.

As your noise increases you need to reduce your filter settings and you start getting serious compromises to your performance. This is a noise limited tune.

Reliability limited is where the aircraft will fail in some way if you tune the aircraft up properly. Normally this is in the form of ESC overcurrent protections causing ESC’s to shut down.

Filter settings:
Ideally I like to keep the noise levels below the 0.1 (10%) on the RATE.Xout messages. I start by carefully setting up the harmonic notch parameters.

INS_HNTCH_ATT,40
INS_HNTCH_BW, (2/3) * INS_HNTCH_FREQ
INS_HNTCH_ENABLE,1
INS_HNTCH_FREQ, measured from batch logging
INS_HNTCH_HMNCS, Your main harmonics, should be 3 for you
INS_HNTCH_MODE,1

Then I start with filter settings of:
INS_ACCEL_FILTER,10
INS_GYRO_FILTER 40
ATC_RAT_PIT_FLTD,20
ATC_RAT_PIT_FLTE,0
ATC_RAT_PIT_FLTT,10
ATC_RAT_RLL_FLTD,20
ATC_RAT_RLL_FLTE,0
ATC_RAT_RLL_FLTT,10

I look at the noise levels on the RATE.Xout messages dataflash logs and if they are large I reduce to:
INS_GYRO_FILTER 30
ATC_RAT_PIT_FLTD,15
ATC_RAT_RLL_FLTD,15

then if needed:
INS_GYRO_FILTER 20
ATC_RAT_PIT_FLTD,10
ATC_RAT_RLL_FLTD,10

The idea being to get the fastest filter settings with reasonable noise.

Manual tune and Autotune:

Autotune can be tricky for people to get right. Everybody used to emphasise getting a really calm day and letting it drift with the wind but the community has become complacent and it is used as a “flick a switch and get a tune” in any conditions option. People get something flying, do autotune and don’t even look at the parameters any more. This is why doing a manual tune is very helpful. It ensures the aircraft can handle Autotune, or more to the point the recovery from each test. And it also give the pilot an idea of what they expect the tune to look like.

In this case we should see similar tunes in roll and pitch:

ATC_ACCEL_P_MAX,35212.49
ATC_ANG_PIT_P,7.85549
ATC_RAT_PIT_FLTD,2
ATC_RAT_PIT_FLTE,0
ATC_RAT_PIT_FLTT,9
ATC_RAT_PIT_D,0.008191199
ATC_RAT_PIT_I,0.08153227
ATC_RAT_PIT_P,0.08153227

ATC_ACCEL_R_MAX,45817.86
ATC_ANG_RLL_P,5.472067
ATC_RAT_RLL_FLTD,9
ATC_RAT_RLL_FLTE,0
ATC_RAT_RLL_FLTT,9
ATC_RAT_RLL_D,0.002590117
ATC_RAT_RLL_I,0.1075044
ATC_RAT_RLL_P,0.1075044

The significant difference in the D terms suggest that there may be a problem with the autotune on roll.

Autotune can be adversely impacted by wind, badly setup MOT_THST_EXPO and MOT_SPIN_MIN, offset CG, payload or autopilot mounting.

In general you should always start with AUTOTUNE_AGGR set to 0.1. This is a conservative value and there is no reason to go lower here. This value defines the overshoot plus noise. In a perfectly clean aircraft the ideal value for disturbance rejection is 0.1 but 0.05 is ever so slightly faster. So when you factor in a little noise you get a nice safe range. The risk to going lower is any noise on your system can quickly cause autotune to fail so 0.1 or 0.15 for a noisy aircraft are good. (fix noise if you have it use 0.1).

You have autotuned yaw and have got a decent tune by the looks of things. You should be careful here because autotune can give a great yaw tune that can momentarily steal bandwidth from roll and pitch. I tend to set the accel a little lower and not let the P term go over 1.

ATC_ACCEL_Y_MAX,9230.682
ATC_ANG_YAW_P,4.310193
ATC_RAT_YAW_FLTD,0
ATC_RAT_YAW_FLTE,1
ATC_RAT_YAW_FLTT,9
ATC_RAT_YAW_D,0
ATC_RAT_YAW_I,0.1050341
ATC_RAT_YAW_P,1.050341

So to soften yaw and give roll and pitch a little more room, I would tend to drop it to:
ATC_ACCEL_Y_MAX,6000
ATC_RAT_YAW_D,0
ATC_RAT_YAW_I,0.1
ATC_RAT_YAW_P,1

Well, that is probably enough for now.

A quick summary:
Check your

  • PWM settings
  • MOT_SPIN_MIN
  • Roll tune, in particular how low D went
  • Setup your harmonic notch
  • See if you can increase your filter settings

After all that it is also helpful to get stable descents to have conservative settings for:
ATC_ACCEL_P_MAX,30000
ATC_ACCEL_R_MAX,30000
for example.

15 Likes