mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_HAL: Add StatsTracker helper
This commit is contained in:
parent
b045939f1d
commit
c64124daf9
@ -163,3 +163,13 @@ uint64_t AP_HAL::UARTDriver::receive_time_constraint_us(uint16_t nbytes)
|
|||||||
{
|
{
|
||||||
return AP_HAL::micros64();
|
return AP_HAL::micros64();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_UART_STATS_ENABLED
|
||||||
|
// Take cumulative bytes and return the change since last call
|
||||||
|
uint32_t AP_HAL::UARTDriver::StatsTracker::ByteTracker::update(uint32_t bytes)
|
||||||
|
{
|
||||||
|
const uint32_t change = bytes - last_bytes;
|
||||||
|
last_bytes = bytes;
|
||||||
|
return change;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
@ -152,8 +152,21 @@ public:
|
|||||||
virtual bool is_dma_enabled() const { return false; }
|
virtual bool is_dma_enabled() const { return false; }
|
||||||
|
|
||||||
#if HAL_UART_STATS_ENABLED
|
#if HAL_UART_STATS_ENABLED
|
||||||
|
// Helper to keep track of data usage since last call
|
||||||
|
struct StatsTracker {
|
||||||
|
class ByteTracker {
|
||||||
|
public:
|
||||||
|
// Take cumulative bytes and return the change since last call
|
||||||
|
uint32_t update(uint32_t bytes);
|
||||||
|
private:
|
||||||
|
uint32_t last_bytes;
|
||||||
|
};
|
||||||
|
ByteTracker tx;
|
||||||
|
ByteTracker rx;
|
||||||
|
};
|
||||||
|
|
||||||
// request information on uart I/O for this uart, for @SYS/uarts.txt
|
// request information on uart I/O for this uart, for @SYS/uarts.txt
|
||||||
virtual void uart_info(ExpandingString &str) {}
|
virtual void uart_info(ExpandingString &str, StatsTracker &stats, const uint32_t dt_ms) {}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user