AP_HAL: add logging of dropped incoming serial data

This commit is contained in:
Iampete1 2025-03-09 18:39:15 +00:00 committed by Andrew Tridgell
parent 434c2b3efa
commit 444cc3c8db
3 changed files with 8 additions and 2 deletions

View File

@ -11,19 +11,21 @@
// @Field: TimeUS: Time since system startup
// @Field: I: instance
// @Field: Tx: transmitted data rate bytes per second
// @Field: Rx: received data rate bytes per second
// @Field: Rx: received data rate bytes per second, this is all incoming data, it may not all be processed by the driver using this port.
// @Field: RxDp: Data rate of dropped received bytes, ideally should be 0. This is the difference between the received data rate and the processed data rate.
struct PACKED log_UART {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
float tx_rate;
float rx_rate;
float rx_drop_rate;
};
#if HAL_UART_STATS_ENABLED
#define LOG_STRUCTURE_FROM_HAL \
{ LOG_UART_MSG, sizeof(log_UART), \
"UART","QBff","TimeUS,I,Tx,Rx", "s#BB", "F---" },
"UART","QBfff","TimeUS,I,Tx,Rx,RxDp", "s#BBB", "F----" },
#else
#define LOG_STRUCTURE_FROM_HAL
#endif

View File

@ -211,6 +211,7 @@ void AP_HAL::UARTDriver::log_stats(const uint8_t inst, StatsTracker &stats, cons
// Update tracking
const uint32_t tx_bytes = stats.tx.update(total_tx_bytes);
const uint32_t rx_bytes = stats.rx.update(total_rx_bytes);
const uint32_t rx_dropped_bytes = stats.rx_dropped.update(get_total_dropped_rx_bytes());
// Assemble struct and log
struct log_UART pkt {
@ -219,6 +220,7 @@ void AP_HAL::UARTDriver::log_stats(const uint8_t inst, StatsTracker &stats, cons
instance : inst,
tx_rate : float((tx_bytes * 1000) / dt_ms),
rx_rate : float((rx_bytes * 1000) / dt_ms),
rx_drop_rate : float((rx_dropped_bytes * 1000) / dt_ms),
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}

View File

@ -171,6 +171,7 @@ public:
};
ByteTracker tx;
ByteTracker rx;
ByteTracker rx_dropped;
};
// request information on uart I/O for this uart, for @SYS/uarts.txt
@ -259,6 +260,7 @@ protected:
// 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; }
virtual uint32_t get_total_dropped_rx_bytes() const { return 0; }
#endif
private: