AP_Bootloader: check VBUS for fast boot

This commit is contained in:
liang 2019-09-29 02:15:15 -07:00 committed by Tom Pittenger
parent 3eb164fb6a
commit 891cc94577
1 changed files with 9 additions and 1 deletions

View File

@ -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);