mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Bootloader: added AP_BOOTLOADER_ALWAYS_ERASE
this will be set on AP_Periph bootloader to avoid a problem on G4
This commit is contained in:
parent
0accc9f897
commit
fa74d5516b
@ -34,6 +34,10 @@ static uint8_t last_uart;
|
||||
#define BOOTLOADER_BAUDRATE 115200
|
||||
#endif
|
||||
|
||||
#ifndef AP_BOOTLOADER_ALWAYS_ERASE
|
||||
#define AP_BOOTLOADER_ALWAYS_ERASE 0
|
||||
#endif
|
||||
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
static bool cin_data(uint8_t *data, uint8_t len, unsigned timeout_ms)
|
||||
@ -141,10 +145,14 @@ uint32_t flash_func_sector_size(uint32_t sector)
|
||||
|
||||
bool flash_func_erase_sector(uint32_t sector, bool force_erase)
|
||||
{
|
||||
#if AP_BOOTLOADER_ALWAYS_ERASE
|
||||
return stm32_flash_erasepage(flash_base_page+sector);
|
||||
#else
|
||||
if (force_erase || !stm32_flash_ispageerased(flash_base_page+sector)) {
|
||||
return stm32_flash_erasepage(flash_base_page+sector);
|
||||
}
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
// read one-time programmable memory
|
||||
|
Loading…
Reference in New Issue
Block a user