mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 16:08:28 -04:00
AP_Filesystem: FATFS: remove redundant delay expectations
The delays will be canceled on return by the EXPECT_DELAY_MS(3000) destructor at the start of the function. The current behavior will unexpectedly cancel delays from higher levels up the stack and is likely not what was intended.
This commit is contained in:
parent
d230e9c552
commit
c57ac3b916
@ -254,7 +254,6 @@ static bool remount_file_system(void)
|
||||
}
|
||||
if (!sdcard_retry()) {
|
||||
remount_needed = true;
|
||||
EXPECT_DELAY_MS(0);
|
||||
return false;
|
||||
}
|
||||
remount_needed = false;
|
||||
@ -278,7 +277,6 @@ static bool remount_file_system(void)
|
||||
f_lseek(fh, offset);
|
||||
}
|
||||
}
|
||||
EXPECT_DELAY_MS(0);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user