From 0619247992976762c98cef21dab4f53373f8b7d4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 19 May 2015 13:17:15 +1000 Subject: [PATCH] HAL_Linux: don't advance time in delay() and delay_microseconds() this could cause time to go backwards in Replay. Thanks to Peter for finding this --- libraries/AP_HAL_Linux/Scheduler.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index 3c46d1101f..7fa0e07262 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -125,7 +125,6 @@ void LinuxScheduler::_microsleep(uint32_t usec) void LinuxScheduler::delay(uint16_t ms) { if (stopped_clock_usec) { - stopped_clock_usec += 1000UL*ms; return; } uint64_t start = millis64(); @@ -178,7 +177,6 @@ uint32_t LinuxScheduler::micros() void LinuxScheduler::delay_microseconds(uint16_t us) { if (stopped_clock_usec) { - stopped_clock_usec += us; return; } _microsleep(us);