mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: check VBUS for fast boot
This commit is contained in:
parent
3eb164fb6a
commit
891cc94577
|
@ -106,6 +106,14 @@ int main(void)
|
||||||
try_boot = false;
|
try_boot = false;
|
||||||
timeout = 0;
|
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
|
#endif
|
||||||
|
|
||||||
// if we fail to boot properly we want to pause in bootloader to give
|
// if we fail to boot properly we want to pause in bootloader to give
|
||||||
|
|
Loading…
Reference in New Issue