AP_HAL_ChibiOS: correct UART RX stats

This commit is contained in:
Andy Piper 2022-06-11 09:33:39 +01:00 committed by Andrew Tridgell
parent 064b6c8a9d
commit 4068337971

View File

@ -573,6 +573,7 @@ __RAMFUNC__ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
we have data to copy out we have data to copy out
*/ */
uart_drv->_readbuf.write(uart_drv->rx_bounce_buf[bounce_idx], len); uart_drv->_readbuf.write(uart_drv->rx_bounce_buf[bounce_idx], len);
uart_drv->_rx_stats_bytes += len;
uart_drv->receive_timestamp_update(); uart_drv->receive_timestamp_update();
} }