ulog mavlink: use the px4_sem calls (needed for OSX)

This commit is contained in:
Beat Küng 2016-10-19 11:57:00 +02:00 committed by Lorenz Meier
parent 7c40c8dfd9
commit 3bb479f72e
2 changed files with 5 additions and 5 deletions

View File

@ -45,7 +45,7 @@
bool MavlinkULog::_init = false;
MavlinkULog *MavlinkULog::_instance = nullptr;
sem_t MavlinkULog::_lock;
px4_sem_t MavlinkULog::_lock;
const float MavlinkULog::_rate_calculation_delta_t = 0.1f;
@ -185,7 +185,7 @@ void MavlinkULog::initialize()
if (_init) {
return;
}
sem_init(&_lock, 1, 1);
px4_sem_init(&_lock, 1, 1);
_init = true;
}

View File

@ -105,17 +105,17 @@ private:
static void lock()
{
do {} while (sem_wait(&_lock) != 0);
do {} while (px4_sem_wait(&_lock) != 0);
}
static void unlock()
{
sem_post(&_lock);
px4_sem_post(&_lock);
}
void publish_ack(uint16_t sequence);
static sem_t _lock;
static px4_sem_t _lock;
static bool _init;
static MavlinkULog *_instance;
static const float _rate_calculation_delta_t; ///< rate update interval