mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: lower throttle threshold for quadplane is_flying
This commit is contained in:
parent
a94a19bd09
commit
20cf326093
@ -590,7 +590,7 @@ bool QuadPlane::is_flying(void)
|
||||
if (!available()) {
|
||||
return false;
|
||||
}
|
||||
if (motors->get_throttle() > 0.2 && !motors->limit.throttle_lower) {
|
||||
if (motors->get_throttle() > 0.1 && !motors->limit.throttle_lower) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user