AP_HAL: UARTDriver: add getters for cumulative tx and rx counts

This commit is contained in:
Iampete1 2024-04-06 17:06:55 +01:00 committed by Andrew Tridgell
parent c5ecddad92
commit a4fd3980a8
1 changed files with 7 additions and 1 deletions

View File

@ -233,7 +233,13 @@ protected:
// discard incoming data on the port // discard incoming data on the port
virtual bool _discard_input(void) = 0; virtual bool _discard_input(void) = 0;
#if HAL_UART_STATS_ENABLED
// Getters for cumulative tx and rx counts
virtual uint32_t get_total_tx_bytes() const { return 0; }
virtual uint32_t get_total_rx_bytes() const { return 0; }
#endif
private: private:
// option bits for port // option bits for port
uint16_t _last_options; uint16_t _last_options;