AP_Bootloader: correct placement of AP_BOOTLOADER_ALWAYS_ERASE

this moves it outside of defined(BOOTLOADER_DEV_LIST)
This commit is contained in:
Peter Barker 2024-01-11 15:47:39 +11:00 committed by Andrew Tridgell
parent 8ccf51b0ed
commit 85fc178769

View File

@ -22,6 +22,10 @@
// optional uprintf() code for debug // optional uprintf() code for debug
// #define BOOTLOADER_DEBUG SD1 // #define BOOTLOADER_DEBUG SD1
#ifndef AP_BOOTLOADER_ALWAYS_ERASE
#define AP_BOOTLOADER_ALWAYS_ERASE 0
#endif
#if defined(BOOTLOADER_DEV_LIST) #if defined(BOOTLOADER_DEV_LIST)
static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST }; static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST };
#if HAL_USE_SERIAL == TRUE #if HAL_USE_SERIAL == TRUE
@ -34,10 +38,6 @@ static uint8_t last_uart;
#define BOOTLOADER_BAUDRATE 115200 #define BOOTLOADER_BAUDRATE 115200
#endif #endif
#ifndef AP_BOOTLOADER_ALWAYS_ERASE
#define AP_BOOTLOADER_ALWAYS_ERASE 0
#endif
// #pragma GCC optimize("O0") // #pragma GCC optimize("O0")
static bool cin_data(uint8_t *data, uint8_t len, unsigned timeout_ms) static bool cin_data(uint8_t *data, uint8_t len, unsigned timeout_ms)