AP_Arming: added eeprom full arming check

tell users if params may not persist
This commit is contained in:
Andrew Tridgell 2024-06-14 14:04:56 +10:00 committed by Randy Mackay
parent c496003740
commit 9cdf4b96f9
1 changed files with 5 additions and 0 deletions

View File

@ -1084,6 +1084,11 @@ bool AP_Arming::system_checks(bool report)
return false;
}
if (AP_Param::get_eeprom_full()) {
check_failed(ARMING_CHECK_PARAMETERS, report, "parameter storage full");
return false;
}
// check main loop rate is at least 90% of expected value
const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();