AP_Filesystem: fixed set_mtime semaphore
This commit is contained in:
parent
552a06dab7
commit
184b3e1d63
@ -815,6 +815,8 @@ bool AP_Filesystem::set_mtime(const char *filename, const time_t mtime_sec)
|
||||
fno.fdate = fdate;
|
||||
fno.ftime = ftime;
|
||||
|
||||
WITH_SEMAPHORE(sem);
|
||||
|
||||
return f_utime(filename, (FILINFO *)&fno) == FR_OK;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user