AP_Var: fill all of EEPROM with 0xFF on erase_all()

This wipes all parameter values, and also clears out any waypoints as
the waypoint format could have changed between firmware revisions.

This also ensures that the AP_Var code can't re-use any key values
from the old EEPROM state, which makes us less dependent on the old
EEPROM being in a good state

Pair-Programmed-With: Mike Smith

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3231 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-09-04 06:39:28 +00:00
parent 6075b7ce73
commit b8b8b7e8ca

View File

@ -304,6 +304,7 @@ void
AP_Var::erase_all() AP_Var::erase_all()
{ {
AP_Var *vp; AP_Var *vp;
uint16_t i;
debug("erase EEPROM"); debug("erase EEPROM");
@ -316,9 +317,12 @@ AP_Var::erase_all()
vp = vp->_link; vp = vp->_link;
} }
// overwrite the first byte of the header, invalidating the EEPROM // wipe the whole EEPROM, including waypoints, as we call this
// // on firmware revison changes, which may include a change to the
eeprom_write_byte(0, 0xff); // waypoint format
for (i = 0; i < k_EEPROM_size; i++) {
eeprom_write_byte((uint8_t *)i, 0xff);
}
// revert to ignorance about the state of the EEPROM // revert to ignorance about the state of the EEPROM
_tail_sentinel = 0; _tail_sentinel = 0;