Browse Source

AP_HAL_Linux: allow PollerThread to stop

master
Lucas De Marchi 8 years ago
parent
commit
20650e14b7
  1. 17
      libraries/AP_HAL_Linux/PollerThread.cpp
  2. 2
      libraries/AP_HAL_Linux/PollerThread.h
  3. 3
      libraries/AP_HAL_Linux/Thread.h

17
libraries/AP_HAL_Linux/PollerThread.cpp

@ -140,10 +140,25 @@ void PollerThread::mainloop() @@ -140,10 +140,25 @@ void PollerThread::mainloop()
return;
}
while (true) {
while (!_should_exit) {
_poller.poll();
_cleanup_timers();
}
_started = false;
_should_exit = false;
}
bool PollerThread::stop()
{
if (!is_started()) {
return false;
}
_should_exit = true;
_poller.wakeup();
return true;
}
}

2
libraries/AP_HAL_Linux/PollerThread.h

@ -72,6 +72,8 @@ public: @@ -72,6 +72,8 @@ public:
void mainloop();
bool stop() override;
protected:
void _cleanup_timers();

3
libraries/AP_HAL_Linux/Thread.h

@ -45,6 +45,8 @@ public: @@ -45,6 +45,8 @@ public:
bool set_stack_size(size_t stack_size);
virtual bool stop() { return false; }
protected:
static void *_run_trampoline(void *arg);
@ -59,6 +61,7 @@ protected: @@ -59,6 +61,7 @@ protected:
task_t _task;
bool _started = false;
bool _should_exit = false;
pthread_t _ctx = 0;
struct stack_debug {

Loading…
Cancel
Save