AP_Arming: only require AP_RALLY_ENABLED if MIS_ITEM_CHECK_RALLY

It's OK to not have AP_RALLY_ENABLED if the user isn't requiring that a rally point be avaiable.  i.e. if the user is requesting that there be a landing point that doesn't infer rally must be compiled in!
This commit is contained in:
Peter Barker 2022-12-29 11:21:25 +11:00 committed by Andrew Tridgell
parent 65547f41c7
commit 80c79f1529

View File

@ -790,15 +790,6 @@ bool AP_Arming::mission_checks(bool report)
check_failed(ARMING_CHECK_MISSION, report, "No mission library present");
return false;
}
#if HAL_RALLY_ENABLED
AP_Rally *rally = AP::rally();
if (rally == nullptr) {
check_failed(ARMING_CHECK_MISSION, report, "No rally library present");
return false;
}
#else
check_failed(ARMING_CHECK_MISSION, report, "No rally library present");
#endif
const struct MisItemTable {
MIS_ITEM_CHECK check;
@ -820,8 +811,13 @@ bool AP_Arming::mission_checks(bool report)
}
}
}
#if HAL_RALLY_ENABLED
if (_required_mission_items & MIS_ITEM_CHECK_RALLY) {
#if HAL_RALLY_ENABLED
AP_Rally *rally = AP::rally();
if (rally == nullptr) {
check_failed(ARMING_CHECK_MISSION, report, "No rally library present");
return false;
}
Location ahrs_loc;
if (!AP::ahrs().get_location(ahrs_loc)) {
check_failed(ARMING_CHECK_MISSION, report, "Can't check rally without position");
@ -832,8 +828,11 @@ bool AP_Arming::mission_checks(bool report)
check_failed(ARMING_CHECK_MISSION, report, "No sufficently close rally point located");
return false;
}
}
#else
check_failed(ARMING_CHECK_MISSION, report, "No rally library present");
return false;
#endif
}
}
return true;