mirror of https://github.com/ArduPilot/ardupilot
parent
2bbdd2e227
commit
a489d24f83
|
@ -112,6 +112,9 @@ uint16_t AP_Param::param_overrides_len;
|
|||
uint16_t AP_Param::num_param_overrides;
|
||||
uint16_t AP_Param::num_read_only;
|
||||
|
||||
// goes true if we run out of param space
|
||||
bool AP_Param::eeprom_full;
|
||||
|
||||
ObjectBuffer_TS<AP_Param::param_save> AP_Param::save_queue{30};
|
||||
bool AP_Param::registered_save_handler;
|
||||
|
||||
|
@ -1194,6 +1197,8 @@ void AP_Param::save_sync(bool force_save, bool send_to_gcs)
|
|||
return;
|
||||
}
|
||||
if (ofs == (uint16_t) ~0) {
|
||||
eeprom_full = true;
|
||||
DEV_PRINTF("EEPROM full\n");
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1226,6 +1231,7 @@ void AP_Param::save_sync(bool force_save, bool send_to_gcs)
|
|||
|
||||
if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _storage.size()) {
|
||||
// we are out of room for saving variables
|
||||
eeprom_full = true;
|
||||
DEV_PRINTF("EEPROM full\n");
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -428,6 +428,11 @@ public:
|
|||
///
|
||||
static bool load_all();
|
||||
|
||||
// return true if eeprom is full, used for arming check
|
||||
static bool get_eeprom_full(void) {
|
||||
return eeprom_full;
|
||||
}
|
||||
|
||||
// returns storage space used:
|
||||
static uint16_t storage_used() { return sentinal_offset; }
|
||||
|
||||
|
@ -845,6 +850,8 @@ private:
|
|||
};
|
||||
static defaults_list *default_list;
|
||||
static void check_default(AP_Param *ap, float *default_value);
|
||||
|
||||
static bool eeprom_full;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
Loading…
Reference in New Issue