mirror of https://github.com/ArduPilot/ardupilot
AP_TECS: Ensure no throttle output if is_gliding flag is true when flying without airspeed.
This commit is contained in:
parent
8ca6b3e3ee
commit
5865e010b0
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue