mirror of https://github.com/ArduPilot/ardupilot
parent
b68af03419
commit
ae8ee5325c
|
@ -112,6 +112,9 @@ uint16_t AP_Param::param_overrides_len;
|
||||||
uint16_t AP_Param::num_param_overrides;
|
uint16_t AP_Param::num_param_overrides;
|
||||||
uint16_t AP_Param::num_read_only;
|
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};
|
ObjectBuffer_TS<AP_Param::param_save> AP_Param::save_queue{30};
|
||||||
bool AP_Param::registered_save_handler;
|
bool AP_Param::registered_save_handler;
|
||||||
|
|
||||||
|
@ -1192,6 +1195,8 @@ void AP_Param::save_sync(bool force_save, bool send_to_gcs)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (ofs == (uint16_t) ~0) {
|
if (ofs == (uint16_t) ~0) {
|
||||||
|
eeprom_full = true;
|
||||||
|
DEV_PRINTF("EEPROM full\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1224,6 +1229,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()) {
|
if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _storage.size()) {
|
||||||
// we are out of room for saving variables
|
// we are out of room for saving variables
|
||||||
|
eeprom_full = true;
|
||||||
DEV_PRINTF("EEPROM full\n");
|
DEV_PRINTF("EEPROM full\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -430,6 +430,11 @@ public:
|
||||||
///
|
///
|
||||||
static bool load_all();
|
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:
|
// returns storage space used:
|
||||||
static uint16_t storage_used() { return sentinal_offset; }
|
static uint16_t storage_used() { return sentinal_offset; }
|
||||||
|
|
||||||
|
@ -865,6 +870,8 @@ private:
|
||||||
};
|
};
|
||||||
static defaults_list *default_list;
|
static defaults_list *default_list;
|
||||||
static void check_default(AP_Param *ap, float *default_value);
|
static void check_default(AP_Param *ap, float *default_value);
|
||||||
|
|
||||||
|
static bool eeprom_full;
|
||||||
};
|
};
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
|
Loading…
Reference in New Issue