mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-08 20:09:13 +08:00
AP_Bootloader: for fast boot don't init USB
This commit is contained in:
@@ -42,8 +42,6 @@ struct boardinfo board_info;
|
||||
|
||||
int main(void)
|
||||
{
|
||||
init_uarts();
|
||||
|
||||
board_info.board_type = APJ_BOARD_ID;
|
||||
board_info.board_rev = 0;
|
||||
board_info.fw_size = (BOARD_FLASH_SIZE - FLASH_BOOTLOADER_LOAD_KB)*1024;
|
||||
@@ -51,8 +49,6 @@ int main(void)
|
||||
board_info.fw_size = (1024 - FLASH_BOOTLOADER_LOAD_KB)*1024;
|
||||
}
|
||||
|
||||
flash_init();
|
||||
|
||||
bool try_boot = false;
|
||||
uint32_t timeout = HAL_BOOTLOADER_TIMEOUT;
|
||||
|
||||
@@ -71,6 +67,9 @@ int main(void)
|
||||
if (try_boot) {
|
||||
jump_to_app();
|
||||
}
|
||||
|
||||
init_uarts();
|
||||
flash_init();
|
||||
|
||||
while (true) {
|
||||
bootloader(timeout);
|
||||
|
||||
Reference in New Issue
Block a user