[Solved] Quadplane flips on takeoff

HI there folks,

I was testing a quadplane today (converted Durafly Tundra, running Arduplane 3.8.2), and had a few good flights in FBWA/B with a well-performing RTL (with QRTL_MODE = 1 and a good transition) during the second last flight. I decided to go for an AUTO mission, just a simple VTOL takeoff and a few rounds. The takeoff didn’t go very smoothly, as the aircraft immediately flipped onto its side, luckily without too much damage.

Inspecting the dataflash log tells me that the CH6 (rear left) motors don’t seem to spin up enough at the start corresponding to the direction of the fli[, however I’m quite sure enough time was given after arming for all motors to spin at what seemed to be the same speed. This is a taildragger, so not sure if that would affect anything.

^ The purple line for CH6 output stays low while the rest increase as expected. The desired roll and pitch seem to be as expected, so I’m not sure why this is the case. QHOVER, QSTABILIZE, transitions, etc are all fairly smooth as well.

Attached here is the link to the dataflash log - I’m very new to quadplanes and I was hoping someone could help me take a look to see what’s wrong?

Thanks!

wow, nasty!
do you have the log of the flight that led up to that? Or a tlog from a GCS from before this flight?
It seems to have kept a roll demand from before the start of this log, and I’d like to try and reproduce that in the simulator. It would help if I could see what happened before the log you sent.

Thanks Tridge. Wasn’t all that nasty, I think after working with heli crashes for so long, these fixed wing crashes are far more tame (and cheap!) :sweat_smile:

I’m attaching the three other logs from before this flight (all from today’s one session), hopefully that will help.

Log 1 - a FBWA checkout flight at the start of the session, also to get airspeed and TECS tuning values.

Log 2 - first attempt at FBWB, aircraft was not climbing even with much elevator deflection, changed TECS_SPDWEIGHT to 0.9 from 1 and increased the FBWB_CLIMB rate. Tested RTL mode as well, felt that this RTL_RADIUS was too high, and also bounced on landing.

Log 3 - much better response in FBWB, seemed to climb correctly. RTL was also much better, smooth landing.

These three are in chronological order, and the log in the original post comes directly after Log 3.

Hi @tridge, any luck with this? I tried to take a look at that pre-existing roll demand, but it looks pretty minimal (the value doesn’t show up on the picture, but around maybe -2 degrees when AUTO mode is on. Doesn’t seem to be commanded either based on the RCIN values.

thanks. Unfortunately the log with the flip is after a reboot. It starts with a boot time of 193 seconds, whereas log3 ends 16 minutes earlier.
Do you happen to have a tlog from a ground station for that period while it was booting up?

the key value I am interested in isn’t the roll demand, it’s PIQR.P, which is the output of the multirotor roll PID controller. That should be close to zero, but for some reason is it over 1.0. What I’d like to know is what conditions led up to that. Ideally I’d like to be able to reproduce it in SITL so I can be sure I’ve fixed the real cause.
Cheers, Tridge

Hi Tridge,

https://drive.google.com/open?id=0B_bbiwjdkLT2dnRpZVptQUVKMmc - this is the tlog that ends with the flip (the AUTO mode marker).

https://drive.google.com/open?id=0B_bbiwjdkLT2NmhEdHRWSWoxdnM - this is the earlier tlog from the day

fantastic, thanks! Using your tlogs I was able to reproduce the key symptom in SITL simulation (the buildup of PIQR.P before takeoff)
Now to actually fix it …

Ah, that’s great! What conditions cause it to happen?

Also, perhaps some additional information would help. The quad motors are fairly underpowered for the frame, requiring about 90% to takeoff at a reasonable speed. Sometimes the aircraft tends to yaw on takeoff and descent, the default yaw headroom is perhaps a bit too little. The AUTO mode was set from the GCS, not from the transmitter, if that makes any difference. The RTL and QRTLs you see in the log right before the AUTO was because on bootup, the TX failsafe was engaged because I placed the TX down on the table (it has a patch antenna).

Not sure if any of this is helpful, but just in case :slight_smile:

I can get it to happen by making the simulated frame have a few degree roll and pitch on the ground, then arming in FBWB mode, then switching to AUTO.
Still investigating why FBWB matters and how the PID buildup occurs

Okay thanks Tridge. Can I temporarily resolve this by only arming in FBWA? Was hoping to continue to test-fly the aircraft tomorrow.

I’ve finally tracked down this issue properly, and I can confirm the issue won’t happen if you arm in FBWA on the ground instead of FBWB.
The issue is buildup of multicopter control while the throttle is suppressed in an auto-throttle fixed wing mode (so FBWB and CRUISE)
It will be fixed in 3.8.3
Many thanks for your very helpful logs!

Thank you very much for the speedy fix! Will un-ground the aircraft :slight_smile:

Did you simulate this in usual SITL? Or RealFlight? I couldn’t figure out how to tilt the aircraft before takeoff in the default SITL.

I simulated it in SITL, by changing SIM_Aircraft.cpp to give it a slant on the ground.
I may add that as an option in SITL. I just hacked it in for this test.

Ah okay, that makes sense. Thanks again!

A new incarnation of that aircraft was rebuilt and flight tested today, with 3 successful AUTO missions under its belt. I’ve uploaded some logs here in case anyone wants to take a look.

https://drive.google.com/open?id=0B_bbiwjdkLT2UjZMUjgzcU9UaVk

Looks like the fix has gone in here: https://github.com/ArduPilot/ardupilot/commit/af893ddde71d5aa415327efcd5745d42e4d36da6

Cheers!