AP_HAL_Linux: Thread: allow to override run method

This commit is contained in:
Lucas De Marchi 2016-02-02 21:08:26 -02:00
parent a183ff8d32
commit 66e6cd60d8
2 changed files with 19 additions and 2 deletions

View File

@ -33,12 +33,22 @@ namespace Linux {
void *Thread::_run_trampoline(void *arg)
{
Thread *thread = static_cast<Thread *>(arg);
thread->_task();
thread->_run();
return nullptr;
}
bool Thread::_run()
{
if (!_task) {
return false;
}
_task();
return true;
}
bool Thread::start(const char *name, int policy, int prio)
{
if (_started) {

View File

@ -43,6 +43,13 @@ public:
protected:
static void *_run_trampoline(void *arg);
/*
* Run the task assigned in the constructor. May be overriden in case it's
* preferred to use Thread as an interface or when user wants to aggregate
* some initialization or teardown for the thread.
*/
virtual bool _run();
task_t _task;
bool _started;
pthread_t _ctx;