mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Bootloader: fix return the size of flash sector
flash_base_page+num_pages already be more than last sector of flash, there should be num_pages-flash_base_page when judge the last sector
This commit is contained in:
parent
bb0a4f3c78
commit
8fe39e8784
@ -97,7 +97,7 @@ void flash_func_write_word(uint32_t offset, uint32_t v)
|
|||||||
|
|
||||||
uint32_t flash_func_sector_size(uint32_t sector)
|
uint32_t flash_func_sector_size(uint32_t sector)
|
||||||
{
|
{
|
||||||
if (sector >= flash_base_page+num_pages) {
|
if (sector >= num_pages-flash_base_page) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
return stm32_flash_getpagesize(flash_base_page+sector);
|
return stm32_flash_getpagesize(flash_base_page+sector);
|
||||||
|
Loading…
Reference in New Issue
Block a user