mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
HAL_Linux: fixed stopped clock delay
This commit is contained in:
parent
9b53db66cb
commit
78ff078988
@ -87,8 +87,10 @@ void LinuxScheduler::_microsleep(uint32_t usec)
|
|||||||
|
|
||||||
void LinuxScheduler::delay(uint16_t ms)
|
void LinuxScheduler::delay(uint16_t ms)
|
||||||
{
|
{
|
||||||
uint32_t old_stop = stopped_clock_ms;
|
if (stopped_clock_ms) {
|
||||||
stopped_clock_ms = 0;
|
stopped_clock_ms += ms;
|
||||||
|
return;
|
||||||
|
}
|
||||||
uint32_t start = millis();
|
uint32_t start = millis();
|
||||||
|
|
||||||
while ((millis() - start) < ms) {
|
while ((millis() - start) < ms) {
|
||||||
@ -100,7 +102,6 @@ void LinuxScheduler::delay(uint16_t ms)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
stopped_clock_ms = old_stop;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t LinuxScheduler::millis()
|
uint32_t LinuxScheduler::millis()
|
||||||
|
Loading…
Reference in New Issue
Block a user