@ -105,9 +105,11 @@ int AP_Filesystem_Sys::open(const char *fname, int flags)
if (strcmp(fname, "memory.txt") == 0) {
hal.util->mem_info(*r.str);
}
#if HAL_UART_STATS_ENABLED
if (strcmp(fname, "uarts.txt") == 0) {
hal.util->uart_info(*r.str);
#endif
#if HAL_CANMANAGER_ENABLED
if (strcmp(fname, "can_log.txt") == 0) {
AP::can().log_retrieve(*r.str);