AP_TECS: Ensure no throttle output if is_gliding flag is true when flying without airspeed.

This commit is contained in:
Samuel Tabor 2021-05-17 17:23:26 +01:00 committed by Andrew Tridgell
parent 8ca6b3e3ee
commit 5865e010b0
1 changed files with 1 additions and 0 deletions

View File

@ -770,6 +770,7 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge)
if (_flags.is_gliding)
{
_throttle_dem = 0.0f;
return;
}
// Calculate additional throttle for turn drag compensation including throttle nudging