mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 09:22:18 +00:00
CDev extract from drivers Device class hierarchy
- leave CDev shim for now until all usage is updated
This commit is contained in:
@@ -37,6 +37,7 @@ px4_add_git_submodule(TARGET git_matrix PATH "matrix")
|
||||
add_subdirectory(airspeed)
|
||||
add_subdirectory(battery)
|
||||
add_subdirectory(bezier)
|
||||
add_subdirectory(cdev)
|
||||
add_subdirectory(circuit_breaker)
|
||||
add_subdirectory(controllib)
|
||||
add_subdirectory(conversion)
|
||||
|
||||
398
src/lib/cdev/CDev.cpp
Normal file
398
src/lib/cdev/CDev.cpp
Normal file
@@ -0,0 +1,398 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 CDev.cpp
|
||||
*
|
||||
* Character device base class.
|
||||
*/
|
||||
|
||||
#include "CDev.hpp"
|
||||
|
||||
#include <cstring>
|
||||
|
||||
#include <px4_posix.h>
|
||||
#include <drivers/drv_device.h>
|
||||
|
||||
namespace cdev
|
||||
{
|
||||
|
||||
CDev::CDev(const char *devname) :
|
||||
_devname(devname)
|
||||
{
|
||||
PX4_DEBUG("CDev::CDev");
|
||||
|
||||
int ret = px4_sem_init(&_lock, 0, 1);
|
||||
|
||||
if (ret != 0) {
|
||||
PX4_ERR("SEM INIT FAIL: ret %d", ret);
|
||||
}
|
||||
}
|
||||
|
||||
CDev::~CDev()
|
||||
{
|
||||
PX4_DEBUG("CDev::~CDev");
|
||||
|
||||
if (_registered) {
|
||||
unregister_driver(_devname);
|
||||
}
|
||||
|
||||
if (_pollset) {
|
||||
delete[](_pollset);
|
||||
}
|
||||
|
||||
px4_sem_destroy(&_lock);
|
||||
}
|
||||
|
||||
int
|
||||
CDev::register_class_devname(const char *class_devname)
|
||||
{
|
||||
PX4_DEBUG("CDev::register_class_devname %s", class_devname);
|
||||
|
||||
if (class_devname == nullptr) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
int class_instance = 0;
|
||||
int ret = -ENOSPC;
|
||||
|
||||
while (class_instance < 4) {
|
||||
char name[32];
|
||||
snprintf(name, sizeof(name), "%s%d", class_devname, class_instance);
|
||||
ret = register_driver(name, &fops, 0666, (void *)this);
|
||||
|
||||
if (ret == OK) {
|
||||
break;
|
||||
}
|
||||
|
||||
class_instance++;
|
||||
}
|
||||
|
||||
if (class_instance == 4) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
return class_instance;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::unregister_class_devname(const char *class_devname, unsigned class_instance)
|
||||
{
|
||||
PX4_DEBUG("CDev::unregister_class_devname");
|
||||
|
||||
char name[32];
|
||||
snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
|
||||
return unregister_driver(name);
|
||||
}
|
||||
|
||||
int
|
||||
CDev::init()
|
||||
{
|
||||
PX4_DEBUG("CDev::init");
|
||||
|
||||
int ret = PX4_OK;
|
||||
|
||||
// now register the driver
|
||||
if (_devname != nullptr) {
|
||||
ret = register_driver(_devname, &fops, 0666, (void *)this);
|
||||
|
||||
if (ret == PX4_OK) {
|
||||
_registered = true;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*
|
||||
* Default implementations of the character device interface
|
||||
*/
|
||||
int
|
||||
CDev::open(file_t *filep)
|
||||
{
|
||||
PX4_DEBUG("CDev::open");
|
||||
int ret = PX4_OK;
|
||||
|
||||
lock();
|
||||
/* increment the open count */
|
||||
_open_count++;
|
||||
|
||||
if (_open_count == 1) {
|
||||
|
||||
/* first-open callback may decline the open */
|
||||
ret = open_first(filep);
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
_open_count--;
|
||||
}
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::close(file_t *filep)
|
||||
{
|
||||
PX4_DEBUG("CDev::close");
|
||||
int ret = PX4_OK;
|
||||
|
||||
lock();
|
||||
|
||||
if (_open_count > 0) {
|
||||
/* decrement the open count */
|
||||
_open_count--;
|
||||
|
||||
/* callback cannot decline the close */
|
||||
if (_open_count == 0) {
|
||||
ret = close_last(filep);
|
||||
}
|
||||
|
||||
} else {
|
||||
ret = -EBADF;
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::ioctl(file_t *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
PX4_DEBUG("CDev::ioctl");
|
||||
int ret = -ENOTTY;
|
||||
|
||||
switch (cmd) {
|
||||
|
||||
/* fetch a pointer to the driver's private data */
|
||||
case DIOC_GETPRIV:
|
||||
*(void **)(uintptr_t)arg = (void *)this;
|
||||
ret = PX4_OK;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
|
||||
{
|
||||
PX4_DEBUG("CDev::Poll %s", setup ? "setup" : "teardown");
|
||||
int ret = PX4_OK;
|
||||
|
||||
if (setup) {
|
||||
/*
|
||||
* Save the file pointer in the pollfd for the subclass'
|
||||
* benefit.
|
||||
*/
|
||||
fds->priv = (void *)filep;
|
||||
PX4_DEBUG("CDev::poll: fds->priv = %p", filep);
|
||||
|
||||
/*
|
||||
* Lock against poll_notify() and possibly other callers (protect _pollset).
|
||||
*/
|
||||
ATOMIC_ENTER;
|
||||
|
||||
/*
|
||||
* Try to store the fds for later use and handle array resizing.
|
||||
*/
|
||||
while ((ret = store_poll_waiter(fds)) == -ENFILE) {
|
||||
|
||||
// No free slot found. Resize the pollset. This is expensive, but it's only needed initially.
|
||||
|
||||
if (_max_pollwaiters >= 256 / 2) { //_max_pollwaiters is uint8_t
|
||||
ret = -ENOMEM;
|
||||
break;
|
||||
}
|
||||
|
||||
const uint8_t new_count = _max_pollwaiters > 0 ? _max_pollwaiters * 2 : 1;
|
||||
px4_pollfd_struct_t **prev_pollset = _pollset;
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
// malloc uses a semaphore, we need to call it enabled IRQ's
|
||||
px4_leave_critical_section(flags);
|
||||
#endif
|
||||
px4_pollfd_struct_t **new_pollset = new px4_pollfd_struct_t *[new_count];
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
flags = px4_enter_critical_section();
|
||||
#endif
|
||||
|
||||
if (prev_pollset == _pollset) {
|
||||
// no one else updated the _pollset meanwhile, so we're good to go
|
||||
if (!new_pollset) {
|
||||
ret = -ENOMEM;
|
||||
break;
|
||||
}
|
||||
|
||||
if (_max_pollwaiters > 0) {
|
||||
memset(new_pollset + _max_pollwaiters, 0, sizeof(px4_pollfd_struct_t *) * (new_count - _max_pollwaiters));
|
||||
memcpy(new_pollset, _pollset, sizeof(px4_pollfd_struct_t *) * _max_pollwaiters);
|
||||
}
|
||||
|
||||
_pollset = new_pollset;
|
||||
_pollset[_max_pollwaiters] = fds;
|
||||
_max_pollwaiters = new_count;
|
||||
|
||||
// free the previous _pollset (we need to unlock here which is fine because we don't access _pollset anymore)
|
||||
#ifdef __PX4_NUTTX
|
||||
px4_leave_critical_section(flags);
|
||||
#endif
|
||||
|
||||
if (prev_pollset) {
|
||||
delete[](prev_pollset);
|
||||
}
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
flags = px4_enter_critical_section();
|
||||
#endif
|
||||
|
||||
// Success
|
||||
ret = PX4_OK;
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
px4_leave_critical_section(flags);
|
||||
#endif
|
||||
// We have to retry
|
||||
delete[] new_pollset;
|
||||
#ifdef __PX4_NUTTX
|
||||
flags = px4_enter_critical_section();
|
||||
#endif
|
||||
}
|
||||
|
||||
if (ret == PX4_OK) {
|
||||
|
||||
/*
|
||||
* Check to see whether we should send a poll notification
|
||||
* immediately.
|
||||
*/
|
||||
fds->revents |= fds->events & poll_state(filep);
|
||||
|
||||
/* yes? post the notification */
|
||||
if (fds->revents != 0) {
|
||||
px4_sem_post(fds->sem);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
ATOMIC_LEAVE;
|
||||
|
||||
} else {
|
||||
ATOMIC_ENTER;
|
||||
/*
|
||||
* Handle a teardown request.
|
||||
*/
|
||||
ret = remove_poll_waiter(fds);
|
||||
ATOMIC_LEAVE;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
CDev::poll_notify(pollevent_t events)
|
||||
{
|
||||
PX4_DEBUG("CDev::poll_notify events = %0x", events);
|
||||
|
||||
/* lock against poll() as well as other wakeups */
|
||||
ATOMIC_ENTER;
|
||||
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (nullptr != _pollset[i]) {
|
||||
poll_notify_one(_pollset[i], events);
|
||||
}
|
||||
}
|
||||
|
||||
ATOMIC_LEAVE;
|
||||
}
|
||||
|
||||
void
|
||||
CDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
|
||||
{
|
||||
PX4_DEBUG("CDev::poll_notify_one");
|
||||
|
||||
/* update the reported event set */
|
||||
fds->revents |= fds->events & events;
|
||||
|
||||
PX4_DEBUG(" Events fds=%p %0x %0x %0x", fds, fds->revents, fds->events, events);
|
||||
|
||||
if (fds->revents != 0) {
|
||||
px4_sem_post(fds->sem);
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
CDev::store_poll_waiter(px4_pollfd_struct_t *fds)
|
||||
{
|
||||
// Look for a free slot.
|
||||
PX4_DEBUG("CDev::store_poll_waiter");
|
||||
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (nullptr == _pollset[i]) {
|
||||
|
||||
/* save the pollfd */
|
||||
_pollset[i] = fds;
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
}
|
||||
|
||||
return -ENFILE;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
|
||||
{
|
||||
PX4_DEBUG("CDev::remove_poll_waiter");
|
||||
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (fds == _pollset[i]) {
|
||||
|
||||
_pollset[i] = nullptr;
|
||||
return PX4_OK;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
PX4_DEBUG("poll: bad fd state");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
} // namespace cdev
|
||||
300
src/lib/cdev/CDev.hpp
Normal file
300
src/lib/cdev/CDev.hpp
Normal file
@@ -0,0 +1,300 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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 CDev.hpp
|
||||
*
|
||||
* Definitions for the generic base classes in the device framework.
|
||||
*/
|
||||
|
||||
#ifndef _CDEV_HPP
|
||||
#define _CDEV_HPP
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
#include "nuttx/cdev_platform.hpp"
|
||||
#else
|
||||
#include "posix/cdev_platform.hpp"
|
||||
#endif
|
||||
|
||||
namespace cdev
|
||||
{
|
||||
|
||||
/**
|
||||
* Abstract class for any character device
|
||||
*/
|
||||
class __EXPORT CDev
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
*/
|
||||
CDev(const char *devname);
|
||||
|
||||
virtual ~CDev();
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Handle an open of the device.
|
||||
*
|
||||
* This function is called for every open of the device. The default
|
||||
* implementation maintains _open_count and always returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open is allowed, -errno otherwise.
|
||||
*/
|
||||
virtual int open(file_t *filep);
|
||||
|
||||
/**
|
||||
* Handle a close of the device.
|
||||
*
|
||||
* This function is called for every close of the device. The default
|
||||
* implementation maintains _open_count and returns OK as long as it is not zero.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the close was successful, -errno otherwise.
|
||||
*/
|
||||
virtual int close(file_t *filep);
|
||||
|
||||
/**
|
||||
* Perform a read from the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer into which data should be placed.
|
||||
* @param buflen The number of bytes to be read.
|
||||
* @return The number of bytes read or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t read(file_t *filep, char *buffer, size_t buflen) { return -ENOSYS; }
|
||||
|
||||
/**
|
||||
* Perform a write to the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer from which data should be read.
|
||||
* @param buflen The number of bytes to be written.
|
||||
* @return The number of bytes written or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t write(file_t *filep, const char *buffer, size_t buflen) { return -ENOSYS; }
|
||||
|
||||
/**
|
||||
* Perform a logical seek operation on the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param offset The new file position relative to whence.
|
||||
* @param whence SEEK_OFS, SEEK_CUR or SEEK_END.
|
||||
* @return The previous offset, or -errno otherwise.
|
||||
*/
|
||||
virtual off_t seek(file_t *filep, off_t offset, int whence) { return -ENOSYS; }
|
||||
|
||||
/**
|
||||
* Perform an ioctl operation on the device.
|
||||
*
|
||||
* The default implementation handles DIOC_GETPRIV, and otherwise
|
||||
* returns -ENOTTY. Subclasses should call the default implementation
|
||||
* for any command they do not handle themselves.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param cmd The ioctl command value.
|
||||
* @param arg The ioctl argument value.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int ioctl(file_t *filep, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Perform a poll setup/teardown operation.
|
||||
*
|
||||
* This is handled internally and should not normally be overridden.
|
||||
*
|
||||
* @param filep Pointer to the internal file structure.
|
||||
* @param fds Poll descriptor being waited on.
|
||||
* @param setup True if this is establishing a request, false if
|
||||
* it is being torn down.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup);
|
||||
|
||||
protected:
|
||||
/**
|
||||
* Pointer to the default cdev file operations table; useful for
|
||||
* registering clone devices etc.
|
||||
*/
|
||||
static const px4_file_operations_t fops;
|
||||
|
||||
/**
|
||||
* Check the current state of the device for poll events from the
|
||||
* perspective of the file.
|
||||
*
|
||||
* This function is called by the default poll() implementation when
|
||||
* a poll is set up to determine whether the poll should return immediately.
|
||||
*
|
||||
* The default implementation returns no events.
|
||||
*
|
||||
* @param filep The file that's interested.
|
||||
* @return The current set of poll events.
|
||||
*/
|
||||
virtual pollevent_t poll_state(file_t *filep) { return 0; }
|
||||
|
||||
/**
|
||||
* Report new poll events.
|
||||
*
|
||||
* This function should be called anytime the state of the device changes
|
||||
* in a fashion that might be interesting to a poll waiter.
|
||||
*
|
||||
* @param events The new event(s) being announced.
|
||||
*/
|
||||
virtual void poll_notify(pollevent_t events);
|
||||
|
||||
/**
|
||||
* Internal implementation of poll_notify.
|
||||
*
|
||||
* @param fds A poll waiter to notify.
|
||||
* @param events The event(s) to send to the waiter.
|
||||
*/
|
||||
virtual void poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events);
|
||||
|
||||
/**
|
||||
* Notification of the first open.
|
||||
*
|
||||
* This function is called when the device open count transitions from zero
|
||||
* to one. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open should proceed, -errno otherwise.
|
||||
*/
|
||||
virtual int open_first(file_t *filep) { return PX4_OK; }
|
||||
|
||||
/**
|
||||
* Notification of the last close.
|
||||
*
|
||||
* This function is called when the device open count transitions from
|
||||
* one to zero. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open should return OK, -errno otherwise.
|
||||
*/
|
||||
virtual int close_last(file_t *filep) { return PX4_OK; }
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @return class_instamce Class instance created, or -errno on failure
|
||||
*/
|
||||
virtual int register_class_devname(const char *class_devname);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @param class_instance Device class instance from register_class_devname()
|
||||
* @return OK on success, -errno otherwise
|
||||
*/
|
||||
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
|
||||
|
||||
/**
|
||||
* Get the device name.
|
||||
*
|
||||
* @return the file system string of the device handle
|
||||
*/
|
||||
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) */
|
||||
|
||||
private:
|
||||
const char *_devname{nullptr}; /**< device node name */
|
||||
|
||||
px4_pollfd_struct_t **_pollset{nullptr};
|
||||
|
||||
bool _registered{false}; /**< true if device name was registered */
|
||||
|
||||
uint8_t _max_pollwaiters{0}; /**< size of the _pollset array */
|
||||
uint8_t _open_count{0}; /**< number of successful opens */
|
||||
|
||||
/**
|
||||
* Store a pollwaiter in a slot where we can find it later.
|
||||
*
|
||||
* Expands the pollset as required. Must be called with the driver locked.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int store_poll_waiter(px4_pollfd_struct_t *fds);
|
||||
|
||||
/**
|
||||
* Remove a poll waiter.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int remove_poll_waiter(px4_pollfd_struct_t *fds);
|
||||
|
||||
/* do not allow copying this class */
|
||||
CDev(const CDev &);
|
||||
CDev operator=(const CDev &);
|
||||
};
|
||||
|
||||
} // namespace cdev
|
||||
|
||||
#endif /* _CDEV_HPP */
|
||||
49
src/lib/cdev/CMakeLists.txt
Normal file
49
src/lib/cdev/CMakeLists.txt
Normal file
@@ -0,0 +1,49 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
set(SRCS_PLATFORM)
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND SRCS_PLATFORM
|
||||
nuttx/cdev_platform.cpp
|
||||
)
|
||||
else()
|
||||
list(APPEND SRCS_PLATFORM
|
||||
posix/cdev_platform.cpp
|
||||
posix/vfile.cpp
|
||||
)
|
||||
endif()
|
||||
|
||||
px4_add_library(cdev
|
||||
CDev.cpp
|
||||
${SRCS_PLATFORM}
|
||||
)
|
||||
@@ -47,7 +47,7 @@
|
||||
# error This driver is not compatible with CONFIG_DISABLE_POLL
|
||||
#endif
|
||||
|
||||
namespace device
|
||||
namespace cdev
|
||||
{
|
||||
|
||||
/*
|
||||
@@ -71,7 +71,7 @@ static int cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup);
|
||||
* Note that we use the GNU extension syntax here because we don't get designated
|
||||
* initialisers in gcc 4.6.
|
||||
*/
|
||||
const struct file_operations device::CDev::fops = {
|
||||
const struct file_operations cdev::CDev::fops = {
|
||||
open : cdev_open,
|
||||
close : cdev_close,
|
||||
read : cdev_read,
|
||||
@@ -87,7 +87,7 @@ unlink : nullptr
|
||||
static int
|
||||
cdev_open(file_t *filp)
|
||||
{
|
||||
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
|
||||
cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private);
|
||||
|
||||
return cdev->open(filp);
|
||||
}
|
||||
@@ -95,7 +95,7 @@ cdev_open(file_t *filp)
|
||||
static int
|
||||
cdev_close(file_t *filp)
|
||||
{
|
||||
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
|
||||
cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private);
|
||||
|
||||
return cdev->close(filp);
|
||||
}
|
||||
@@ -103,7 +103,7 @@ cdev_close(file_t *filp)
|
||||
static ssize_t
|
||||
cdev_read(file_t *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
|
||||
cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private);
|
||||
|
||||
return cdev->read(filp, buffer, buflen);
|
||||
}
|
||||
@@ -111,7 +111,7 @@ cdev_read(file_t *filp, char *buffer, size_t buflen)
|
||||
static ssize_t
|
||||
cdev_write(file_t *filp, const char *buffer, size_t buflen)
|
||||
{
|
||||
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
|
||||
cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private);
|
||||
|
||||
return cdev->write(filp, buffer, buflen);
|
||||
}
|
||||
@@ -119,7 +119,7 @@ cdev_write(file_t *filp, const char *buffer, size_t buflen)
|
||||
static off_t
|
||||
cdev_seek(file_t *filp, off_t offset, int whence)
|
||||
{
|
||||
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
|
||||
cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private);
|
||||
|
||||
return cdev->seek(filp, offset, whence);
|
||||
}
|
||||
@@ -127,7 +127,7 @@ cdev_seek(file_t *filp, off_t offset, int whence)
|
||||
static int
|
||||
cdev_ioctl(file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
|
||||
cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private);
|
||||
|
||||
return cdev->ioctl(filp, cmd, arg);
|
||||
}
|
||||
@@ -135,9 +135,9 @@ cdev_ioctl(file_t *filp, int cmd, unsigned long arg)
|
||||
static int
|
||||
cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup)
|
||||
{
|
||||
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
|
||||
cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private);
|
||||
|
||||
return cdev->poll(filp, fds, setup);
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
} // namespace cdev
|
||||
@@ -10,10 +10,10 @@
|
||||
#define ATOMIC_ENTER irqstate_t flags = px4_enter_critical_section()
|
||||
#define ATOMIC_LEAVE px4_leave_critical_section(flags)
|
||||
|
||||
namespace device
|
||||
namespace cdev
|
||||
{
|
||||
|
||||
using px4_file_operations_t = struct file_operations;
|
||||
using file_t = struct file;
|
||||
|
||||
} // namespace device
|
||||
} // namespace cdev
|
||||
@@ -54,7 +54,7 @@
|
||||
using namespace std;
|
||||
using namespace DriverFramework;
|
||||
|
||||
const device::px4_file_operations_t device::CDev::fops = {};
|
||||
const cdev::px4_file_operations_t cdev::CDev::fops = {};
|
||||
|
||||
pthread_mutex_t devmutex = PTHREAD_MUTEX_INITIALIZER;
|
||||
pthread_mutex_t filemutex = PTHREAD_MUTEX_INITIALIZER;
|
||||
@@ -65,13 +65,13 @@ volatile bool sim_delay = false;
|
||||
|
||||
#define PX4_MAX_FD 350
|
||||
static map<string, void *> devmap;
|
||||
static device::file_t filemap[PX4_MAX_FD] = {};
|
||||
static cdev::file_t filemap[PX4_MAX_FD] = {};
|
||||
|
||||
extern "C" {
|
||||
|
||||
int px4_errno;
|
||||
|
||||
static device::CDev *getDev(const char *path)
|
||||
static cdev::CDev *getDev(const char *path)
|
||||
{
|
||||
PX4_DEBUG("CDev::getDev");
|
||||
|
||||
@@ -81,7 +81,7 @@ extern "C" {
|
||||
|
||||
if (item != devmap.end()) {
|
||||
pthread_mutex_unlock(&devmutex);
|
||||
return (device::CDev *)item->second;
|
||||
return (cdev::CDev *)item->second;
|
||||
}
|
||||
|
||||
pthread_mutex_unlock(&devmutex);
|
||||
@@ -89,14 +89,14 @@ extern "C" {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
static device::CDev *get_vdev(int fd)
|
||||
static cdev::CDev *get_vdev(int fd)
|
||||
{
|
||||
pthread_mutex_lock(&filemutex);
|
||||
bool valid = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd].vdev);
|
||||
device::CDev *dev;
|
||||
cdev::CDev *dev;
|
||||
|
||||
if (valid) {
|
||||
dev = (device::CDev *)(filemap[fd].vdev);
|
||||
dev = (cdev::CDev *)(filemap[fd].vdev);
|
||||
|
||||
} else {
|
||||
dev = nullptr;
|
||||
@@ -106,7 +106,7 @@ extern "C" {
|
||||
return dev;
|
||||
}
|
||||
|
||||
int register_driver(const char *name, const device::px4_file_operations_t *fops, device::mode_t mode, void *data)
|
||||
int register_driver(const char *name, const cdev::px4_file_operations_t *fops, cdev::mode_t mode, void *data)
|
||||
{
|
||||
PX4_DEBUG("CDev::register_driver %s", name);
|
||||
int ret = 0;
|
||||
@@ -157,7 +157,7 @@ extern "C" {
|
||||
int px4_open(const char *path, int flags, ...)
|
||||
{
|
||||
PX4_DEBUG("px4_open");
|
||||
device::CDev *dev = getDev(path);
|
||||
cdev::CDev *dev = getDev(path);
|
||||
int ret = 0;
|
||||
int i;
|
||||
mode_t mode;
|
||||
@@ -172,7 +172,7 @@ extern "C" {
|
||||
|
||||
// Create the file
|
||||
PX4_DEBUG("Creating virtual file %s", path);
|
||||
dev = device::VFile::createFile(path, mode);
|
||||
dev = cdev::VFile::createFile(path, mode);
|
||||
}
|
||||
|
||||
if (dev) {
|
||||
@@ -181,7 +181,7 @@ extern "C" {
|
||||
|
||||
for (i = 0; i < PX4_MAX_FD; ++i) {
|
||||
if (filemap[i].vdev == nullptr) {
|
||||
filemap[i] = device::file_t(flags, dev);
|
||||
filemap[i] = cdev::file_t(flags, dev);
|
||||
break;
|
||||
}
|
||||
}
|
||||
@@ -227,7 +227,7 @@ extern "C" {
|
||||
{
|
||||
int ret;
|
||||
|
||||
device::CDev *dev = get_vdev(fd);
|
||||
cdev::CDev *dev = get_vdev(fd);
|
||||
|
||||
if (dev) {
|
||||
pthread_mutex_lock(&filemutex);
|
||||
@@ -254,7 +254,7 @@ extern "C" {
|
||||
{
|
||||
int ret;
|
||||
|
||||
device::CDev *dev = get_vdev(fd);
|
||||
cdev::CDev *dev = get_vdev(fd);
|
||||
|
||||
if (dev) {
|
||||
PX4_DEBUG("px4_read fd = %d", fd);
|
||||
@@ -276,7 +276,7 @@ extern "C" {
|
||||
{
|
||||
int ret;
|
||||
|
||||
device::CDev *dev = get_vdev(fd);
|
||||
cdev::CDev *dev = get_vdev(fd);
|
||||
|
||||
if (dev) {
|
||||
PX4_DEBUG("px4_write fd = %d", fd);
|
||||
@@ -299,7 +299,7 @@ extern "C" {
|
||||
PX4_DEBUG("px4_ioctl fd = %d", fd);
|
||||
int ret = 0;
|
||||
|
||||
device::CDev *dev = get_vdev(fd);
|
||||
cdev::CDev *dev = get_vdev(fd);
|
||||
|
||||
if (dev) {
|
||||
ret = dev->ioctl(&filemap[fd], cmd, arg);
|
||||
@@ -358,7 +358,7 @@ extern "C" {
|
||||
fds[i].revents = 0;
|
||||
fds[i].priv = nullptr;
|
||||
|
||||
device::CDev *dev = get_vdev(fds[i].fd);
|
||||
cdev::CDev *dev = get_vdev(fds[i].fd);
|
||||
|
||||
// If fd is valid
|
||||
if (dev) {
|
||||
@@ -419,7 +419,7 @@ extern "C" {
|
||||
// go through all fds and count how many have data
|
||||
for (i = 0; i < nfds; ++i) {
|
||||
|
||||
device::CDev *dev = get_vdev(fds[i].fd);
|
||||
cdev::CDev *dev = get_vdev(fds[i].fd);
|
||||
|
||||
// If fd is valid
|
||||
if (dev) {
|
||||
@@ -457,7 +457,7 @@ extern "C" {
|
||||
return -1;
|
||||
}
|
||||
|
||||
device::CDev *dev = getDev(pathname);
|
||||
cdev::CDev *dev = getDev(pathname);
|
||||
return (dev != nullptr) ? 0 : -1;
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
#define ATOMIC_ENTER lock()
|
||||
#define ATOMIC_LEAVE unlock()
|
||||
|
||||
namespace device
|
||||
namespace cdev
|
||||
{
|
||||
|
||||
struct file_operations {
|
||||
@@ -25,8 +25,8 @@ struct file_t {
|
||||
file_t(int f, void *c) : flags(f), priv(nullptr), vdev(c) {}
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
} // namespace cdev
|
||||
|
||||
extern "C" __EXPORT int register_driver(const char *name, const device::px4_file_operations_t *fops,
|
||||
device::mode_t mode, void *data);
|
||||
extern "C" __EXPORT int register_driver(const char *name, const cdev::px4_file_operations_t *fops,
|
||||
cdev::mode_t mode, void *data);
|
||||
extern "C" __EXPORT int unregister_driver(const char *path);
|
||||
@@ -40,11 +40,11 @@
|
||||
|
||||
#include "vfile.h"
|
||||
|
||||
namespace device
|
||||
namespace cdev
|
||||
{
|
||||
|
||||
VFile::VFile(const char *fname, mode_t mode) :
|
||||
CDev("vfile", fname)
|
||||
CDev(fname)
|
||||
{
|
||||
}
|
||||
|
||||
@@ -64,4 +64,4 @@ ssize_t VFile::write(file_t *handlep, const char *buffer, size_t buflen)
|
||||
return buflen;
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
} // namespace cdev
|
||||
@@ -42,7 +42,7 @@
|
||||
|
||||
#include "../CDev.hpp"
|
||||
|
||||
namespace device
|
||||
namespace cdev
|
||||
{
|
||||
|
||||
class VFile : public CDev
|
||||
@@ -59,4 +59,4 @@ private:
|
||||
VFile(const VFile &);
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
} // namespace cdev
|
||||
@@ -44,81 +44,13 @@
|
||||
#include "px4_posix.h"
|
||||
#include "drivers/drv_device.h"
|
||||
|
||||
#if 1 // Disable poll debug ouput by default completely as it uses CPU cycles
|
||||
#define DEVICE_POLL_DEBUG(FMT, ...)
|
||||
#else
|
||||
#define DEVICE_POLL_DEBUG(FMT, ...) DEVICE_DEBUG(FMT, ##__VA_ARGS__)
|
||||
#endif
|
||||
|
||||
namespace device
|
||||
{
|
||||
|
||||
CDev::CDev(const char *name, const char *devname) :
|
||||
Device(name),
|
||||
_devname(devname)
|
||||
cdev::CDev(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()
|
||||
{
|
||||
DEVICE_DEBUG("CDev::~CDev");
|
||||
|
||||
if (_registered) {
|
||||
unregister_driver(_devname);
|
||||
}
|
||||
|
||||
if (_pollset) {
|
||||
delete[](_pollset);
|
||||
}
|
||||
|
||||
px4_sem_destroy(&_lock);
|
||||
}
|
||||
|
||||
int
|
||||
CDev::register_class_devname(const char *class_devname)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::register_class_devname %s", class_devname);
|
||||
|
||||
if (class_devname == nullptr) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
int class_instance = 0;
|
||||
int ret = -ENOSPC;
|
||||
|
||||
while (class_instance < 4) {
|
||||
char name[32];
|
||||
snprintf(name, sizeof(name), "%s%d", class_devname, class_instance);
|
||||
ret = register_driver(name, &fops, 0666, (void *)this);
|
||||
|
||||
if (ret == OK) {
|
||||
break;
|
||||
}
|
||||
|
||||
class_instance++;
|
||||
}
|
||||
|
||||
if (class_instance == 4) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
return class_instance;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::unregister_class_devname(const char *class_devname, unsigned class_instance)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::unregister_class_devname");
|
||||
char name[32];
|
||||
snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
|
||||
return unregister_driver(name);
|
||||
}
|
||||
|
||||
int
|
||||
@@ -134,109 +66,18 @@ CDev::init()
|
||||
}
|
||||
|
||||
// now register the driver
|
||||
if (_devname != nullptr) {
|
||||
ret = register_driver(_devname, &fops, 0666, (void *)this);
|
||||
if (get_devname() != nullptr) {
|
||||
ret = cdev::CDev::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
_registered = true;
|
||||
}
|
||||
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*
|
||||
* Default implementations of the character device interface
|
||||
*/
|
||||
int
|
||||
CDev::open(file_t *filep)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::open");
|
||||
int ret = PX4_OK;
|
||||
|
||||
lock();
|
||||
/* increment the open count */
|
||||
_open_count++;
|
||||
|
||||
if (_open_count == 1) {
|
||||
|
||||
/* first-open callback may decline the open */
|
||||
ret = open_first(filep);
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
_open_count--;
|
||||
}
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::open_first(file_t *filep)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::open_first");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::close(file_t *filep)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::close");
|
||||
int ret = PX4_OK;
|
||||
|
||||
lock();
|
||||
|
||||
if (_open_count > 0) {
|
||||
/* decrement the open count */
|
||||
_open_count--;
|
||||
|
||||
/* callback cannot decline the close */
|
||||
if (_open_count == 0) {
|
||||
ret = close_last(filep);
|
||||
}
|
||||
|
||||
} else {
|
||||
ret = -EBADF;
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::close_last(file_t *filep)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::close_last");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
CDev::read(file_t *filep, char *buffer, size_t buflen)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::read");
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
CDev::write(file_t *filep, const char *buffer, size_t buflen)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::write");
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
off_t
|
||||
CDev::seek(file_t *filep, off_t offset, int whence)
|
||||
{
|
||||
DEVICE_DEBUG("CDev::seek");
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::ioctl(file_t *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
@@ -271,200 +112,4 @@ CDev::ioctl(file_t *filep, int cmd, unsigned long arg)
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
|
||||
{
|
||||
DEVICE_POLL_DEBUG("CDev::Poll %s", setup ? "setup" : "teardown");
|
||||
int ret = PX4_OK;
|
||||
|
||||
if (setup) {
|
||||
/*
|
||||
* Save the file pointer in the pollfd for the subclass'
|
||||
* benefit.
|
||||
*/
|
||||
fds->priv = (void *)filep;
|
||||
DEVICE_POLL_DEBUG("CDev::poll: fds->priv = %p", filep);
|
||||
|
||||
/*
|
||||
* Lock against poll_notify() and possibly other callers (protect _pollset).
|
||||
*/
|
||||
ATOMIC_ENTER;
|
||||
|
||||
/*
|
||||
* Try to store the fds for later use and handle array resizing.
|
||||
*/
|
||||
while ((ret = store_poll_waiter(fds)) == -ENFILE) {
|
||||
|
||||
// No free slot found. Resize the pollset. This is expensive, but it's only needed initially.
|
||||
|
||||
if (_max_pollwaiters >= 256 / 2) { //_max_pollwaiters is uint8_t
|
||||
ret = -ENOMEM;
|
||||
break;
|
||||
}
|
||||
|
||||
const uint8_t new_count = _max_pollwaiters > 0 ? _max_pollwaiters * 2 : 1;
|
||||
px4_pollfd_struct_t **prev_pollset = _pollset;
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
// malloc uses a semaphore, we need to call it enabled IRQ's
|
||||
px4_leave_critical_section(flags);
|
||||
#endif
|
||||
px4_pollfd_struct_t **new_pollset = new px4_pollfd_struct_t *[new_count];
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
flags = px4_enter_critical_section();
|
||||
#endif
|
||||
|
||||
if (prev_pollset == _pollset) {
|
||||
// no one else updated the _pollset meanwhile, so we're good to go
|
||||
if (!new_pollset) {
|
||||
ret = -ENOMEM;
|
||||
break;
|
||||
}
|
||||
|
||||
if (_max_pollwaiters > 0) {
|
||||
memset(new_pollset + _max_pollwaiters, 0, sizeof(px4_pollfd_struct_t *) * (new_count - _max_pollwaiters));
|
||||
memcpy(new_pollset, _pollset, sizeof(px4_pollfd_struct_t *) * _max_pollwaiters);
|
||||
}
|
||||
|
||||
_pollset = new_pollset;
|
||||
_pollset[_max_pollwaiters] = fds;
|
||||
_max_pollwaiters = new_count;
|
||||
|
||||
// free the previous _pollset (we need to unlock here which is fine because we don't access _pollset anymore)
|
||||
#ifdef __PX4_NUTTX
|
||||
px4_leave_critical_section(flags);
|
||||
#endif
|
||||
|
||||
if (prev_pollset) {
|
||||
delete[](prev_pollset);
|
||||
}
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
flags = px4_enter_critical_section();
|
||||
#endif
|
||||
|
||||
// Success
|
||||
ret = PX4_OK;
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
px4_leave_critical_section(flags);
|
||||
#endif
|
||||
// We have to retry
|
||||
delete[] new_pollset;
|
||||
#ifdef __PX4_NUTTX
|
||||
flags = px4_enter_critical_section();
|
||||
#endif
|
||||
}
|
||||
|
||||
if (ret == PX4_OK) {
|
||||
|
||||
/*
|
||||
* Check to see whether we should send a poll notification
|
||||
* immediately.
|
||||
*/
|
||||
fds->revents |= fds->events & poll_state(filep);
|
||||
|
||||
/* yes? post the notification */
|
||||
if (fds->revents != 0) {
|
||||
px4_sem_post(fds->sem);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
ATOMIC_LEAVE;
|
||||
|
||||
} else {
|
||||
ATOMIC_ENTER;
|
||||
/*
|
||||
* Handle a teardown request.
|
||||
*/
|
||||
ret = remove_poll_waiter(fds);
|
||||
ATOMIC_LEAVE;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
CDev::poll_notify(pollevent_t events)
|
||||
{
|
||||
DEVICE_POLL_DEBUG("CDev::poll_notify events = %0x", events);
|
||||
|
||||
/* lock against poll() as well as other wakeups */
|
||||
ATOMIC_ENTER;
|
||||
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (nullptr != _pollset[i]) {
|
||||
poll_notify_one(_pollset[i], events);
|
||||
}
|
||||
}
|
||||
|
||||
ATOMIC_LEAVE;
|
||||
}
|
||||
|
||||
void
|
||||
CDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
|
||||
{
|
||||
DEVICE_POLL_DEBUG("CDev::poll_notify_one");
|
||||
|
||||
/* update the reported event set */
|
||||
fds->revents |= fds->events & events;
|
||||
|
||||
DEVICE_POLL_DEBUG(" Events fds=%p %0x %0x %0x", fds, fds->revents, fds->events, events);
|
||||
|
||||
if (fds->revents != 0) {
|
||||
px4_sem_post(fds->sem);
|
||||
}
|
||||
}
|
||||
|
||||
pollevent_t
|
||||
CDev::poll_state(file_t *filep)
|
||||
{
|
||||
DEVICE_POLL_DEBUG("CDev::poll_notify");
|
||||
/* by default, no poll events to report */
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::store_poll_waiter(px4_pollfd_struct_t *fds)
|
||||
{
|
||||
/*
|
||||
* Look for a free slot.
|
||||
*/
|
||||
DEVICE_POLL_DEBUG("CDev::store_poll_waiter");
|
||||
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (nullptr == _pollset[i]) {
|
||||
|
||||
/* save the pollfd */
|
||||
_pollset[i] = fds;
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
}
|
||||
|
||||
return -ENFILE;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
|
||||
{
|
||||
DEVICE_POLL_DEBUG("CDev::remove_poll_waiter");
|
||||
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (fds == _pollset[i]) {
|
||||
|
||||
_pollset[i] = nullptr;
|
||||
return PX4_OK;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
DEVICE_POLL_DEBUG("poll: bad fd state");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
|
||||
@@ -41,26 +41,23 @@
|
||||
#define _DEVICE_CDEV_HPP
|
||||
|
||||
#include "Device.hpp"
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
#include "nuttx/cdev_platform.hpp"
|
||||
#else
|
||||
#include "posix/cdev_platform.hpp"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Namespace encapsulating all device framework classes, functions and data.
|
||||
*/
|
||||
namespace device
|
||||
{
|
||||
|
||||
using file_t = cdev::file_t;
|
||||
|
||||
/**
|
||||
* Abstract class for any character device
|
||||
*/
|
||||
class __EXPORT CDev : public Device
|
||||
class __EXPORT CDev : public Device, public cdev::CDev
|
||||
{
|
||||
public:
|
||||
/**
|
||||
@@ -71,68 +68,10 @@ public:
|
||||
*/
|
||||
CDev(const char *name, const char *devname); // TODO: dagar remove name and Device inheritance
|
||||
|
||||
virtual ~CDev();
|
||||
virtual ~CDev() = default;
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Handle an open of the device.
|
||||
*
|
||||
* This function is called for every open of the device. The default
|
||||
* implementation maintains _open_count and always returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open is allowed, -errno otherwise.
|
||||
*/
|
||||
virtual int open(file_t *filep);
|
||||
|
||||
/**
|
||||
* Handle a close of the device.
|
||||
*
|
||||
* This function is called for every close of the device. The default
|
||||
* implementation maintains _open_count and returns OK as long as it is not zero.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the close was successful, -errno otherwise.
|
||||
*/
|
||||
virtual int close(file_t *filep);
|
||||
|
||||
/**
|
||||
* Perform a read from the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer into which data should be placed.
|
||||
* @param buflen The number of bytes to be read.
|
||||
* @return The number of bytes read or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t read(file_t *filep, char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a write to the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer from which data should be read.
|
||||
* @param buflen The number of bytes to be written.
|
||||
* @return The number of bytes written or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t write(file_t *filep, const char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a logical seek operation on the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param offset The new file position relative to whence.
|
||||
* @param whence SEEK_OFS, SEEK_CUR or SEEK_END.
|
||||
* @return The previous offset, or -errno otherwise.
|
||||
*/
|
||||
virtual off_t seek(file_t *filep, off_t offset, int whence);
|
||||
|
||||
/**
|
||||
* Perform an ioctl operation on the device.
|
||||
*
|
||||
@@ -147,164 +86,12 @@ public:
|
||||
*/
|
||||
virtual int ioctl(file_t *filep, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Perform a poll setup/teardown operation.
|
||||
*
|
||||
* This is handled internally and should not normally be overridden.
|
||||
*
|
||||
* @param filep Pointer to the internal file structure.
|
||||
* @param fds Poll descriptor being waited on.
|
||||
* @param setup True if this is establishing a request, false if
|
||||
* it is being torn down.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup);
|
||||
|
||||
protected:
|
||||
/**
|
||||
* Pointer to the default cdev file operations table; useful for
|
||||
* registering clone devices etc.
|
||||
*/
|
||||
static const px4_file_operations_t fops;
|
||||
|
||||
/**
|
||||
* Check the current state of the device for poll events from the
|
||||
* perspective of the file.
|
||||
*
|
||||
* This function is called by the default poll() implementation when
|
||||
* a poll is set up to determine whether the poll should return immediately.
|
||||
*
|
||||
* The default implementation returns no events.
|
||||
*
|
||||
* @param filep The file that's interested.
|
||||
* @return The current set of poll events.
|
||||
*/
|
||||
virtual pollevent_t poll_state(file_t *filep);
|
||||
|
||||
/**
|
||||
* Report new poll events.
|
||||
*
|
||||
* This function should be called anytime the state of the device changes
|
||||
* in a fashion that might be interesting to a poll waiter.
|
||||
*
|
||||
* @param events The new event(s) being announced.
|
||||
*/
|
||||
virtual void poll_notify(pollevent_t events);
|
||||
|
||||
/**
|
||||
* Internal implementation of poll_notify.
|
||||
*
|
||||
* @param fds A poll waiter to notify.
|
||||
* @param events The event(s) to send to the waiter.
|
||||
*/
|
||||
virtual void poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events);
|
||||
|
||||
/**
|
||||
* Notification of the first open.
|
||||
*
|
||||
* This function is called when the device open count transitions from zero
|
||||
* to one. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open should proceed, -errno otherwise.
|
||||
*/
|
||||
virtual int open_first(file_t *filep);
|
||||
|
||||
/**
|
||||
* Notification of the last close.
|
||||
*
|
||||
* This function is called when the device open count transitions from
|
||||
* one to zero. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open should return OK, -errno otherwise.
|
||||
*/
|
||||
virtual int close_last(file_t *filep);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @return class_instamce Class instance created, or -errno on failure
|
||||
*/
|
||||
virtual int register_class_devname(const char *class_devname);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @param class_instance Device class instance from register_class_devname()
|
||||
* @return OK on success, -errno otherwise
|
||||
*/
|
||||
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
|
||||
|
||||
/**
|
||||
* Get the device name.
|
||||
*
|
||||
* @return the file system string of the device handle
|
||||
*/
|
||||
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{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.
|
||||
*
|
||||
* Must be called with the driver locked.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
inline int store_poll_waiter(px4_pollfd_struct_t *fds);
|
||||
|
||||
/**
|
||||
* Remove a poll waiter.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
inline int remove_poll_waiter(px4_pollfd_struct_t *fds);
|
||||
|
||||
/* do not allow copying this class */
|
||||
CDev(const CDev &);
|
||||
CDev operator=(const CDev &);
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
|
||||
@@ -33,9 +33,6 @@
|
||||
|
||||
set(SRCS_PLATFORM)
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND SRCS_PLATFORM
|
||||
nuttx/cdev_platform.cpp
|
||||
)
|
||||
if ("${CONFIG_I2C}" STREQUAL "y")
|
||||
list(APPEND SRCS_PLATFORM nuttx/I2C.cpp)
|
||||
endif()
|
||||
@@ -46,8 +43,6 @@ if (${OS} STREQUAL "nuttx")
|
||||
else()
|
||||
list(APPEND SRCS_PLATFORM
|
||||
posix/I2C.cpp
|
||||
posix/cdev_platform.cpp
|
||||
posix/vfile.cpp
|
||||
)
|
||||
endif()
|
||||
|
||||
@@ -61,3 +56,5 @@ px4_add_library(drivers__device
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
target_link_libraries(drivers__device PRIVATE nuttx_arch)
|
||||
endif()
|
||||
|
||||
target_link_libraries(drivers__device PRIVATE cdev)
|
||||
|
||||
@@ -137,21 +137,23 @@ public:
|
||||
*
|
||||
* @return The bus ID
|
||||
*/
|
||||
uint8_t get_device_bus() { return _device_id.devid_s.bus; }
|
||||
uint8_t get_device_bus() const { return _device_id.devid_s.bus; }
|
||||
|
||||
uint32_t get_device_id() const { return _device_id.devid; }
|
||||
|
||||
/**
|
||||
* Return the bus type the device is connected to.
|
||||
*
|
||||
* @return The bus type
|
||||
*/
|
||||
DeviceBusType get_device_bus_type() { return _device_id.devid_s.bus_type; }
|
||||
DeviceBusType get_device_bus_type() const { return _device_id.devid_s.bus_type; }
|
||||
|
||||
/**
|
||||
* Return the bus address of the device.
|
||||
*
|
||||
* @return The bus address
|
||||
*/
|
||||
uint8_t get_device_address() { return _device_id.devid_s.address; }
|
||||
uint8_t get_device_address() const { return _device_id.devid_s.address; }
|
||||
|
||||
void set_device_address(int address) { _device_id.devid_s.address = address; }
|
||||
|
||||
|
||||
Reference in New Issue
Block a user