Browse Source

HAL_PX4: added Semaphore_Recursive

master
Andrew Tridgell 7 years ago
parent
commit
1397c85f8e
  1. 1
      libraries/AP_HAL_PX4/AP_HAL_PX4_Namespace.h
  2. 15
      libraries/AP_HAL_PX4/Semaphores.cpp
  3. 12
      libraries/AP_HAL_PX4/Semaphores.h

1
libraries/AP_HAL_PX4/AP_HAL_PX4_Namespace.h

@ -15,6 +15,7 @@ namespace PX4 { @@ -15,6 +15,7 @@ namespace PX4 {
class PX4I2CDriver;
class PX4_I2C;
class Semaphore;
class Semaphore_Recursive;
class PX4CAN;
class PX4CANManager;
}

15
libraries/AP_HAL_PX4/Semaphores.cpp

@ -9,6 +9,21 @@ extern const AP_HAL::HAL& hal; @@ -9,6 +9,21 @@ extern const AP_HAL::HAL& hal;
using namespace PX4;
// construct a semaphore
Semaphore::Semaphore()
{
pthread_mutex_init(&_lock, nullptr);
}
// construct a recursive semaphore (allows a thread to take it more than once)
Semaphore_Recursive::Semaphore_Recursive()
{
pthread_mutexattr_t attr;
pthread_mutexattr_init(&attr);
pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE);
pthread_mutex_init(&_lock, &attr);
}
bool Semaphore::give()
{
return pthread_mutex_unlock(&_lock) == 0;

12
libraries/AP_HAL_PX4/Semaphores.h

@ -9,13 +9,17 @@ @@ -9,13 +9,17 @@
class PX4::Semaphore : public AP_HAL::Semaphore {
public:
Semaphore() {
pthread_mutex_init(&_lock, nullptr);
}
Semaphore();
bool give();
bool take(uint32_t timeout_ms);
bool take_nonblocking();
private:
protected:
pthread_mutex_t _lock;
};
class PX4::Semaphore_Recursive : public PX4::Semaphore {
public:
Semaphore_Recursive();
};

Loading…
Cancel
Save