mirror of https://github.com/ArduPilot/ardupilot
AP_Param: methods to provide amount of parameter space used
AP_Param: provide method for storage size
This commit is contained in:
parent
4ef64261a1
commit
b493805fb4
|
@ -36,6 +36,8 @@
|
|||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
uint16_t AP_Param::sentinal_offset;
|
||||
|
||||
#define ENABLE_DEBUG 1
|
||||
|
||||
#if ENABLE_DEBUG
|
||||
|
@ -117,6 +119,7 @@ void AP_Param::write_sentinal(uint16_t ofs)
|
|||
set_key(phdr, _sentinal_key);
|
||||
phdr.group_element = _sentinal_group;
|
||||
eeprom_write_check(&phdr, ofs, sizeof(phdr));
|
||||
sentinal_offset = ofs;
|
||||
}
|
||||
|
||||
// erase all EEPROM variables by re-writing the header and adding
|
||||
|
@ -695,6 +698,7 @@ bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs)
|
|||
if (is_sentinal(phdr)) {
|
||||
// we've reached the sentinal
|
||||
*pofs = ofs;
|
||||
sentinal_offset = ofs;
|
||||
return false;
|
||||
}
|
||||
ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
|
||||
|
@ -1353,6 +1357,7 @@ bool AP_Param::load_all()
|
|||
// against power off while adding a variable
|
||||
if (is_sentinal(phdr)) {
|
||||
// we've reached the sentinal
|
||||
sentinal_offset = ofs;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -1438,6 +1443,7 @@ void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct
|
|||
// against power off while adding a variable
|
||||
if (is_sentinal(phdr)) {
|
||||
// we've reached the sentinal
|
||||
sentinal_offset = ofs;
|
||||
break;
|
||||
}
|
||||
if (get_key(phdr) == key) {
|
||||
|
|
|
@ -349,6 +349,12 @@ public:
|
|||
///
|
||||
static bool load_all();
|
||||
|
||||
// returns storage space used:
|
||||
static uint16_t storage_used() { return sentinal_offset; }
|
||||
|
||||
// returns storage space :
|
||||
static uint16_t storage_size() { return _storage.size(); }
|
||||
|
||||
/// reoad the hal.util defaults file. Called after pointer parameters have been allocated
|
||||
///
|
||||
static void reload_defaults_file(bool last_pass);
|
||||
|
@ -470,6 +476,8 @@ private:
|
|||
uint8_t spare;
|
||||
};
|
||||
|
||||
static uint16_t sentinal_offset;
|
||||
|
||||
/* This header is prepended to a variable stored in EEPROM.
|
||||
* The meaning is as follows:
|
||||
*
|
||||
|
|
Loading…
Reference in New Issue