AP_HAL_Linux: allow PeriodicThread to stop

This takes the simplest approach of just waiting for the next time we
will process events.
This commit is contained in:
Lucas De Marchi 2016-10-26 11:14:28 -02:00
parent 20650e14b7
commit 3b2de6de46
2 changed files with 17 additions and 1 deletions

View File

@ -235,7 +235,7 @@ bool PeriodicThread::_run()
uint64_t next_run_usec = AP_HAL::micros64() + _period_usec;
while (true) {
while (!_should_exit) {
uint64_t dt = next_run_usec - AP_HAL::micros64();
if (dt > _period_usec) {
// we've lost sync - restart
@ -248,6 +248,20 @@ bool PeriodicThread::_run()
_task();
}
_started = false;
_should_exit = false;
return true;
}
bool PeriodicThread::stop()
{
if (!is_started()) {
return false;
}
_should_exit = true;
return true;
}

View File

@ -80,6 +80,8 @@ public:
bool set_rate(uint32_t rate_hz);
bool stop() override;
protected:
bool _run() override;