Browse Source

HAL_PX4: fixed dirty_mask calculation in FRAM storage

this could lead to a number of bytes on 512 byte boundaries not being
written when changed in ram, so they would revert on next boot
master
Andrew Tridgell 11 years ago
parent
commit
74525cad89
  1. 12
      libraries/AP_HAL_PX4/Storage.cpp

12
libraries/AP_HAL_PX4/Storage.cpp

@ -176,12 +176,12 @@ void PX4Storage::_storage_open(void) @@ -176,12 +176,12 @@ void PX4Storage::_storage_open(void)
*/
void PX4Storage::_mark_dirty(uint16_t loc, uint16_t length)
{
uint16_t end = loc + length;
while (loc < end) {
uint8_t line = (loc >> PX4_STORAGE_LINE_SHIFT);
_dirty_mask |= 1 << line;
loc += PX4_STORAGE_LINE_SIZE;
}
uint16_t end = loc + length;
for (uint8_t line=loc>>PX4_STORAGE_LINE_SHIFT;
line <= end>>PX4_STORAGE_LINE_SHIFT;
line++) {
_dirty_mask |= 1U << line;
}
}
void PX4Storage::read_block(void *dst, uint16_t loc, size_t n)

Loading…
Cancel
Save