From 8dc6b758f39dff98ea59da97c99536999db30f51 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Nov 2013 14:41:24 +1100 Subject: [PATCH] HAL_PX4: switch to delay_microseconds_semaphore() for UART timer this may prevent some timing jitter on the GPS UARTs --- libraries/AP_HAL_PX4/Scheduler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index 1e35bf6c66..795910f74e 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -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();