From d40835c666aff2b48352b1e8519bf69ce284b338 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 26 Aug 2019 15:55:44 +1000 Subject: [PATCH] AP_Logger: use AP::FS().set_mtime() --- libraries/AP_Logger/AP_Logger_File.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 550635984e..5ae398c448 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -1018,11 +1018,7 @@ void AP_Logger_File::_io_timer(void) if (_need_rtc_update) { uint64_t utc_usec; if (AP::rtc().get_utc_usec(utc_usec)) { - struct utimbuf t {}; - t.modtime = utc_usec / (1000UL * 1000UL); - t.actime = t.modtime; - // we ignore return on utime() as there is nothing useful we can do - UNUSED_RESULT(utime(_write_filename, &t)); + AP::FS().set_mtime(_write_filename, utc_usec/(1000U*1000U)); _need_rtc_update = false; } }