HAL_Linux: run timer thread at average 1kHz without drift

this avoids drift in the 1kHz timer, to avoid bias in the IMU
filtering
This commit is contained in:
Andrew Tridgell 2014-08-19 20:03:15 +10:00
parent 3c2ab31415
commit b9dc2335ee

View File

@ -235,12 +235,22 @@ void *LinuxScheduler::_timer_thread(void)
while (system_initializing()) {
poll(NULL, 0, 1);
}
/*
this aims to run at an average of 1kHz, so that it can be used
to drive 1kHz processes without drift
*/
uint32_t next_run_usec = micros() + 1000;
while (true) {
_microsleep(1000);
uint32_t dt = next_run_usec - micros();
if (dt > 2000) {
// we've lost sync - restart
next_run_usec = micros();
} else {
_microsleep(dt);
}
next_run_usec += 1000;
// run registered timers
_run_timers(true);
}
return NULL;
}