From ca4af948333968abf5804f10e0c483199dbeee50 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 11 May 2020 11:42:19 +1000 Subject: [PATCH] AP_Logger: prevent potential infinite recursion in log-open codepath If anything in start_new_log did logging (for example, by sending a statustext), we end up infinitely recursing. With the patch: diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 69b8ef0431..eb422d10f8 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -778,6 +778,7 @@ void AP_Logger_File::PrepForArming() */ void AP_Logger_File::start_new_log(void) { + gcs().send_text(MAV_SEVERITY_WARNING, "Starting new log"); stop_logging(); start_new_log_reset_variables(); pbarker@bluebottle:~/rc/ardupilot(master)$ We see: at ../../libraries/AP_Logger/AP_Logger_File.cpp:781 this=0x555555ad9d30, pBuffer=0x7fffff8209d0, size=75, is_critical=true) at ../../libraries/AP_Logger/AP_Logger_Backend.cpp:372 this=0x555555ad9d30, pBuffer=0x7fffff8209d0, size=75) at ../../libraries/AP_Logger/AP_Logger_Backend.h:32 this=0x555555ad9d30, message=0x7fffff820b10 "Starting new log") at ../../libraries/AP_Logger/LogFile.cpp:466 this=0x555555a6d758 , message=0x7fffff820b10 "Starting new log") at ../../libraries/AP_Logger/AP_Logger.cpp:752 this=0x555555a6e708 , severity=MAV_SEVERITY_WARNING, fmt=0x5555557d64d0 "Starting new log", arg_list=0x7fffff820be0, dest_bitmask=1 '\001') at ../../libraries/GCS_MAVLink/GCS_Common.cpp:1847 this=0x555555a6e708 , severity=MAV_SEVERITY_WARNING, fmt=0x5555557d64d0 "Starting new log", arg_list=0x7fffff820be0) at ../../libraries/GCS_MAVLink/GCS.cpp:53 this=0x555555a6e708 , severity=MAV_SEVERITY_WARNING, fmt=0x5555557d64d0 "Starting new log") at ../../libraries/GCS_MAVLink/GCS.cpp:60 at ../../libraries/AP_Logger/AP_Logger_File.cpp:781 this=0x555555ad9d30, pBuffer=0x7fffff820dc0, size=75, is_critical=true) at ../../libraries/AP_Logger/AP_Logger_Backend.cpp:372 I'm not aware of any instances in the code where this will actually happen - but it could easily sneak in. --- libraries/AP_Logger/AP_Logger_File.cpp | 25 +++++++++++++------------ 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 69b8ef0431..98a7703881 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -778,16 +778,24 @@ void AP_Logger_File::PrepForArming() */ void AP_Logger_File::start_new_log(void) { - stop_logging(); - - start_new_log_reset_variables(); - if (_open_error) { // we have previously failed to open a file - don't try again // to prevent us trying to open files while in flight return; } + // set _open_error here to avoid infinite recursion. Simply + // writing a prioritised block may try to open a log - which means + // if anything in the start_new_log path does a gcs().send_text() + // (for example), you will end up recursing if we don't take + // precautions. We will reset _open_error if we actually manage + // to open the log... + _open_error = true; + + stop_logging(); + + start_new_log_reset_variables(); + if (_read_fd != -1) { AP::FS().close(_read_fd); _read_fd = -1; @@ -795,7 +803,6 @@ void AP_Logger_File::start_new_log(void) if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) { hal.console->printf("Out of space for logging\n"); - _open_error = true; return; } @@ -808,7 +815,6 @@ void AP_Logger_File::start_new_log(void) log_num = 1; } if (!write_fd_semaphore.take(1)) { - _open_error = true; return; } if (_write_filename) { @@ -817,7 +823,6 @@ void AP_Logger_File::start_new_log(void) } _write_filename = _log_file_name(log_num); if (_write_filename == nullptr) { - _open_error = true; write_fd_semaphore.give(); return; } @@ -834,7 +839,6 @@ void AP_Logger_File::start_new_log(void) if (_write_fd == -1) { _initialised = false; - _open_error = true; write_fd_semaphore.give(); int saved_errno = errno; ::printf("Log open fail for %s - %s\n", @@ -851,13 +855,10 @@ void AP_Logger_File::start_new_log(void) // now update lastlog.txt with the new log number char *fname = _lastlog_file_name(); - // we avoid fopen()/fprintf() here as it is not available on as many - // systems as open/write EXPECT_DELAY_MS(3000); int fd = AP::FS().open(fname, O_WRONLY|O_CREAT); free(fname); if (fd == -1) { - _open_error = true; return; } @@ -868,9 +869,9 @@ void AP_Logger_File::start_new_log(void) AP::FS().close(fd); if (written < to_write) { - _open_error = true; return; } + _open_error = false; return; }