AP_HAL_ChibiOS: use new UART stats tracking helper moving history up to util

This commit is contained in:
Iampete1 2024-03-15 14:20:43 +00:00 committed by Peter Hall
parent c64124daf9
commit edc12c2857
4 changed files with 27 additions and 14 deletions

View File

@ -1696,9 +1696,11 @@ uint16_t UARTDriver::get_options(void) const
#if HAL_UART_STATS_ENABLED
// request information on uart I/O for @SYS/uarts.txt for this uart
void UARTDriver::uart_info(ExpandingString &str)
void UARTDriver::uart_info(ExpandingString &str, StatsTracker &stats, const uint32_t dt_ms)
{
uint32_t now_ms = AP_HAL::millis();
const uint32_t tx_bytes = stats.tx.update(_tx_stats_bytes);
const uint32_t rx_bytes = stats.rx.update(_rx_stats_bytes);
if (sdef.is_usb) {
str.printf("OTG%u ", unsigned(sdef.instance));
} else {
@ -1706,14 +1708,11 @@ void UARTDriver::uart_info(ExpandingString &str)
}
str.printf("TX%c=%8u RX%c=%8u TXBD=%6u RXBD=%6u\n",
tx_dma_enabled ? '*' : ' ',
unsigned(_tx_stats_bytes),
unsigned(tx_bytes),
rx_dma_enabled ? '*' : ' ',
unsigned(_rx_stats_bytes),
unsigned(_tx_stats_bytes * 10000 / (now_ms - _last_stats_ms)),
unsigned(_rx_stats_bytes * 10000 / (now_ms - _last_stats_ms)));
_tx_stats_bytes = 0;
_rx_stats_bytes = 0;
_last_stats_ms = now_ms;
unsigned(rx_bytes),
unsigned((tx_bytes * 10000) / dt_ms),
unsigned((rx_bytes * 10000) / dt_ms));
}
#endif

View File

@ -123,7 +123,7 @@ public:
#if HAL_UART_STATS_ENABLED
// request information on uart I/O for one uart
void uart_info(ExpandingString &str) override;
void uart_info(ExpandingString &str, StatsTracker &stats, const uint32_t dt_ms) override;
#endif
/*
@ -209,7 +209,6 @@ private:
// statistics
uint32_t _tx_stats_bytes;
uint32_t _rx_stats_bytes;
uint32_t _last_stats_ms;
// we remember config options from set_options to apply on sdStart()
uint32_t _cr1_options;

View File

@ -682,18 +682,23 @@ extern ChibiOS::UARTDriver uart_io;
// request information on uart I/O
void Util::uart_info(ExpandingString &str)
{
// Calculate time since last call
const uint32_t now_ms = AP_HAL::millis();
const uint32_t dt_ms = now_ms - uart_stats.last_ms;
uart_stats.last_ms = now_ms;
// a header to allow for machine parsers to determine format
str.printf("UARTV1\n");
for (uint8_t i = 0; i < HAL_UART_NUM_SERIAL_PORTS; i++) {
auto *uart = hal.serial(i);
if (uart) {
str.printf("SERIAL%u ", i);
uart->uart_info(str);
uart->uart_info(str, uart_stats.serial[i], dt_ms);
}
}
#if HAL_WITH_IO_MCU
str.printf("IOMCU ");
uart_io.uart_info(str);
uart_io.uart_info(str, uart_stats.io, dt_ms);
#endif
}
#endif

View File

@ -98,7 +98,7 @@ public:
#endif
#if HAL_UART_STATS_ENABLED
// request information on uart I/O
virtual void uart_info(ExpandingString &str) override;
void uart_info(ExpandingString &str) override;
#endif
#if HAL_USE_PWM == TRUE
void timer_info(ExpandingString &str) override;
@ -161,4 +161,14 @@ private:
#if HAL_ENABLE_DFU_BOOT
void boot_to_dfu() override;
#endif
#if HAL_UART_STATS_ENABLED
struct {
AP_HAL::UARTDriver::StatsTracker serial[HAL_UART_NUM_SERIAL_PORTS];
#if HAL_WITH_IO_MCU
AP_HAL::UARTDriver::StatsTracker io;
#endif
uint32_t last_ms;
} uart_stats;
#endif
};