AP_Var: avoid wearing out EEPROM by re-writing the same value
when saving a variable, this avoids EEPROM wear by checking if the existing value is already the same as the value being written, and avoiding the write. Thanks to Mike Smith for the implementation git-svn-id: https://arducopter.googlecode.com/svn/trunk@3233 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e099079cc0
commit
06c4f60490
@ -207,7 +207,23 @@ bool AP_Var::save(void)
|
||||
// if it fit in the buffer, save it to EEPROM
|
||||
if (size <= sizeof(vbuf)) {
|
||||
debug("saving %u to %u", size, _key);
|
||||
eeprom_write_block(vbuf, (void *)_key, size);
|
||||
// XXX this should use eeprom_update_block if/when Arduino moves to
|
||||
// avr-libc >= 1.7
|
||||
uint8_t *ep = (uint8_t *)_key;
|
||||
for (size_t i = 0; i < size; i++, ep++) {
|
||||
uint8_t newv;
|
||||
// if value needs to change, change it
|
||||
if (eeprom_read_byte(ep) != vbuf[i])
|
||||
eeprom_write_byte(ep, vbuf[i]);
|
||||
|
||||
// now read it back
|
||||
newv = eeprom_read_byte(ep);
|
||||
if (newv != vbuf[i]) {
|
||||
debug("readback failed at offset %p: got %u, expected %u",
|
||||
ep, newv, vbuf[i]);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user