mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: add method to check caller same as thread
This commit is contained in:
parent
e3beef0f77
commit
0282ebb8ff
|
@ -91,4 +91,9 @@ bool Thread::start(const char *name, int policy, int prio)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Thread::is_current_thread()
|
||||||
|
{
|
||||||
|
return pthread_equal(pthread_self(), _ctx);
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -40,6 +40,8 @@ public:
|
||||||
|
|
||||||
bool start(const char *name, int policy, int prio);
|
bool start(const char *name, int policy, int prio);
|
||||||
|
|
||||||
|
bool is_current_thread();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
static void *_run_trampoline(void *arg);
|
static void *_run_trampoline(void *arg);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue