mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: added eeprom full arming check
tell users if params may not persist
This commit is contained in:
parent
a489d24f83
commit
2216f64c30
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue