VTOL Tricopter Tilt-Motor – Unstable Pitch Increase at High Throttle in Multicopter Mode (Looping)

Hello everyone,

I’m part of a university AeroDesign team, and we are currently developing a VTOL tricopter with tilt motors and vectored yaw. We are facing a critical stability issue when flying in Multicopter (Drone) mode, and we would appreciate any guidance.

At low throttle, the vehicle behaves well. It can hover stably, and roll, pitch, and yaw respond as expected. However, when we increase throttle beyond a certain point, the aircraft starts to pitch up continuously. Unfortunately, this behavior caused a crash during our latest flight.

The issue seems to be strongly related to higher thrust levels rather than pilot input. The multicopter tuning was done manually, following the ArduPilot documentation step by step, and the PID values were tuned and validated during low-throttle hover. We have also checked the basics such as motor order, rotation direction, frame orientation, and CG position. Despite multiple tuning attempts, the problem persists.

To help with analysis, I will attach a top-view diagram showing the motor layout and tilt axes, the flight log, and a video of the crash.

We would like to understand if this kind of behavior is common in tilt-motor tricopter configurations. Could this be related to thrust vector misalignment, tilt geometry, pitch–throttle coupling, or motor saturation at higher throttle? Are there any specific parameters or common pitfalls in ArduPilot that are especially important for this type of VTOL, such as tilt compensation, thrust linearization, PID scaling, or feedforward effects? We are also wondering if this could be caused by an issue that only becomes visible at higher thrust levels, such as frame or IMU alignment errors.

Any insight, similar experiences, or parameter suggestions would be extremely helpful for us. Thank you very much for your time and support.

.BIN (Uploaded to google drive)

Video of the crash (Uploade to youtube)

The PID controls are too high. Q_A_RAT_xxxReset them to the defaults and follow the tuning guides in the ardupilot wiki.

Reset ARMING_CHECKS,1 If it won’t arm or you get errors then you need to fix those. Turning off the arming checks is a long term recipe for a crash.

The notch filters aren’t set right. Turn off the second filter. INS_HNTC2_ENABLE,0 and try this:

INS_HNTCH_MODE,1 #THROTTLE
INS_HNTCH_FREQ, 45
INS_HNTCH_BW,20
INS_HNTCH_REF, 0.6
INS_HNTCH_HMNCS, 1

This won’t be a perfect filter, but there’s so much other stuff going on that this might give you a fighting chance to get a start and then we can dial it in as you get a good hover flight in.

There are lots of VTOLS of this configuration flying. Ardupilot will do this very well. You just need to follow the process.

Just to clarify, we did follow the ArduPilot tuning guide step by step. The Q_A_RAT parameters were initially set per the documentation/default and then adjusted based on flight behavior. In practice, we had to reduce the pitch rate gains, while roll gains could be increased. For yaw, the recommended values caused oscillations, so those gains were also reduced.

Understood and agreed. ARMING_CHECKS will be enabled for the next flights.

Regarding the notch filters, this is likely an area where we lacked deeper understanding. We chose an FFT-based setup because it seemed simpler and more automatic at the time. We’ll disable the second notch filter and test the throttle-based configuration you suggested to help isolate the issue.

For context, we already have a stable hover mode and have successfully completed a fully autonomous flight including VTOL transition. The pitch-up instability only shows up when throttle is increased significantly.

There was a lot of oscillation in the motor outputs, even when it was just hovering. I don’t think it was flying as well as you might have thought and just got lucky. Did you use the VTOL Quicktune or did you tune it manually? If you want, provide a .bin of a “good” flight to compare.

I noticed you have Dshot for the motors, but you didn’t set up bidirectional dshot for ESC telemetry. That would give you the best data for the filters. Throttle will work fine if you can’t set up bdshot. FFT is generally difficult to set up well and doesn’t provide any real benefit over the other methods for filtering. Generally, filtering is really key to a good flying drone, but you want as little as possible.

I have rebuilt the aircraft and retuned it manually (no Quicktune). One additional change is that we had to switch from 7’ props to 6’ props after breaking the 7. I also switched to the throttle-based notch filter configuration you suggested.

During the retune, I also noticed that Q_A_RAT_PIT_IMAX was unintentionally set to 0, effectively disabling the pitch integrator. After restoring it to 0.5, the original pitch-up issue at higher throttle was resolved.

I have flown again since then and the behavior is much improved. In this flight, throttle was intentionally pushed quite hard to stress the system. I’ll attach a new .bin from this flight for comparison.

From here, any guidance on what to focus on next in the tuning process would be appreciated (remaining oscillations, filtering).

Log file

Good catch on the IMAX! Tune looks reasonable. The motor outputs in the hover look much better. And sitting between 1500-1600 in a hover is pretty good for a VTOL.

Q_MOT_THST_HOVER seems like it’s really high. You have it set to 0.75 but I think it should be closer to 0.35.

How is the flight controller mounted? I’m worried that it’s soft mounted because the vibrations seem to be unreasonably low. (Less than 0.5 in a hover) Soft mounting a FC when it’s not needed is kind of like putting blinders on the IMU. It can’t detect what’s really going on.

I don’t want to mess with filters until these are addressed.

Regarding the FC mounting, I agree it may be soft mounted. The FC sits on a vibration damper, which could explain the unusually low vibration levels. I’m attaching a photo of the mounting.

In parallel, we ran FEM simulations of the rebuilt airframe and found the first bending/torsion modes around ~25Hz.

Regarding Q_MOT_THST_HOVER, what could it lead to if it is significantly higher than expected, since it flew well in AUTO mode?

There should be no need to soft mount the controller. You will get better performance if you hard mount the controller and use filters to deal with any minor issues. Using soft mounts will blind the IMU to what actually is going on. Unless you have combustion engines, you should be able to hard mount the controller on a good airframe.