mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: UARTDriver: add getters for cumulative tx and rx counts
This commit is contained in:
parent
7dd2529683
commit
e970a6cb5d
@ -145,6 +145,12 @@ protected:
|
|||||||
void _flush() override;
|
void _flush() override;
|
||||||
bool _discard_input() override;
|
bool _discard_input() override;
|
||||||
|
|
||||||
|
#if HAL_UART_STATS_ENABLED
|
||||||
|
// Getters for cumulative tx and rx counts
|
||||||
|
uint32_t get_total_tx_bytes() const override { return _tx_stats_bytes; }
|
||||||
|
uint32_t get_total_rx_bytes() const override { return _rx_stats_bytes; }
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void handle_writing_from_writebuffer_to_device();
|
void handle_writing_from_writebuffer_to_device();
|
||||||
void handle_reading_from_device_to_readbuffer();
|
void handle_reading_from_device_to_readbuffer();
|
||||||
|
Loading…
Reference in New Issue
Block a user