AP_Radio: expect delay whil resetting radios

This commit is contained in:
Peter Barker 2019-11-26 14:11:53 +11:00 committed by Peter Barker
parent 73c56220ff
commit 306aa5b654
1 changed files with 1 additions and 0 deletions

View File

@ -290,6 +290,7 @@ bool AP_Radio_cypress::reset(void)
to reset radio hold reset high for 0.5s, then low for 0.5s to reset radio hold reset high for 0.5s, then low for 0.5s
*/ */
#if defined(HAL_GPIO_RADIO_RESET) #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.gpio->write(HAL_GPIO_RADIO_RESET, 1);
hal.scheduler->delay(500); hal.scheduler->delay(500);
hal.gpio->write(HAL_GPIO_RADIO_RESET, 0); hal.gpio->write(HAL_GPIO_RADIO_RESET, 0);