mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
HAL_Linux: prevent time from going backwards in Replay
This commit is contained in:
parent
d7000c4105
commit
179e47c618
@ -416,8 +416,10 @@ void LinuxScheduler::reboot(bool hold_in_bootloader)
|
|||||||
|
|
||||||
void LinuxScheduler::stop_clock(uint64_t time_usec)
|
void LinuxScheduler::stop_clock(uint64_t time_usec)
|
||||||
{
|
{
|
||||||
stopped_clock_usec = time_usec;
|
if (time_usec >= stopped_clock_usec) {
|
||||||
_run_io();
|
stopped_clock_usec = time_usec;
|
||||||
|
_run_io();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
Loading…
Reference in New Issue
Block a user