mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Bootloader: fixed use of FLASH_RESERVE_END_KB
This commit is contained in:
parent
8e83783b18
commit
a74f2428f2
@ -51,9 +51,9 @@ int main(void)
|
||||
{
|
||||
board_info.board_type = APJ_BOARD_ID;
|
||||
board_info.board_rev = 0;
|
||||
board_info.fw_size = (BOARD_FLASH_SIZE - FLASH_BOOTLOADER_LOAD_KB)*1024;
|
||||
board_info.fw_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + FLASH_RESERVE_END_KB))*1024;
|
||||
if (BOARD_FLASH_SIZE > 1024 && check_limit_flash_1M()) {
|
||||
board_info.fw_size = (1024 - FLASH_BOOTLOADER_LOAD_KB)*1024;
|
||||
board_info.fw_size = (1024 - FLASH_BOOTLOADER_LOAD_KB)*1024;
|
||||
}
|
||||
|
||||
bool try_boot = false;
|
||||
|
@ -80,11 +80,22 @@ void flash_init(void)
|
||||
{
|
||||
uint32_t reserved = 0;
|
||||
num_pages = stm32_flash_getnumpages();
|
||||
/*
|
||||
advance flash_base_page to account for FLASH_BOOTLOADER_LOAD_KB
|
||||
*/
|
||||
while (reserved < FLASH_BOOTLOADER_LOAD_KB * 1024U &&
|
||||
flash_base_page < num_pages) {
|
||||
reserved += stm32_flash_getpagesize(flash_base_page);
|
||||
flash_base_page++;
|
||||
}
|
||||
/*
|
||||
reduce num_pages to account for FLASH_RESERVE_END_KB
|
||||
*/
|
||||
reserved = 0;
|
||||
while (reserved < FLASH_RESERVE_END_KB * 1024U) {
|
||||
reserved += stm32_flash_getpagesize(num_pages-1);
|
||||
num_pages--;
|
||||
}
|
||||
}
|
||||
|
||||
void flash_set_keep_unlocked(bool set)
|
||||
|
Loading…
Reference in New Issue
Block a user