From 891cc945770e54636096a55e78a54a740bdd7bf0 Mon Sep 17 00:00:00 2001 From: liang <466175335@qq.com> Date: Sun, 29 Sep 2019 02:15:15 -0700 Subject: [PATCH] AP_Bootloader: check VBUS for fast boot --- Tools/AP_Bootloader/AP_Bootloader.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/Tools/AP_Bootloader/AP_Bootloader.cpp b/Tools/AP_Bootloader/AP_Bootloader.cpp index 1ce163b47e..96023a1bef 100644 --- a/Tools/AP_Bootloader/AP_Bootloader.cpp +++ b/Tools/AP_Bootloader/AP_Bootloader.cpp @@ -107,7 +107,15 @@ int main(void) timeout = 0; } #endif - +#if defined(HAL_GPIO_PIN_VBUS) && defined(HAL_ENABLE_VBUS_CHECK) +#if HAL_USE_SERIAL_USB == TRUE + else if (palReadLine(HAL_GPIO_PIN_VBUS) == 0) { + try_boot = true; + timeout = 0; + } +#endif +#endif + // if we fail to boot properly we want to pause in bootloader to give // a chance to load new app code set_fast_reboot(RTC_BOOT_OFF);