AP_HAL_SITL: and `uart_log` method and stats struct

This commit is contained in:
Iampete1 2024-04-06 17:12:19 +01:00 committed by Andrew Tridgell
parent 73f4a47496
commit 6017f372a2
2 changed files with 35 additions and 6 deletions

View File

@ -199,8 +199,8 @@ void HALSITL::Util::uart_info(ExpandingString &str)
{ {
// Calculate time since last call // Calculate time since last call
const uint32_t now_ms = AP_HAL::millis(); const uint32_t now_ms = AP_HAL::millis();
const uint32_t dt_ms = now_ms - uart_stats.last_ms; const uint32_t dt_ms = now_ms - sys_uart_stats.last_ms;
uart_stats.last_ms = now_ms; sys_uart_stats.last_ms = now_ms;
// a header to allow for machine parsers to determine format // a header to allow for machine parsers to determine format
str.printf("UARTV1\n"); str.printf("UARTV1\n");
@ -211,8 +211,27 @@ void HALSITL::Util::uart_info(ExpandingString &str)
auto *uart = hal.serial(i); auto *uart = hal.serial(i);
if (uart) { if (uart) {
str.printf("SERIAL%u ", i); str.printf("SERIAL%u ", i);
uart->uart_info(str, uart_stats.serial[i], dt_ms); uart->uart_info(str, sys_uart_stats.serial[i], dt_ms);
} }
} }
} }
#endif
#if HAL_LOGGING_ENABLED
// Log UART message for each serial port
void HALSITL::Util::uart_log()
{
// Calculate time since last call
const uint32_t now_ms = AP_HAL::millis();
const uint32_t dt_ms = now_ms - log_uart_stats.last_ms;
log_uart_stats.last_ms = now_ms;
// Loop over all ports
for (uint8_t i = 0; i < hal.num_serial; i++) {
auto *uart = hal.serial(i);
if (uart) {
uart->log_stats(i, log_uart_stats.serial[i], dt_ms);
}
}
}
#endif // HAL_LOGGING_ENABLED
#endif // HAL_UART_STATS_ENABLED

View File

@ -5,6 +5,7 @@
#include "AP_HAL_SITL.h" #include "AP_HAL_SITL.h"
#include "Semaphores.h" #include "Semaphores.h"
#include "ToneAlarm_SF.h" #include "ToneAlarm_SF.h"
#include <AP_Logger/AP_Logger_config.h>
#if !defined(__CYGWIN__) && !defined(__CYGWIN64__) #if !defined(__CYGWIN__) && !defined(__CYGWIN64__)
#include <sys/types.h> #include <sys/types.h>
@ -110,14 +111,23 @@ private:
#if HAL_UART_STATS_ENABLED #if HAL_UART_STATS_ENABLED
// request information on uart I/O // request information on uart I/O
void uart_info(ExpandingString &str) override; void uart_info(ExpandingString &str) override;
#if HAL_LOGGING_ENABLED
// Log UART message for each serial port
void uart_log() override;
#endif #endif
#endif // HAL_UART_STATS_ENABLED
private: private:
#if HAL_UART_STATS_ENABLED #if HAL_UART_STATS_ENABLED
// UART stats tracking helper // UART stats tracking helper
struct { struct uart_stats {
AP_HAL::UARTDriver::StatsTracker serial[AP_HAL::HAL::num_serial]; AP_HAL::UARTDriver::StatsTracker serial[AP_HAL::HAL::num_serial];
uint32_t last_ms; uint32_t last_ms;
} uart_stats; };
uart_stats sys_uart_stats;
#if HAL_LOGGING_ENABLED
uart_stats log_uart_stats;
#endif #endif
#endif // HAL_UART_STATS_ENABLED
}; };