mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_HAL_ChibiOS: Changing the timeout detection
This commit is contained in:
parent
10b7988092
commit
124d8c7fdf
@ -342,7 +342,7 @@ bool Storage::_flash_erase_ok(void)
|
||||
bool Storage::healthy(void)
|
||||
{
|
||||
return ((_initialisedType != StorageBackend::None) &&
|
||||
(AP_HAL::millis() - (_last_empty_ms < 2000)));
|
||||
(AP_HAL::millis() - _last_empty_ms < 2000u));
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user