mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
AP_HAL_Linux: allow PollerThread to stop
This commit is contained in:
parent
da65a5c349
commit
20650e14b7
@ -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;
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -72,6 +72,8 @@ public:
|
||||
|
||||
void mainloop();
|
||||
|
||||
bool stop() override;
|
||||
|
||||
protected:
|
||||
void _cleanup_timers();
|
||||
|
||||
|
@ -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:
|
||||
|
||||
task_t _task;
|
||||
bool _started = false;
|
||||
bool _should_exit = false;
|
||||
pthread_t _ctx = 0;
|
||||
|
||||
struct stack_debug {
|
||||
|
Loading…
Reference in New Issue
Block a user