HAL_QURT: implement _timer_tick in UARTDriver

This commit is contained in:
Andrew Tridgell 2018-01-22 06:45:31 +11:00
parent 25ea60da69
commit e4fc0e9f62
3 changed files with 7 additions and 6 deletions

View File

@ -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;
}

View File

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

View File

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