From 32555030328f4a9d575ea38a4a66c1adde160db8 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Sun, 4 Sep 2011 06:39:49 +0000 Subject: [PATCH] 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 --- libraries/AP_Common/AP_Var.cpp | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Common/AP_Var.cpp b/libraries/AP_Common/AP_Var.cpp index ffe09e658a..95b7016335 100644 --- a/libraries/AP_Common/AP_Var.cpp +++ b/libraries/AP_Common/AP_Var.cpp @@ -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;