From 306aa5b65429eb3d3c9b60f8199d814f1cfc570e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 26 Nov 2019 14:11:53 +1100 Subject: [PATCH] AP_Radio: expect delay whil resetting radios --- libraries/AP_Radio/AP_Radio_cypress.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Radio/AP_Radio_cypress.cpp b/libraries/AP_Radio/AP_Radio_cypress.cpp index 1d143ba7f3..8fc9c7e93c 100644 --- a/libraries/AP_Radio/AP_Radio_cypress.cpp +++ b/libraries/AP_Radio/AP_Radio_cypress.cpp @@ -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);