initialise spare bits in AP_Var headers

if we ever need these bits, it would be nice to know that they are
zero in existing eeproms
This commit is contained in:
Andrew Tridgell 2011-10-09 15:54:40 +11:00
parent cb8f8ec083
commit a3e6f5d51f

View File

@ -669,6 +669,7 @@ bool AP_Var::_EEPROM_locate(bool allocate)
pad_size = (((uint8_t)micros()) % k_size_max) + 1; // should be fairly random
var_header.key = k_key_pad;
var_header.size = pad_size - 1;
var_header.spare = 0;
eeprom_write_block(&var_header, (void *)_tail_sentinel, sizeof(var_header));
_tail_sentinel += sizeof(var_header) + pad_size;
@ -686,6 +687,7 @@ bool AP_Var::_EEPROM_locate(bool allocate)
//
var_header.key = k_key_sentinel;
var_header.size = 0;
var_header.spare = 0;
eeprom_write_block(&var_header, (void *)_tail_sentinel, sizeof(var_header));
// Write the header for the block we have just located, claiming the EEPROM space.