mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: fixed is_flying_vtol() for non-quadplane
This commit is contained in:
parent
a159eedd8c
commit
388b7ad6bd
@ -661,6 +661,9 @@ bool QuadPlane::should_relax(void)
|
||||
// see if we are flying in vtol
|
||||
bool QuadPlane::is_flying_vtol(void)
|
||||
{
|
||||
if (!available()) {
|
||||
return false;
|
||||
}
|
||||
if (motors->get_throttle() > 0.01f) {
|
||||
// if we are demanding more than 1% throttle then don't consider aircraft landed
|
||||
return true;
|
||||
|
Loading…
Reference in New Issue
Block a user