Plane: tailsitters in VTOL transition use FW rates

This commit is contained in:
Iampete1 2020-10-07 14:51:19 +01:00 committed by Andrew Tridgell
parent 175d55a0aa
commit 2acbef5579
1 changed files with 2 additions and 1 deletions

View File

@ -848,7 +848,8 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
check_attitude_relax();
// normal control modes for VTOL and FW flight
if (in_vtol_mode()) {
// tailsitter in transition to VTOL flight is not really in a VTOL mode yet
if (in_vtol_mode() && !in_tailsitter_vtol_transition()) {
// tailsitter-only body-frame roll control options
// Angle mode attitude control for pitch and body-frame roll, rate control for euler yaw.