Browse Source

AP_Radio: expect delay whil resetting radios

zr-v5.1
Peter Barker 5 years ago committed by Peter Barker
parent
commit
306aa5b654
  1. 1
      libraries/AP_Radio/AP_Radio_cypress.cpp

1
libraries/AP_Radio/AP_Radio_cypress.cpp

@ -290,6 +290,7 @@ bool AP_Radio_cypress::reset(void) @@ -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…
Cancel
Save