HAL_PX4: switch to delay_microseconds_semaphore() for UART timer

this may prevent some timing jitter on the GPS UARTs
This commit is contained in:
Andrew Tridgell 2013-11-05 14:41:24 +11:00
parent 78604bd84e
commit 8dc6b758f3

View File

@ -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();