diff --git a/libraries/AP_HAL_QURT/Scheduler.cpp b/libraries/AP_HAL_QURT/Scheduler.cpp index 5e790f7db0..07396498c9 100644 --- a/libraries/AP_HAL_QURT/Scheduler.cpp +++ b/libraries/AP_HAL_QURT/Scheduler.cpp @@ -237,10 +237,11 @@ void *Scheduler::_uart_thread(void *arg) // process any pending serial bytes //((UARTDriver *)hal.uartA)->timer_tick(); - ((UARTDriver *)hal.uartB)->timer_tick(); - ((UARTDriver *)hal.uartC)->timer_tick(); - ((UARTDriver *)hal.uartD)->timer_tick(); - ((UARTDriver *)hal.uartE)->timer_tick(); + hal.uartB->timer_tick(); + hal.uartC->timer_tick(); + hal.uartD->timer_tick(); + hal.uartE->timer_tick(); + hal.uartF->timer_tick(); } return nullptr; } diff --git a/libraries/AP_HAL_QURT/UARTDriver.cpp b/libraries/AP_HAL_QURT/UARTDriver.cpp index ee0fd00e30..f61655cf17 100644 --- a/libraries/AP_HAL_QURT/UARTDriver.cpp +++ b/libraries/AP_HAL_QURT/UARTDriver.cpp @@ -269,7 +269,7 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size) push any pending bytes to/from the serial port. This is called at 1kHz in the timer thread */ -void UARTDriver::timer_tick(void) +void UARTDriver::_timer_tick(void) { uint16_t n; diff --git a/libraries/AP_HAL_QURT/UARTDriver.h b/libraries/AP_HAL_QURT/UARTDriver.h index f1c2965cad..c6e22e74ad 100644 --- a/libraries/AP_HAL_QURT/UARTDriver.h +++ b/libraries/AP_HAL_QURT/UARTDriver.h @@ -48,7 +48,7 @@ public: void _read_callback(char *buf, size_t size); - void timer_tick(void); + void _timer_tick(void) override; private: const char *devname;