mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
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
This commit is contained in:
parent
7aad03df28
commit
74525cad89
@ -177,10 +177,10 @@ void PX4Storage::_storage_open(void)
|
|||||||
void PX4Storage::_mark_dirty(uint16_t loc, uint16_t length)
|
void PX4Storage::_mark_dirty(uint16_t loc, uint16_t length)
|
||||||
{
|
{
|
||||||
uint16_t end = loc + length;
|
uint16_t end = loc + length;
|
||||||
while (loc < end) {
|
for (uint8_t line=loc>>PX4_STORAGE_LINE_SHIFT;
|
||||||
uint8_t line = (loc >> PX4_STORAGE_LINE_SHIFT);
|
line <= end>>PX4_STORAGE_LINE_SHIFT;
|
||||||
_dirty_mask |= 1 << line;
|
line++) {
|
||||||
loc += PX4_STORAGE_LINE_SIZE;
|
_dirty_mask |= 1U << line;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user