drivers device move locking to cdev

This commit is contained in:
Daniel Agar 2017-11-09 16:33:11 -05:00 committed by Lorenz Meier
parent bf435fc520
commit 2aeb4aa55f
5 changed files with 75 additions and 173 deletions

View File

@ -48,19 +48,16 @@ namespace device
{
CDev::CDev(const char *name, const char *devname) :
// base class
Device(name),
// public
// protected
_pub_blocked(false),
// private
_devname(devname),
_registered(false),
_max_pollwaiters(0),
_open_count(0),
_pollset(nullptr)
_devname(devname)
{
DEVICE_DEBUG("CDev::CDev");
int ret = px4_sem_init(&_lock, 0, 1);
if (ret != 0) {
PX4_WARN("SEM INIT FAIL: ret %d", ret);
}
}
CDev::~CDev()
@ -74,6 +71,8 @@ CDev::~CDev()
if (_pollset) {
delete[](_pollset);
}
px4_sem_destroy(&_lock);
}
int

View File

@ -160,16 +160,6 @@ public:
*/
virtual int poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup);
/**
* Test whether the device is currently open.
*
* This can be used to avoid tearing down a device that is still active.
* Note - not virtual, cannot be overridden by a subclass.
*
* @return True if the device is currently open.
*/
bool is_open() { return _open_count > 0; }
protected:
/**
* Pointer to the default cdev file operations table; useful for
@ -261,15 +251,40 @@ protected:
*/
const char *get_devname() { return _devname; }
/**
* Take the driver lock.
*
* Each driver instance has its own lock/semaphore.
*
* Note that we must loop as the wait may be interrupted by a signal.
*
* Careful: lock() calls cannot be nested!
*/
void lock()
{
do {} while (px4_sem_wait(&_lock) != 0);
}
/**
* Release the driver lock.
*/
void unlock()
{
px4_sem_post(&_lock);
}
px4_sem_t _lock; /**< lock to protect access to all class members (also for derived classes) */
bool _pub_blocked{false}; /**< true if publishing should be blocked */
private:
const char *_devname; /**< device node name */
bool _registered{false}; /**< true if device name was registered */
uint8_t _max_pollwaiters; /**< size of the _pollset array */
uint16_t _open_count; /**< number of successful opens */
px4_pollfd_struct_t **_pollset;
uint8_t _max_pollwaiters{0}; /**< size of the _pollset array */
uint16_t _open_count{0}; /**< number of successful opens */
px4_pollfd_struct_t **_pollset{nullptr};
/**
* Store a pollwaiter in a slot where we can find it later.

View File

@ -35,7 +35,6 @@ set(SRCS)
list(APPEND SRCS
CDev.cpp
Device.cpp
ringbuffer.cpp
integrator.cpp
)

View File

@ -1,108 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2014 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 device.cpp
*
* Fundamental driver base class for the device framework.
*/
#include "Device.hpp"
#include "px4_log.h"
#include <stdio.h>
#include <unistd.h>
#include <drivers/drv_device.h>
namespace device
{
Device::Device(const char *name) :
// public
// protected
_name(name),
_debug_enabled(false)
{
int ret = px4_sem_init(&_lock, 0, 1);
if (ret != 0) {
PX4_WARN("SEM INIT FAIL: ret %d", ret);
}
/* setup a default device ID. When bus_type is UNKNOWN the
other fields are invalid */
_device_id.devid = 0;
_device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
_device_id.devid_s.bus = 0;
_device_id.devid_s.address = 0;
_device_id.devid_s.devtype = 0;
}
Device::~Device()
{
px4_sem_destroy(&_lock);
}
int
Device::init()
{
int ret = OK;
return ret;
}
int
Device::read(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
int
Device::write(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
int
Device::ioctl(unsigned operation, unsigned &arg)
{
switch (operation) {
case DEVIOCGDEVICEID:
return (int)_device_id.devid;
}
return -ENODEV;
}
} // namespace device

View File

@ -46,6 +46,8 @@
#include <px4_config.h>
#include <px4_posix.h>
#include <drivers/drv_device.h>
#define DEVICE_LOG(FMT, ...) PX4_LOG_NAMED(_name, FMT, ##__VA_ARGS__)
#define DEVICE_DEBUG(FMT, ...) PX4_LOG_NAMED_COND(_name, _debug_enabled, FMT, ##__VA_ARGS__)
@ -68,7 +70,7 @@ public:
*
* Public so that anonymous devices can be destroyed.
*/
virtual ~Device();
virtual ~Device() = default;
/*
* Direct access methods.
@ -79,7 +81,7 @@ public:
*
* @return OK if the driver initialized OK, negative errno otherwise;
*/
virtual int init();
virtual int init() { return PX4_OK; }
/**
* Read directly from the device.
@ -91,7 +93,7 @@ public:
* @param count The number of items to read.
* @return The number of items read on success, negative errno otherwise.
*/
virtual int read(unsigned address, void *data, unsigned count);
virtual int read(unsigned address, void *data, unsigned count) { return -ENODEV; }
/**
* Write directly to the device.
@ -103,7 +105,7 @@ public:
* @param count The number of items to write.
* @return The number of items written on success, negative errno otherwise.
*/
virtual int write(unsigned address, void *data, unsigned count);
virtual int write(unsigned address, void *data, unsigned count) { return -ENODEV; }
/**
* Perform a device-specific operation.
@ -112,7 +114,15 @@ public:
* @param arg An argument to the operation.
* @return Negative errno on error, OK or positive value on success.
*/
virtual int ioctl(unsigned operation, unsigned &arg);
virtual int ioctl(unsigned operation, unsigned &arg)
{
switch (operation) {
case DEVIOCGDEVICEID:
return (int)_device_id.devid;
}
return -ENODEV;
}
/** Device bus types for DEVID */
enum DeviceBusType {
@ -150,6 +160,8 @@ public:
*/
virtual void set_device_type(uint8_t devtype) { _device_id.devid_s.devtype = devtype; }
//virtual bool external() = 0;
/*
broken out device elements. The bitfields are used to keep
the overall value small enough to fit in a float accurately,
@ -169,51 +181,36 @@ public:
};
protected:
const char *_name; /**< driver name */
char *_lock_name; /**< name of the semaphore */
bool _debug_enabled; /**< if true, debug messages are printed */
union DeviceId _device_id; /**< device identifier information */
/**
* Constructor
*
* @param name Driver name
*/
Device(const char *name);
const char *_name; /**< driver name */
bool _debug_enabled{false}; /**< if true, debug messages are printed */
/**
* Take the driver lock.
*
* Each driver instance has its own lock/semaphore.
*
* Note that we must loop as the wait may be interrupted by a signal.
*
* Careful: lock() calls cannot be nested!
*/
void lock()
Device(const char *name) : _name(name)
{
do {} while (px4_sem_wait(&_lock) != 0);
/* setup a default device ID. When bus_type is UNKNOWN the
other fields are invalid */
_device_id.devid = 0;
_device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
_device_id.devid_s.bus = 0;
_device_id.devid_s.address = 0;
_device_id.devid_s.devtype = 0;
}
/**
* Release the driver lock.
*/
void unlock()
Device(DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype = 0)
{
px4_sem_post(&_lock);
_device_id.devid = 0;
_device_id.devid_s.bus_type = bus_type;
_device_id.devid_s.bus = bus;
_device_id.devid_s.address = address;
_device_id.devid_s.devtype = devtype;
}
DeviceId &get_device_id() { return _device_id; }
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 */
Device(const Device &);
/** disable assignment for this and all subclasses */
Device &operator = (const Device &);
// no copy, assignment, move, move assignment
Device(const Device &) = delete;
Device &operator=(const Device &) = delete;
Device(Device &&) = delete;
Device &operator=(Device &&) = delete;
};