mirror of https://github.com/ArduPilot/ardupilot
Plane: AP_Arming: use `mission.contains_item()` eather than `.mission.get_landing_sequence_start() > 0`
This commit is contained in:
parent
eadcf9b09e
commit
77ef4eb4e6
|
@ -437,7 +437,7 @@ bool AP_Arming_Plane::mission_checks(bool report)
|
|||
{
|
||||
// base checks
|
||||
bool ret = AP_Arming::mission_checks(report);
|
||||
if (plane.mission.get_landing_sequence_start() > 0 && plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) {
|
||||
if (plane.mission.contains_item(MAV_CMD_DO_LAND_START) && plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) {
|
||||
ret = false;
|
||||
check_failed(ARMING_CHECK_MISSION, report, "DO_LAND_START set and RTL_AUTOLAND disabled");
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue