PID tuning for a small Flying Wing (~47 cm wingspan)

PID tuning of a Flying Wing

I have been tuning the PID values of a small (47 cm wingspan) Flying Wing, and noticed that the default values result in oscillations at 5Hz.

The wing is the one shown in the video below, which is incredibly agile (and almost impossible to control manually):

Flight with Default PID

We can observe 5Hz oscillation in roll (and pitch), and the gains were following:

FW_RR_D, 0.0
FW_RR_FF, 0.5
FW_RR_I, 0.10000000149011612
FW_RR_IMAX, 0.20000000298023224
FW_RR_P, 0.05000000074505806

Hereā€™s a log: https://logs.px4.io/plot_app?log=be371402-3c77-426a-88cd-d1ce733ed3b8

Flight with reduced FF and P gains

I reduced the FF (0.5 ā†’ 0.25) and P gain (0.05 ā†’ 0.03), like following:

FW_RR_D, 0.0
FW_RR_FF, 0.25
FW_RR_I, 0.10000000149011612
FW_RR_IMAX, 0.20000000298023224
FW_RR_P, 0.029999999329447746

And from this, I was actually surprised that the oscillation didnā€™t really improve even with smaller FF and P gains :frowning_face:.

Hereā€™s a log: https://logs.px4.io/plot_app?log=650a1033-1138-4fca-bb0a-4827b78f292a

Discussion

The tuning guide suggests to set PID gains to minimum, then start with increasing the FF gain, then tune P, D, and I each.

Questions

So I had 4 questions:

How is it possible that reducing the FF gain and P gain still results in a similar oscillation? Shouldnā€™t they have been a bit better?

Whether the FW_R_TC for the attitude controller was perhaps too aggressive (which I thought should be the case however, since itā€™s a small wing).

Whether the D term should be added (currently itā€™s 0), as without the D, can Fixed Wings achieve the desired attitude without an overshoot?

Whether the auto-tune (which I would try after getting the initial FF gains more satisfactory and with no oscillation) would also work well for such agile platform (this wing is essentially not controllable with manual control)

Thanks in advance!

Notes

Relevant article: Followup of 7/13/22 devcall, FF/Kp/Ki gains ratios

The default gains are very FF heavy. I donā€™t think that works well with likely not too stable wings as yours. Iā€™d recommend you reduce the FF to about 0.2 and start with a P of 0.3 and possibly increase it further.

I see that you donā€™t have an airspeed sensor. Thus you have to make sure manually to fly it close to the intended cruising speed, as otherwise the effectiveness of the surfaces changes a lot (and the controller has no way of knowing about that).

1 Like

Airspeed Scaling

Actually, I often noticed that vehicle was wobbling after ā€œfew seconds of flight after takeoffā€, and after close examination of the log, I found that most likely it is suffering from PID not being scaled with respect to the airspeed.

Log link: https://logs.px4.io/plot_app?log=e7f3aa9c-9321-4286-a877-90a54d687f92

As I plotted vxy (ground speed) here, you can clearly tell that as the vehicle crosses around 6 m/s mark (as I remove the throttle and let it glide), the vibration goes away.

Therefore, I am planning on:

  • Enabling the Airspeed selector module
  • Setting ASPD_PRIMARY to ā€œGroundspeed minus windspeedā€

This I believe should then provide the estimated airspeed data from the ground speed and allow PID scaling, I will have to test this!

PID gains

As you said, FF of 0.2 or higher often resulted in overshoot, so in the flight linked above, I actually removed the FF gains, and only relied on P and I gains.

However, it seems like probably airspeed scaling would help remove the wobble, then I will definitely also tune the PID gains again (and perhaps put FF back in).

Btw is having FF gain very crucial?

Update on Flight with no FF gain and just P & I gain

So I did another flight yesterday with 0 FF gain and just P (0.05 for both pitch and roll) and I gain (0.1 for roll, 0.2 for pitch) to check what happens:

image

Log link: https://logs.px4.io/plot_app?log=fc2f17c6-1699-4cfa-9dbd-5bb488cd2093

It seems like the following are observed:

  1. Maximum roll rate FW_R_RMAX (70 deg/s) is easily surpassed by the vehicle (with roll torque setpoint of less than 0.4, it already reaches 200 deg/s).
  2. Vehicle suddenly nose dives & does a left roll 2 times, then crashes

This is without airspeed scaling in effect, so just the tuning have changed from the last flight.

So my takeaway would then be:

  1. Increase the maximum roll rate to actually meet vehicleā€™s capability to around 300 deg/s (if itā€™s too small compared to the capability, I think it becomes prone to losing control authority & be sluggish)
  2. Increase the P gains

And regarding airspeed estimation from ground to wind speed difference (on answer above), I would:

  1. Set airspeed trim to 7.0 m/s (around what the gliding speed is)
  2. Set minimum airspeed to 4.0 m/s, and stall to 3.0 m/s
  3. Set EKF2_ARSP_THR to 2.4 m/s (80% of stall speed), to enable airspeed fusion and make yaw estimator (using no magnetometer) more precise, hopefully

Hopefully this will make the wing more stable, and I can trigger the autotune!

Update on Flight with Airspeed scaling

With airspeed scaling applied (by turning on the ground minus wind based airspeed estimation), the ā€˜flutteringā€™ issue is now finally gone (rate overshooting and oscillating around the rate setpoint), which makes sense!

However, now I observed that thereā€™s an (almost) bias / barrier between the rate setpoint vs achieved rate. As shown in screenshot below, the rate setpoint for roll is hardly ever reached.

Log link: https://logs.px4.io/plot_app?log=764dd3a1-f2d7-4ca4-997b-d89ba7e90f85

From the fact that as soon as the ā€˜setpointā€™ decreases, the rate follows that direction as well, I can now conclude that the controller is too overpowered with FF gain (hence, the ā€˜setpointā€™ is basically driving the whole control, with no feedback).

You can notice that FF term is the majority of the PID-FF outputs are dominated by the FF gain in the PID component log that I added.

Notes

However, I noticed that integral value for roll barely changes when thereā€™s constant rate error, and it is due to the following feature on reducing I-gain upon big rate error (as P or FF term should do that job)

Also, Iā€™m not sure why the integral value for the rollspeed is ā€˜decreasingā€™ when thereā€™s always a positive error (setpoitnt - current rate), for example throughout 9 ~ 14 seconds mark in the graph above :person_shrugging:

I canā€™t think of any reason how this could happen.

TODOs

So what I would do are:

  1. Decrease FF gain to 0.05 or smaller (was 0.1 here)
  2. Increase P gain to 0.3 (was 0.15 here)

Testing with No FF gain and just P gain

So because of the analysis above & to make PID tuning as simple as possible, I conducted tests with just the P-gains enabled (FF, I, D set to 0) for both roll and pitch.

However, note that I initially started with I gains non-zero (noted below), then turned it off later.

I have observed:

  1. Roll P = 0.4, Pitch P = 0.2 (I gains enabled): Pitching down a lot and crashing
  2. Roll and Pitch P = 0.3 (I gains enabled): Fluttering
  3. Roll and Pitch P = 0.2 (I gains enabled): Fluttering
  4. Roll and Pitch P = 0.1 (I gains disabled): Still oscillating
  5. Roll and Pitch P = 0.05 (I gains disabled): Pitching down and diving
  6. Roll P = 0.05, Pitch P = 0.07 (I gains disabled): More flyable, but still pitching down and diving

So from this, I deduced that:

  1. Pitch definitely needs some I gain to compensate for the natural tendancy of the vehicle to pitch down
  2. Gains over 0.1 already seems too high and causes oscillations (Surprised how my previous flights with 0.3 gains or so flew somehow!)

Note, however that I changed the ā€˜trimmed airspeedā€™ parameter from 6 m/s to 11 m/s, which is more realistic for gliding speed, hence the PID values from previous flights needs to be scaled down 50% to be consistent (hence, we now have really small P gains, as they should be quite small at 11m/s, compared to 6 m/s).

Flight with both roll and pitch P gain 0.05

Log: https://logs.px4.io/plot_app?log=b70dc1f8-fc63-4891-bfa2-cecaede4ee81

For me, here the roll control seems fine (itā€™s tracking around the setpoint), and itā€™s just the pitch thatā€™s constantly around -0.1 radians (-6 degrees), while Iā€™m commanding 0.7 radians (45 degrees), thatā€™s not being controlled.

Flight with both roll P gain 0.05, pitch P gain 0.07

Log: https://logs.px4.io/plot_app?log=b9a731ea-1541-4fbc-b0be-0543af38c672

Here too, the pitch seems to be just too low (pitching down).

TODOs

  1. Add the I-term to the Pitch
1 Like