orb: move SmartLock into global space and use it also for NuttX

This commit is contained in:
Beat Küng 2016-04-26 09:55:02 +02:00 committed by Lorenz Meier
parent 4269db73a0
commit 1ce5d795be
5 changed files with 78 additions and 33 deletions

View File

@ -188,6 +188,8 @@ protected:
* Each driver instance has its own lock/semaphore. * Each driver instance has its own lock/semaphore.
* *
* Note that we must loop as the wait may be interrupted by a signal. * Note that we must loop as the wait may be interrupted by a signal.
*
* Careful: lock() calls cannot be nested!
*/ */
void lock() void lock()
{ {
@ -202,10 +204,11 @@ protected:
sem_post(&_lock); sem_post(&_lock);
} }
sem_t _lock; /**< lock to protect access to all class members (also for derived classes) */
private: private:
int _irq; int _irq;
bool _irq_attached; bool _irq_attached;
sem_t _lock;
/** disable copy construction for this and all subclasses */ /** disable copy construction for this and all subclasses */
Device(const Device &); Device(const Device &);

View File

@ -196,29 +196,9 @@ protected:
px4_sem_post(&_lock); px4_sem_post(&_lock);
} }
/**
* @class Smart locking object that uses the same lock as lock(), but automatically
* takes the lock when created and releases the lock when the object goes out of
* scope. Use like this:
* {
* SmartLock smart_lock(*this);
* //critical section start
* ...
* //critical section end
* }
*/
class SmartLock
{
public:
SmartLock(Device &device) : _device(device) { _device.lock(); }
~SmartLock() { _device.unlock(); }
private:
Device &_device;
};
private:
px4_sem_t _lock; /**< lock to protect access to all class members (also for derived classes) */ px4_sem_t _lock; /**< lock to protect access to all class members (also for derived classes) */
private:
/** disable copy construction for this and all subclasses */ /** disable copy construction for this and all subclasses */
Device(const Device &); Device(const Device &);

View File

@ -40,6 +40,7 @@
#include "uORBUtils.hpp" #include "uORBUtils.hpp"
#include "uORBManager.hpp" #include "uORBManager.hpp"
#include "uORBCommunicator.hpp" #include "uORBCommunicator.hpp"
#include <px4_sem.hpp>
#include <stdlib.h> #include <stdlib.h>
uORB::ORBMap uORB::DeviceMaster::_node_map; uORB::ORBMap uORB::DeviceMaster::_node_map;
@ -603,9 +604,6 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
return ret; return ret;
} }
/* ensure that only one advertiser runs through this critical section */
lock();
ret = ERROR; ret = ERROR;
/* try for topic groups */ /* try for topic groups */
@ -619,11 +617,12 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
group_tries = *adv->instance; group_tries = *adv->instance;
if (group_tries >= max_group_tries) { if (group_tries >= max_group_tries) {
unlock();
return -ENOMEM; return -ENOMEM;
} }
} }
SmartLock smart_lock(_lock);
do { do {
/* if path is modifyable change try index */ /* if path is modifyable change try index */
if (adv->instance != nullptr) { if (adv->instance != nullptr) {
@ -636,7 +635,6 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
objname = strdup(meta->o_name); objname = strdup(meta->o_name);
if (objname == nullptr) { if (objname == nullptr) {
unlock();
return -ENOMEM; return -ENOMEM;
} }
@ -644,7 +642,6 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
devpath = strdup(nodepath); devpath = strdup(nodepath);
if (devpath == nullptr) { if (devpath == nullptr) {
unlock();
free((void *)objname); free((void *)objname);
return -ENOMEM; return -ENOMEM;
} }
@ -654,7 +651,6 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
/* if we didn't get a device, that's bad */ /* if we didn't get a device, that's bad */
if (node == nullptr) { if (node == nullptr) {
unlock();
free((void *)objname); free((void *)objname);
free((void *)devpath); free((void *)devpath);
return -ENOMEM; return -ENOMEM;
@ -698,9 +694,6 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
ret = -ENOMEM; ret = -ENOMEM;
} }
/* the file handle for the driver has been created, unlock */
unlock();
return ret; return ret;
} }

View File

@ -41,6 +41,7 @@
#include "uORBUtils.hpp" #include "uORBUtils.hpp"
#include "uORBManager.hpp" #include "uORBManager.hpp"
#include "uORBCommunicator.hpp" #include "uORBCommunicator.hpp"
#include <px4_sem.hpp>
#include <stdlib.h> #include <stdlib.h>
std::map<std::string, uORB::DeviceNode *> uORB::DeviceMaster::_node_map; std::map<std::string, uORB::DeviceNode *> uORB::DeviceMaster::_node_map;
@ -629,7 +630,7 @@ uORB::DeviceMaster::ioctl(device::file_t *filp, int cmd, unsigned long arg)
} }
} }
SmartLock smart_lock(*this); SmartLock smart_lock(_lock);
do { do {
/* if path is modifyable change try index */ /* if path is modifyable change try index */

68
src/platforms/px4_sem.hpp Normal file
View File

@ -0,0 +1,68 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file px4_sem.hpp
*
* C++ synchronization helpers
*/
#pragma once
#include "px4_sem.h"
/**
* @class Smart locking object that uses a semaphore. It automatically
* takes the lock when created and releases the lock when the object goes out of
* scope. Use like this:
*
* px4_sem_t my_lock;
* int ret = px4_sem_init(&my_lock, 0, 1);
* ...
*
* {
* SmartLock smart_lock(my_lock);
* //critical section start
* ...
* //critical section end
* }
*/
class SmartLock
{
public:
SmartLock(px4_sem_t &sem) : _sem(sem) { do {} while (px4_sem_wait(&_sem) != 0); }
~SmartLock() { px4_sem_post(&_sem); }
private:
px4_sem_t &_sem;
};