mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_HAL_Linux: Thread: allow to override run method
This commit is contained in:
parent
a183ff8d32
commit
66e6cd60d8
@ -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) {
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user