mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_Linux: throw warning if we ever stop-clock backwards
Also don't compile in the stop_clock symbol to make it clear changes in this method won't affect vehicles
This commit is contained in:
parent
0d396f4235
commit
4ebde78bbf
@ -313,13 +313,25 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
||||
exit(1);
|
||||
}
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
void Scheduler::stop_clock(uint64_t time_usec)
|
||||
{
|
||||
if (time_usec >= _stopped_clock_usec) {
|
||||
if (time_usec < _stopped_clock_usec) {
|
||||
::fprintf(stderr, "Warning: setting time backwards from (%" PRIu64 ") to (%" PRIu64 ")\n", _stopped_clock_usec, time_usec);
|
||||
return;
|
||||
}
|
||||
|
||||
_stopped_clock_usec = time_usec;
|
||||
_run_io();
|
||||
}
|
||||
}
|
||||
#else
|
||||
void Scheduler::stop_clock(uint64_t time_usec)
|
||||
{
|
||||
// stop_clock() is not called outside of Replay, but we can't
|
||||
// guard it in the header because of the vehicle-dependent-library
|
||||
// checks in waf.
|
||||
}
|
||||
#endif
|
||||
|
||||
bool Scheduler::SchedulerThread::_run()
|
||||
{
|
||||
|
@ -3,6 +3,7 @@
|
||||
#include <pthread.h>
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
#include "Semaphores.h"
|
||||
#include "Thread.h"
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user