AP_Param: eeprom translated to use AP_HAL. No unit tests available!

This commit is contained in:
Pat Hickey 2012-11-12 13:12:28 -08:00 committed by Andrew Tridgell
parent 87c55f68c2
commit ec53515648
1 changed files with 7 additions and 7 deletions

View File

@ -73,9 +73,9 @@ void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
{
const uint8_t *b = (const uint8_t *)ptr;
while (size--) {
uint8_t v = eeprom_read_byte((const uint8_t *)(uintptr_t)ofs);
uint8_t v = hal.storage->read_byte(ofs);
if (v != *b) {
eeprom_write_byte((uint8_t *)(uintptr_t)ofs, *b);
hal.storage->write_byte(ofs, *b);
}
b++;
ofs++;
@ -228,7 +228,7 @@ bool AP_Param::setup(const struct AP_Param::Info *info, uint16_t eeprom_size)
serialDebug("setup %u vars", (unsigned)_num_vars);
// check the header
eeprom_read_block(&hdr, 0, sizeof(hdr));
hal.storage->read_block(&hdr, 0, sizeof(hdr));
if (hdr.magic[0] != k_EEPROM_magic0 ||
hdr.magic[1] != k_EEPROM_magic1 ||
hdr.revision != k_EEPROM_revision) {
@ -434,7 +434,7 @@ bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs)
struct Param_header phdr;
uint16_t ofs = sizeof(AP_Param::EEPROM_header);
while (ofs < _eeprom_size) {
eeprom_read_block(&phdr, (void *)(uintptr_t)ofs, sizeof(phdr));
hal.storage->read_block(&phdr, ofs, sizeof(phdr));
if (phdr.type == target->type &&
phdr.key == target->key &&
phdr.group_element == target->group_element) {
@ -728,7 +728,7 @@ bool AP_Param::load(void)
}
// found it
eeprom_read_block(ap, (void*)(ofs+sizeof(phdr)), type_size((enum ap_var_type)phdr.type));
hal.storage->read_block(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
return true;
}
@ -796,7 +796,7 @@ bool AP_Param::load_all(void)
uint16_t ofs = sizeof(AP_Param::EEPROM_header);
while (ofs < _eeprom_size) {
eeprom_read_block(&phdr, (void *)(uintptr_t)ofs, sizeof(phdr));
hal.storage->read_block(&phdr, ofs, sizeof(phdr));
// note that this is an || not an && for robustness
// against power off while adding a variable
if (phdr.type == _sentinal_type ||
@ -811,7 +811,7 @@ bool AP_Param::load_all(void)
info = find_by_header(phdr, &ptr);
if (info != NULL) {
eeprom_read_block(ptr, (void*)(ofs+sizeof(phdr)), type_size((enum ap_var_type)phdr.type));
hal.storage->read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
}
ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);