mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_ChibiOS: implement _timer_tick in UARTDriver
This commit is contained in:
parent
5179d13dbf
commit
865e4f3104
@ -308,12 +308,12 @@ void Scheduler::_uart_thread(void* arg)
|
||||
sched->delay_microseconds(1000);
|
||||
|
||||
// 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();
|
||||
((UARTDriver *)hal.uartF)->_timer_tick();*/
|
||||
hal.uartA->_timer_tick();
|
||||
hal.uartB->_timer_tick();
|
||||
hal.uartC->_timer_tick();
|
||||
hal.uartD->_timer_tick();
|
||||
hal.uartE->_timer_tick();
|
||||
hal.uartF->_timer_tick();
|
||||
#if HAL_WITH_IO_MCU
|
||||
uart_io._timer_tick();
|
||||
#endif
|
||||
|
@ -40,8 +40,7 @@ public:
|
||||
uint32_t available() override;
|
||||
uint32_t txspace() override;
|
||||
int16_t read() override;
|
||||
void _timer_tick(void);
|
||||
|
||||
void _timer_tick(void) override;
|
||||
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
|
Loading…
Reference in New Issue
Block a user