mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: allow to join threads
This commit is contained in:
parent
3b2de6de46
commit
992abd170d
|
@ -205,6 +205,23 @@ bool Thread::is_current_thread()
|
|||
return pthread_equal(pthread_self(), _ctx);
|
||||
}
|
||||
|
||||
bool Thread::join()
|
||||
{
|
||||
void *ret;
|
||||
|
||||
if (_ctx == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (pthread_join(_ctx, &ret) != 0 ||
|
||||
(intptr_t)ret != 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool PeriodicThread::set_rate(uint32_t rate_hz)
|
||||
{
|
||||
if (_started || rate_hz == 0) {
|
||||
|
|
|
@ -47,6 +47,8 @@ public:
|
|||
|
||||
virtual bool stop() { return false; }
|
||||
|
||||
bool join();
|
||||
|
||||
protected:
|
||||
static void *_run_trampoline(void *arg);
|
||||
|
||||
|
|
Loading…
Reference in New Issue