Browse Source

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

c415-sdk
Samuel Tabor 4 years ago committed by Andrew Tridgell
parent
commit
5865e010b0
  1. 1
      libraries/AP_TECS/AP_TECS.cpp

1
libraries/AP_TECS/AP_TECS.cpp

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

Loading…
Cancel
Save