mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Arming: added eeprom full arming check
tell users if params may not persist
This commit is contained in:
parent
9c2ad95481
commit
007650af54
@ -1084,6 +1084,11 @@ bool AP_Arming::system_checks(bool report)
|
|||||||
return false;
|
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
|
// check main loop rate is at least 90% of expected value
|
||||||
const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
|
const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
|
||||||
const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();
|
const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();
|
||||||
|
Loading…
Reference in New Issue
Block a user