mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Radio: expect delay whil resetting radios
This commit is contained in:
parent
73c56220ff
commit
306aa5b654
@ -290,6 +290,7 @@ bool AP_Radio_cypress::reset(void)
|
||||
to reset radio hold reset high for 0.5s, then low for 0.5s
|
||||
*/
|
||||
#if defined(HAL_GPIO_RADIO_RESET)
|
||||
hal.scheduler->expect_delay_ms(2000); // avoid main-loop-delay internal error
|
||||
hal.gpio->write(HAL_GPIO_RADIO_RESET, 1);
|
||||
hal.scheduler->delay(500);
|
||||
hal.gpio->write(HAL_GPIO_RADIO_RESET, 0);
|
||||
|
Loading…
Reference in New Issue
Block a user