Browse Source

HAL_PX4: switch to delay_microseconds_semaphore() for UART timer

this may prevent some timing jitter on the GPS UARTs
master
Andrew Tridgell 11 years ago
parent
commit
8dc6b758f3
  1. 2
      libraries/AP_HAL_PX4/Scheduler.cpp

2
libraries/AP_HAL_PX4/Scheduler.cpp

@ -276,7 +276,7 @@ void *PX4Scheduler::_uart_thread(void) @@ -276,7 +276,7 @@ void *PX4Scheduler::_uart_thread(void)
poll(NULL, 0, 1);
}
while (!_px4_thread_should_exit) {
poll(NULL, 0, 1);
delay_microseconds_semaphore(1000);
// process any pending serial bytes
((PX4UARTDriver *)hal.uartA)->_timer_tick();

Loading…
Cancel
Save