mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Logger: use AP::FS().set_mtime()
This commit is contained in:
parent
b489e8a655
commit
d40835c666
@ -1018,11 +1018,7 @@ void AP_Logger_File::_io_timer(void)
|
|||||||
if (_need_rtc_update) {
|
if (_need_rtc_update) {
|
||||||
uint64_t utc_usec;
|
uint64_t utc_usec;
|
||||||
if (AP::rtc().get_utc_usec(utc_usec)) {
|
if (AP::rtc().get_utc_usec(utc_usec)) {
|
||||||
struct utimbuf t {};
|
AP::FS().set_mtime(_write_filename, utc_usec/(1000U*1000U));
|
||||||
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));
|
|
||||||
_need_rtc_update = false;
|
_need_rtc_update = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user