mirror of https://github.com/ArduPilot/ardupilot
StorageManager: remove unnecessary calculations on addr for next area
When writting or reading a block, if the block doesn't fit the area where it begins, the next base address is always zero. Thus the calculations to define the next value of addr are unnecessary. Here's a quick validity proof using the previous calculations: First: Considering the case where the block doesn't fit it's first area: That means that (count + addr > length), what makes: count = length - addr; (1) So the following operations: addr += count; addr -= length; Are the same as doing: addr = addr + count - length; (2) Using (1) and (2) we have: addr = addr + length - addr - length = 0 Second: When the block fits the area where it's at: That means that variable count is not changed, thus (n -= count) evaluates to 0, which makes the loop exit. Another change was (b += count;) being moved after the condition to break the loop, since we just need to move the block pointer when it doesn't fit the first area.
This commit is contained in:
parent
54b7a2db60
commit
6d89a8cf71
|
@ -150,15 +150,15 @@ bool StorageAccess::read_block(void *data, uint16_t addr, size_t n) const
|
|||
}
|
||||
hal.storage->read_block(b, addr+offset, count);
|
||||
n -= count;
|
||||
addr += count;
|
||||
b += count;
|
||||
|
||||
// adjust addr for next area
|
||||
addr -= length;
|
||||
|
||||
if (n == 0) {
|
||||
break;
|
||||
}
|
||||
|
||||
// move pointer after written bytes
|
||||
b += count;
|
||||
// continue writing at the beginning of next valid area
|
||||
addr = 0;
|
||||
}
|
||||
return (n == 0);
|
||||
}
|
||||
|
@ -190,15 +190,15 @@ bool StorageAccess::write_block(uint16_t addr, const void *data, size_t n) const
|
|||
}
|
||||
hal.storage->write_block(addr+offset, b, count);
|
||||
n -= count;
|
||||
addr += count;
|
||||
b += count;
|
||||
|
||||
// adjust addr for next area
|
||||
addr -= length;
|
||||
|
||||
if (n == 0) {
|
||||
break;
|
||||
}
|
||||
|
||||
// move pointer after written bytes
|
||||
b += count;
|
||||
// continue writing at the beginning of next valid area
|
||||
addr = 0;
|
||||
}
|
||||
return (n == 0);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue