mirror of https://github.com/ArduPilot/ardupilot
Plane: refuse arming if we are in a landing sequence
this helps when the aircraft has gone into a landing sequence due to a failsafe before it is armed. Arming while in the landing sequence is very unlikely to be what the user wants
This commit is contained in:
parent
bbd250a5c9
commit
24f5802858
|
@ -102,6 +102,11 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
|
|||
}
|
||||
}
|
||||
|
||||
if (plane.mission.get_in_landing_sequence_flag()) {
|
||||
check_failed(display_failure,"In landing sequence");
|
||||
ret = false;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue