drivers device merge nuttx and posix Device and CDev

This commit is contained in:
Daniel Agar
2017-11-08 11:01:04 -05:00
committed by Lorenz Meier
parent c6b6164cf7
commit bf435fc520
16 changed files with 657 additions and 1535 deletions
@@ -32,37 +32,22 @@
****************************************************************************/
/**
* @file vcdev.cpp
* @file CDev.cpp
*
* Virtual character device base class.
* Character device base class.
*/
#include "CDev.hpp"
#include <cstring>
#include "px4_posix.h"
#include "vdev.h"
#include "drivers/drv_device.h"
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <string>
#include <map>
#include "DevMgr.hpp"
using namespace DriverFramework;
using namespace std;
namespace device
{
int px4_errno;
static map<string, void *> devmap;
pthread_mutex_t devmutex = PTHREAD_MUTEX_INITIALIZER;
CDev::CDev(const char *name,
const char *devname) :
CDev::CDev(const char *name, const char *devname) :
// base class
Device(name),
// public
@@ -106,9 +91,11 @@ CDev::register_class_devname(const char *class_devname)
while (class_instance < 4) {
char name[32];
snprintf(name, sizeof(name), "%s%d", class_devname, class_instance);
ret = register_driver(name, (void *)this);
ret = register_driver(name, &fops, 0666, (void *)this);
if (ret == OK) { break; }
if (ret == OK) {
break;
}
class_instance++;
}
@@ -120,75 +107,13 @@ CDev::register_class_devname(const char *class_devname)
return class_instance;
}
int
CDev::register_driver(const char *name, void *data)
{
DEVICE_DEBUG("CDev::register_driver %s", name);
int ret = 0;
if (name == nullptr || data == nullptr) {
return -EINVAL;
}
pthread_mutex_lock(&devmutex);
// Make sure the device does not already exist
auto item = devmap.find(name);
if (item != devmap.end()) {
pthread_mutex_unlock(&devmutex);
return -EEXIST;
}
devmap[name] = (void *)data;
DEVICE_DEBUG("Registered DEV %s", name);
pthread_mutex_unlock(&devmutex);
return ret;
}
int
CDev::unregister_driver(const char *name)
{
DEVICE_DEBUG("CDev::unregister_driver %s", name);
int ret = -EINVAL;
if (name == nullptr) {
return -EINVAL;
}
pthread_mutex_lock(&devmutex);
if (devmap.erase(name) > 0) {
DEVICE_DEBUG("Unregistered DEV %s", name);
ret = 0;
}
pthread_mutex_unlock(&devmutex);
return ret;
}
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);
int ret = -EINVAL;
PX4_WARN("unregistering class %s", name);
pthread_mutex_lock(&devmutex);
if (devmap.erase(name) > 0) {
DEVICE_DEBUG("Unregistered class DEV %s", name);
ret = 0;
}
pthread_mutex_unlock(&devmutex);
return ret;
return unregister_driver(name);
}
int
@@ -205,7 +130,7 @@ CDev::init()
// now register the driver
if (_devname != nullptr) {
ret = register_driver(_devname, (void *)this);
ret = register_driver(_devname, &fops, 0666, (void *)this);
if (ret != PX4_OK) {
goto out;
@@ -400,7 +325,7 @@ CDev::poll_notify(pollevent_t events)
DEVICE_DEBUG("CDev::poll_notify events = %0x", events);
/* lock against poll() as well as other wakeups */
lock();
ATOMIC_ENTER;
for (unsigned i = 0; i < _max_pollwaiters; i++) {
if (nullptr != _pollset[i]) {
@@ -408,15 +333,20 @@ CDev::poll_notify(pollevent_t events)
}
}
unlock();
ATOMIC_LEAVE;
}
void
CDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
{
DEVICE_DEBUG("CDev::poll_notify_one");
int value;
#ifdef __PX4_NUTTX
int value = fds->sem->semcount;
#else
int value = -1;
px4_sem_getvalue(fds->sem, &value);
#endif
/* update the reported event set */
fds->revents |= fds->events & events;
@@ -499,83 +429,4 @@ CDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
return -EINVAL;
}
CDev *CDev::getDev(const char *path)
{
PX4_DEBUG("CDev::getDev");
pthread_mutex_lock(&devmutex);
auto item = devmap.find(path);
if (item != devmap.end()) {
pthread_mutex_unlock(&devmutex);
return (CDev *)item->second;
}
pthread_mutex_unlock(&devmutex);
return nullptr;
}
void CDev::showDevices()
{
int i = 0;
PX4_INFO("PX4 Devices:");
pthread_mutex_lock(&devmutex);
for (const auto &dev : devmap) {
if (strncmp(dev.first.c_str(), "/dev/", 5) == 0) {
PX4_INFO(" %s", dev.first.c_str());
}
}
pthread_mutex_unlock(&devmutex);
PX4_INFO("DF Devices:");
const char *dev_path;
unsigned int index = 0;
i = 0;
do {
// Each look increments index and returns -1 if end reached
i = DevMgr::getNextDeviceName(index, &dev_path);
if (i == 0) {
PX4_INFO(" %s", dev_path);
}
} while (i == 0);
}
void CDev::showTopics()
{
PX4_INFO("Devices:");
pthread_mutex_lock(&devmutex);
for (const auto &dev : devmap) {
if (strncmp(dev.first.c_str(), "/obj/", 5) == 0) {
PX4_INFO(" %s", dev.first.c_str());
}
}
pthread_mutex_unlock(&devmutex);
}
void CDev::showFiles()
{
PX4_INFO("Files:");
pthread_mutex_lock(&devmutex);
for (const auto &dev : devmap) {
if (strncmp(dev.first.c_str(), "/obj/", 5) != 0 &&
strncmp(dev.first.c_str(), "/dev/", 5) != 0) {
PX4_INFO(" %s", dev.first.c_str());
}
}
pthread_mutex_unlock(&devmutex);
}
} // namespace device
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
* 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
@@ -32,180 +32,33 @@
****************************************************************************/
/**
* @file vdevice.h
* @file CDev.hpp
*
* Definitions for the generic base classes in the virtual device framework.
* Definitions for the generic base classes in the device framework.
*/
#pragma once
#ifndef _DEVICE_CDEV_HPP
#define _DEVICE_CDEV_HPP
/*
* Includes here should only cover the needs of the framework definitions.
*/
#include "Device.hpp"
#include <px4_config.h>
#include <px4_posix.h>
#include <errno.h>
#include <stdbool.h>
#include <stdio.h>
#include <stddef.h>
#include <stdint.h>
#include <semaphore.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__)
#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 __EXPORT
namespace device
{
struct file_t {
int flags;
void *priv;
void *vdev;
file_t() : flags(0), priv(NULL), vdev(NULL) {}
file_t(int f, void *c) : flags(f), priv(NULL), vdev(c) {}
};
/**
* Fundamental base class for all physical drivers (I2C, SPI).
*
* This class provides the basic driver template for I2C and SPI devices
*/
class __EXPORT Device
{
public:
/**
* Destructor.
*
* Public so that anonymous devices can be destroyed.
*/
virtual ~Device();
/*
* Direct access methods.
*/
/**
* Initialise the driver and make it ready for use.
*
* @return OK if the driver initialized OK, negative errno otherwise;
*/
virtual int init();
/**
* Read directly from the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param offset The device address at which to start reading
* @param data The buffer into which the read values should be placed.
* @param count The number of items to read.
* @return The number of items read on success, negative errno otherwise.
*/
virtual int dev_read(unsigned address, void *data, unsigned count);
/**
* Write directly to the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param address The device address at which to start writing.
* @param data The buffer from which values should be read.
* @param count The number of items to write.
* @return The number of items written on success, negative errno otherwise.
*/
virtual int dev_write(unsigned address, void *data, unsigned count);
/**
* Perform a device-specific operation.
*
* @param operation The operation to perform.
* @param arg An argument to the operation.
* @return Negative errno on error, OK or positive value on success.
*/
virtual int dev_ioctl(unsigned operation, unsigned arg);
/*
device bus types for DEVID
*/
enum DeviceBusType {
DeviceBusType_UNKNOWN = 0,
DeviceBusType_I2C = 1,
DeviceBusType_SPI = 2,
DeviceBusType_UAVCAN = 3,
DeviceBusType_SIM = 4,
};
/*
broken out device elements. The bitfields are used to keep
the overall value small enough to fit in a float accurately,
which makes it possible to transport over the MAVLink
parameter protocol without loss of information.
*/
struct DeviceStructure {
enum DeviceBusType bus_type : 3;
uint8_t bus: 5; // which instance of the bus type
uint8_t address; // address on the bus (eg. I2C address)
uint8_t devtype; // device class specific device type
};
union DeviceId {
struct DeviceStructure devid_s;
uint32_t devid;
};
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);
/**
* 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_DEBUG("lock");
do {} while (px4_sem_wait(&_lock) != 0);
}
/**
* Release the driver lock.
*/
void unlock()
{
//DEVICE_DEBUG("unlock");
px4_sem_post(&_lock);
}
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 &);
};
/**
* Abstract class for any virtual character device
* Abstract class for any character device
*/
class __EXPORT CDev : public Device
{
@@ -216,38 +69,12 @@ public:
* @param name Driver name
* @param devname Device node name
*/
CDev(const char *name, const char *devname);
CDev(const char *name, const char *devname); // TODO: dagar remove name and Device inheritance
/**
* Destructor
*/
virtual ~CDev();
virtual int init();
/**
* Perform a poll setup/teardown operation. Based on NuttX implementation.
*
* 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);
/**
* 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; }
/**
* Handle an open of the device.
*
@@ -320,22 +147,35 @@ public:
*/
virtual int ioctl(file_t *filep, int cmd, unsigned long arg);
static CDev *getDev(const char *path);
static void showFiles(void);
static void showDevices(void);
static void showTopics(void);
/**
* 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);
/**
* Get the device name.
* Test whether the device is currently open.
*
* @return the file system string of the device handle
* 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.
*/
const char *get_devname() { return _devname; }
bool is_open() { return _open_count > 0; }
protected:
int register_driver(const char *name, void *data);
int unregister_driver(const char *name);
/**
* 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
@@ -346,8 +186,6 @@ protected:
*
* The default implementation returns no events.
*
* Lock must already be held when calling this.
*
* @param filep The file that's interested.
* @return The current set of poll events.
*/
@@ -366,8 +204,6 @@ protected:
/**
* Internal implementation of poll_notify.
*
* Lock must already be held when calling this.
*
* @param fds A poll waiter to notify.
* @param events The event(s) to send to the waiter.
*/
@@ -418,13 +254,20 @@ protected:
*/
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
bool _pub_blocked; /**< true if publishing should be blocked */
/**
* Get the device name.
*
* @return the file system string of the device handle
*/
const char *get_devname() { return _devname; }
bool _pub_blocked{false}; /**< true if publishing should be blocked */
private:
const char *_devname; /**< device node name */
bool _registered; /**< true if device name was registered */
bool _registered{false}; /**< true if device name was registered */
uint8_t _max_pollwaiters; /**< size of the _pollset array */
unsigned _open_count; /**< number of successful opens */
uint16_t _open_count; /**< number of successful opens */
px4_pollfd_struct_t **_pollset;
@@ -446,7 +289,7 @@ private:
/* do not allow copying this class */
CDev(const CDev &);
//CDev operator=(const CDev&);
CDev operator=(const CDev &);
};
} // namespace device
@@ -458,3 +301,4 @@ enum CLASS_DEVICE {
CLASS_DEVICE_TERTIARY = 2
};
#endif /* _DEVICE_CDEV_HPP */
+4 -5
View File
@@ -34,6 +34,8 @@
set(SRCS)
list(APPEND SRCS
CDev.cpp
Device.cpp
ringbuffer.cpp
integrator.cpp
)
@@ -43,8 +45,7 @@ include_directories(${CMAKE_CURRENT_SOURCE_DIR})
if(${OS} STREQUAL "nuttx")
include_directories(nuttx)
list(APPEND SRCS
nuttx/device_nuttx.cpp
cdev.cpp
nuttx/cdev_platform.cpp
)
if ("${CONFIG_I2C}" STREQUAL "y")
@@ -57,10 +58,8 @@ if(${OS} STREQUAL "nuttx")
else()
include_directories(posix)
list(APPEND SRCS
posix/device_posix.cpp
posix/vdev.cpp
posix/cdev_platform.cpp
posix/vfile.cpp
posix/vdev_posix.cpp
posix/i2c_posix.cpp
)
@@ -37,10 +37,10 @@
* Fundamental driver base class for the device framework.
*/
#include "device.h"
#include "Device.hpp"
#include "px4_log.h"
#include <nuttx/arch.h>
#include <stdio.h>
#include <unistd.h>
#include <drivers/drv_device.h>
@@ -54,7 +54,11 @@ Device::Device(const char *name) :
_name(name),
_debug_enabled(false)
{
sem_init(&_lock, 0, 1);
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 */
@@ -67,7 +71,7 @@ Device::Device(const char *name) :
Device::~Device()
{
sem_destroy(&_lock);
px4_sem_destroy(&_lock);
}
int
+222
View File
@@ -0,0 +1,222 @@
/****************************************************************************
*
* 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 Device.hpp
*
* Definitions for the generic base classes in the device framework.
*/
#ifndef _DEVICE_DEVICE_HPP
#define _DEVICE_DEVICE_HPP
/*
* Includes here should only cover the needs of the framework definitions.
*/
#include <px4_config.h>
#include <px4_posix.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__)
/**
* Namespace encapsulating all device framework classes, functions and data.
*/
namespace device
{
/**
* Fundamental base class for all physical drivers (I2C, SPI).
*
* This class provides the basic driver template for I2C and SPI devices
*/
class __EXPORT Device
{
public:
/**
* Destructor.
*
* Public so that anonymous devices can be destroyed.
*/
virtual ~Device();
/*
* Direct access methods.
*/
/**
* Initialise the driver and make it ready for use.
*
* @return OK if the driver initialized OK, negative errno otherwise;
*/
virtual int init();
/**
* Read directly from the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param offset The device address at which to start reading
* @param data The buffer into which the read values should be placed.
* @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);
/**
* Write directly to the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param address The device address at which to start writing.
* @param data The buffer from which values should be read.
* @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);
/**
* Perform a device-specific operation.
*
* @param operation The operation to perform.
* @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);
/** Device bus types for DEVID */
enum DeviceBusType {
DeviceBusType_UNKNOWN = 0,
DeviceBusType_I2C = 1,
DeviceBusType_SPI = 2,
DeviceBusType_UAVCAN = 3,
};
/**
* Return the bus ID the device is connected to.
*
* @return The bus ID
*/
virtual uint8_t get_device_bus() { return _device_id.devid_s.bus; }
/**
* Return the bus type the device is connected to.
*
* @return The bus type
*/
virtual DeviceBusType get_device_bus_type() { return _device_id.devid_s.bus_type; }
/**
* Return the bus address of the device.
*
* @return The bus address
*/
virtual uint8_t get_device_address() { return _device_id.devid_s.address; }
/**
* Set the device type
*
* @return The device type
*/
virtual void set_device_type(uint8_t devtype) { _device_id.devid_s.devtype = devtype; }
/*
broken out device elements. The bitfields are used to keep
the overall value small enough to fit in a float accurately,
which makes it possible to transport over the MAVLink
parameter protocol without loss of information.
*/
struct DeviceStructure {
enum DeviceBusType bus_type : 3;
uint8_t bus: 5; // which instance of the bus type
uint8_t address; // address on the bus (eg. I2C address)
uint8_t devtype; // device class specific device type
};
union DeviceId {
struct DeviceStructure devid_s;
uint32_t devid;
};
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);
/**
* 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);
}
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 &);
};
} // namespace device
#endif /* _DEVICE_DEVICE_HPP */
-488
View File
@@ -1,488 +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 cdev.cpp
*
* Character device base class.
*/
#include "device.h"
#include "drivers/drv_device.h"
#include <sys/ioctl.h>
#include <arch/irq.h>
#include <cstdlib>
#include <cstdio>
#include <cstring>
#ifdef CONFIG_DISABLE_POLL
# error This driver is not compatible with CONFIG_DISABLE_POLL
#endif
namespace device
{
/* how much to grow the poll waiter set each time it has to be increased */
static const unsigned pollset_increment = 0;
/*
* The standard NuttX operation dispatch table can't call C++ member functions
* directly, so we have to bounce them through this dispatch table.
*/
static int cdev_open(file_t *filp);
static int cdev_close(file_t *filp);
static ssize_t cdev_read(file_t *filp, char *buffer, size_t buflen);
static ssize_t cdev_write(file_t *filp, const char *buffer, size_t buflen);
static off_t cdev_seek(file_t *filp, off_t offset, int whence);
static int cdev_ioctl(file_t *filp, int cmd, unsigned long arg);
static int cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup);
/**
* Character device indirection table.
*
* Every cdev we register gets the same function table; we use the private data
* field in the inode to store the instance pointer.
*
* Note that we use the GNU extension syntax here because we don't get designated
* initialisers in gcc 4.6.
*/
const struct file_operations CDev::fops = {
open : cdev_open,
close : cdev_close,
read : cdev_read,
write : cdev_write,
seek : cdev_seek,
ioctl : cdev_ioctl,
poll : cdev_poll
};
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)
{
}
CDev::~CDev()
{
if (_registered) {
unregister_driver(_devname);
}
if (_pollset) {
delete[](_pollset);
}
}
int
CDev::register_class_devname(const char *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)
{
char name[32];
snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
return unregister_driver(name);
}
int
CDev::init()
{
// base class init first
int ret = Device::init();
if (ret != OK) {
goto out;
}
// now register the driver
if (_devname != nullptr) {
ret = register_driver(_devname, &fops, 0666, (void *)this);
if (ret != OK) {
goto out;
}
_registered = true;
}
out:
return ret;
}
/*
* Default implementations of the character device interface
*/
int
CDev::open(file_t *filp)
{
int ret = OK;
lock();
/* increment the open count */
_open_count++;
if (_open_count == 1) {
/* first-open callback may decline the open */
ret = open_first(filp);
if (ret != OK) {
_open_count--;
}
}
unlock();
return ret;
}
int
CDev::open_first(file_t *filp)
{
return OK;
}
int
CDev::close(file_t *filp)
{
int ret = OK;
lock();
if (_open_count > 0) {
/* decrement the open count */
_open_count--;
/* callback cannot decline the close */
if (_open_count == 0) {
ret = close_last(filp);
}
} else {
ret = -EBADF;
}
unlock();
return ret;
}
int
CDev::close_last(file_t *filp)
{
return OK;
}
ssize_t
CDev::read(file_t *filp, char *buffer, size_t buflen)
{
return -ENOSYS;
}
ssize_t
CDev::write(file_t *filp, const char *buffer, size_t buflen)
{
return -ENOSYS;
}
off_t
CDev::seek(file_t *filp, off_t offset, int whence)
{
return -ENOSYS;
}
int
CDev::ioctl(file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
/* fetch a pointer to the driver's private data */
case DIOC_GETPRIV:
*(void **)(uintptr_t)arg = (void *)this;
return OK;
break;
case DEVIOCSPUBBLOCK:
_pub_blocked = (arg != 0);
return OK;
break;
case DEVIOCGPUBBLOCK:
return _pub_blocked;
break;
}
/* try the superclass. The different ioctl() function form
* means we need to copy arg */
unsigned arg2 = arg;
int ret = Device::ioctl(cmd, arg2);
if (ret != -ENODEV) {
return ret;
}
return -ENOTTY;
}
int
CDev::poll(file_t *filp, struct pollfd *fds, bool setup)
{
int ret = OK;
/*
* Lock against pollnotify() (and possibly other callers)
*/
lock();
if (setup) {
/*
* Save the file pointer in the pollfd for the subclass'
* benefit.
*/
fds->priv = (void *)filp;
/*
* Handle setup requests.
*/
ret = store_poll_waiter(fds);
if (ret == OK) {
/*
* Check to see whether we should send a poll notification
* immediately.
*/
fds->revents |= fds->events & poll_state(filp);
/* yes? post the notification */
if (fds->revents != 0) {
px4_sem_post(fds->sem);
}
}
} else {
/*
* Handle a teardown request.
*/
ret = remove_poll_waiter(fds);
}
unlock();
return ret;
}
void
CDev::poll_notify(pollevent_t events)
{
/* lock against poll() as well as other wakeups */
irqstate_t state = px4_enter_critical_section();
for (unsigned i = 0; i < _max_pollwaiters; i++)
if (nullptr != _pollset[i]) {
poll_notify_one(_pollset[i], events);
}
px4_leave_critical_section(state);
}
void
CDev::poll_notify_one(struct pollfd *fds, pollevent_t events)
{
/* update the reported event set */
fds->revents |= fds->events & events;
/* if the state is now interesting, wake the waiter if it's still asleep */
/* XXX semcount check here is a vile hack; counting semphores should not be abused as cvars */
if ((fds->revents != 0) && (fds->sem->semcount <= 0)) {
px4_sem_post(fds->sem);
}
}
pollevent_t
CDev::poll_state(file_t *filp)
{
/* by default, no poll events to report */
return 0;
}
int
CDev::store_poll_waiter(struct pollfd *fds)
{
/*
* Look for a free slot.
*/
for (unsigned i = 0; i < _max_pollwaiters; i++) {
if (nullptr == _pollset[i]) {
/* save the pollfd */
_pollset[i] = fds;
return OK;
}
}
/* No free slot found. Resize the pollset */
if (_max_pollwaiters >= 256 / 2) { //_max_pollwaiters is uint8_t
return -ENOMEM;
}
const uint8_t new_count = _max_pollwaiters > 0 ? _max_pollwaiters * 2 : 1;
pollfd **new_pollset = new pollfd*[new_count];
if (!new_pollset) {
return -ENOMEM;
}
if (_max_pollwaiters > 0) {
memset(new_pollset + _max_pollwaiters, 0, sizeof(pollfd *) * (new_count - _max_pollwaiters));
memcpy(new_pollset, _pollset, sizeof(pollfd *) * _max_pollwaiters);
delete[](_pollset);
}
_pollset = new_pollset;
_pollset[_max_pollwaiters] = fds;
_max_pollwaiters = new_count;
return OK;
}
int
CDev::remove_poll_waiter(struct pollfd *fds)
{
for (unsigned i = 0; i < _max_pollwaiters; i++) {
if (fds == _pollset[i]) {
_pollset[i] = nullptr;
return OK;
}
}
puts("poll: bad fd state");
return -EINVAL;
}
static int
cdev_open(file_t *filp)
{
CDev *cdev = (CDev *)(filp->f_inode->i_private);
return cdev->open(filp);
}
static int
cdev_close(file_t *filp)
{
CDev *cdev = (CDev *)(filp->f_inode->i_private);
return cdev->close(filp);
}
static ssize_t
cdev_read(file_t *filp, char *buffer, size_t buflen)
{
CDev *cdev = (CDev *)(filp->f_inode->i_private);
return cdev->read(filp, buffer, buflen);
}
static ssize_t
cdev_write(file_t *filp, const char *buffer, size_t buflen)
{
CDev *cdev = (CDev *)(filp->f_inode->i_private);
return cdev->write(filp, buffer, buflen);
}
static off_t
cdev_seek(file_t *filp, off_t offset, int whence)
{
CDev *cdev = (CDev *)(filp->f_inode->i_private);
return cdev->seek(filp, offset, whence);
}
static int
cdev_ioctl(file_t *filp, int cmd, unsigned long arg)
{
CDev *cdev = (CDev *)(filp->f_inode->i_private);
return cdev->ioctl(filp, cmd, arg);
}
static int
cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup)
{
CDev *cdev = (CDev *)(filp->f_inode->i_private);
return cdev->poll(filp, fds, setup);
}
} // namespace device
+2 -15
View File
@@ -33,18 +33,5 @@
#pragma once
#ifdef __PX4_NUTTX
#include "nuttx/device_nuttx.h"
#include <nuttx/arch.h>
#define ATOMIC_ENTER irqstate_t flags = px4_enter_critical_section()
#define ATOMIC_LEAVE px4_leave_critical_section(flags)
#elif defined (__PX4_POSIX)
#include "posix/vdev.h"
#define ATOMIC_ENTER lock()
#define ATOMIC_LEAVE unlock()
#endif
#include "Device.hpp"
#include "CDev.hpp"
+140
View File
@@ -0,0 +1,140 @@
/****************************************************************************
*
* 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_platform.cpp
*
* NuttX Character device functions
*/
#include "cdev_platform.hpp"
#include "../CDev.hpp"
#include "px4_posix.h"
#include "drivers/drv_device.h"
#include <sys/ioctl.h>
#ifdef CONFIG_DISABLE_POLL
# error This driver is not compatible with CONFIG_DISABLE_POLL
#endif
namespace device
{
/*
* The standard NuttX operation dispatch table can't call C++ member functions
* directly, so we have to bounce them through this dispatch table.
*/
static int cdev_open(file_t *filp);
static int cdev_close(file_t *filp);
static ssize_t cdev_read(file_t *filp, char *buffer, size_t buflen);
static ssize_t cdev_write(file_t *filp, const char *buffer, size_t buflen);
static off_t cdev_seek(file_t *filp, off_t offset, int whence);
static int cdev_ioctl(file_t *filp, int cmd, unsigned long arg);
static int cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup);
/**
* Character device indirection table.
*
* Every cdev we register gets the same function table; we use the private data
* field in the inode to store the instance pointer.
*
* 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 = {
open : cdev_open,
close : cdev_close,
read : cdev_read,
write : cdev_write,
seek : cdev_seek,
ioctl : cdev_ioctl,
poll : cdev_poll
};
static int
cdev_open(file_t *filp)
{
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
return cdev->open(filp);
}
static int
cdev_close(file_t *filp)
{
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
return cdev->close(filp);
}
static ssize_t
cdev_read(file_t *filp, char *buffer, size_t buflen)
{
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
return cdev->read(filp, buffer, 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);
return cdev->write(filp, buffer, buflen);
}
static off_t
cdev_seek(file_t *filp, off_t offset, int whence)
{
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
return cdev->seek(filp, offset, whence);
}
static int
cdev_ioctl(file_t *filp, int cmd, unsigned long arg)
{
device::CDev *cdev = (device::CDev *)(filp->f_inode->i_private);
return cdev->ioctl(filp, cmd, 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);
return cdev->poll(filp, fds, setup);
}
} // namespace device
@@ -0,0 +1,18 @@
#pragma once
#include <cinttypes>
#include <px4_micro_hal.h>
#include <nuttx/arch.h>
#define ATOMIC_ENTER irqstate_t flags = px4_enter_critical_section()
#define ATOMIC_LEAVE px4_leave_critical_section(flags)
namespace device
{
using px4_file_operations_t = struct file_operations;
using file_t = struct file;
} // namespace device
-489
View File
@@ -1,489 +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_nuttx.h
*
* Definitions for the generic base classes in the device framework.
*/
#ifndef _DEVICE_DEVICE_H
#define _DEVICE_DEVICE_H
/*
* Includes here should only cover the needs of the framework definitions.
*/
#include <px4_config.h>
#include <px4_posix.h>
#include <errno.h>
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
#include <poll.h>
#include <nuttx/fs/fs.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__)
/**
* Namespace encapsulating all device framework classes, functions and data.
*/
namespace device __EXPORT
{
typedef struct file file_t;
/**
* Fundamental base class for all device drivers.
*
* This class handles the basic "being a driver" things, including
* interrupt registration and dispatch.
*/
class __EXPORT Device
{
public:
/**
* Destructor.
*
* Public so that anonymous devices can be destroyed.
*/
virtual ~Device();
/*
* Direct access methods.
*/
/**
* Initialise the driver and make it ready for use.
*
* @return OK if the driver initialized OK, negative errno otherwise;
*/
virtual int init();
/**
* Read directly from the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param offset The device address at which to start reading
* @param data The buffer into which the read values should be placed.
* @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);
/**
* Write directly to the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param address The device address at which to start writing.
* @param data The buffer from which values should be read.
* @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);
/**
* Perform a device-specific operation.
*
* @param operation The operation to perform.
* @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);
/** Device bus types for DEVID */
enum DeviceBusType {
DeviceBusType_UNKNOWN = 0,
DeviceBusType_I2C = 1,
DeviceBusType_SPI = 2,
DeviceBusType_UAVCAN = 3,
};
/**
* Return the bus ID the device is connected to.
*
* @return The bus ID
*/
virtual uint8_t get_device_bus() { return _device_id.devid_s.bus; }
/**
* Return the bus type the device is connected to.
*
* @return The bus type
*/
virtual DeviceBusType get_device_bus_type() { return _device_id.devid_s.bus_type; }
/**
* Return the bus address of the device.
*
* @return The bus address
*/
virtual uint8_t get_device_address() { return _device_id.devid_s.address; }
/**
* Set the device type
*
* @return The device type
*/
virtual void set_device_type(uint8_t devtype) { _device_id.devid_s.devtype = devtype; }
/*
broken out device elements. The bitfields are used to keep
the overall value small enough to fit in a float accurately,
which makes it possible to transport over the MAVLink
parameter protocol without loss of information.
*/
struct DeviceStructure {
enum DeviceBusType bus_type : 3;
uint8_t bus: 5; // which instance of the bus type
uint8_t address; // address on the bus (eg. I2C address)
uint8_t devtype; // device class specific device type
};
union DeviceId {
struct DeviceStructure devid_s;
uint32_t devid;
};
protected:
const char *_name; /**< driver name */
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);
/**
* Enable the device interrupt
*/
void interrupt_enable();
/**
* Disable the device interrupt
*/
void interrupt_disable();
/**
* 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 (sem_wait(&_lock) != 0);
}
/**
* Release the driver lock.
*/
void unlock()
{
sem_post(&_lock);
}
DeviceId &get_device_id() { return _device_id; }
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 &);
};
/**
* Abstract class for any character device
*/
class __EXPORT CDev : public Device
{
public:
/**
* Constructor
*
* @param name Driver name
* @param devname Device node name
*/
CDev(const char *name, const char *devname);
/**
* Destructor
*/
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 filp Pointer to the NuttX file structure.
* @return OK if the open is allowed, -errno otherwise.
*/
virtual int open(file_t *filp);
/**
* 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 filp Pointer to the NuttX file structure.
* @return OK if the close was successful, -errno otherwise.
*/
virtual int close(file_t *filp);
/**
* Perform a read from the device.
*
* The default implementation returns -ENOSYS.
*
* @param filp 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 *filp, char *buffer, size_t buflen);
/**
* Perform a write to the device.
*
* The default implementation returns -ENOSYS.
*
* @param filp 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 *filp, const char *buffer, size_t buflen);
/**
* Perform a logical seek operation on the device.
*
* The default implementation returns -ENOSYS.
*
* @param filp 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 *filp, off_t offset, int whence);
/**
* 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 filp 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 *filp, int cmd, unsigned long arg);
/**
* Perform a poll setup/teardown operation.
*
* This is handled internally and should not normally be overridden.
*
* @param filp Pointer to the NuttX file structure.
* @param fds Poll descriptor being waited on.
* @param arg 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 *filp, struct pollfd *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
* registering clone devices etc.
*/
static const struct file_operations 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 filp The file that's interested.
* @return The current set of poll events.
*/
virtual pollevent_t poll_state(file_t *filp);
/**
* 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 filp Pointer to the NuttX file structure.
* @return OK if the open should proceed, -errno otherwise.
*/
virtual int open_first(file_t *filp);
/**
* 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 filp Pointer to the NuttX file structure.
* @return OK if the open should return OK, -errno otherwise.
*/
virtual int close_last(file_t *filp);
/**
* 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; }
bool _pub_blocked; /**< true if publishing should be blocked */
private:
const char *_devname; /**< device node name */
bool _registered; /**< true if device name was registered */
uint8_t _max_pollwaiters; /**< size of the _pollset array */
uint16_t _open_count; /**< number of successful opens */
struct pollfd **_pollset;
/**
* 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(struct pollfd *fds);
/* do not allow copying this class */
CDev(const CDev &);
CDev operator=(const CDev &);
};
} // namespace device
// class instance for primary driver of each class
enum CLASS_DEVICE {
CLASS_DEVICE_PRIMARY = 0,
CLASS_DEVICE_SECONDARY = 1,
CLASS_DEVICE_TERTIARY = 2
};
#endif /* _DEVICE_DEVICE_H */
@@ -37,49 +37,66 @@
* POSIX-like API for virtual character device
*/
#include "cdev_platform.hpp"
#include <string>
#include <map>
#include "vfile.h"
#include "../CDev.hpp"
#include <px4_log.h>
#include <px4_posix.h>
#include <px4_time.h>
#include "device.h"
#include "vfile.h"
#include <hrt_work.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <pthread.h>
#include <unistd.h>
#include "DevMgr.hpp"
using namespace device;
using namespace std;
using namespace DriverFramework;
const device::px4_file_operations_t device::CDev::fops = {};
pthread_mutex_t devmutex = PTHREAD_MUTEX_INITIALIZER;
pthread_mutex_t filemutex = PTHREAD_MUTEX_INITIALIZER;
px4_sem_t lockstep_sem;
bool sim_lockstep = false;
volatile bool sim_delay = false;
extern "C" {
#define PX4_MAX_FD 350
static device::file_t filemap[PX4_MAX_FD] = {};
static map<string, void *> devmap;
static device::file_t filemap[PX4_MAX_FD] = {};
extern "C" {
int px4_errno;
inline bool valid_fd(int fd)
static device::CDev *getDev(const char *path)
{
pthread_mutex_lock(&filemutex);
bool ret = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd].vdev);
pthread_mutex_unlock(&filemutex);
return ret;
PX4_DEBUG("CDev::getDev");
pthread_mutex_lock(&devmutex);
auto item = devmap.find(path);
if (item != devmap.end()) {
pthread_mutex_unlock(&devmutex);
return (device::CDev *)item->second;
}
pthread_mutex_unlock(&devmutex);
return nullptr;
}
inline CDev *get_vdev(int fd)
static device::CDev *get_vdev(int fd)
{
pthread_mutex_lock(&filemutex);
bool valid = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd].vdev);
CDev *dev;
device::CDev *dev;
if (valid) {
dev = (CDev *)(filemap[fd].vdev);
dev = (device::CDev *)(filemap[fd].vdev);
} else {
dev = nullptr;
@@ -89,10 +106,58 @@ extern "C" {
return dev;
}
int register_driver(const char *name, const device::px4_file_operations_t *fops, mode_t mode, void *data)
{
PX4_DEBUG("CDev::register_driver %s", name);
int ret = 0;
if (name == nullptr || data == nullptr) {
return -EINVAL;
}
pthread_mutex_lock(&devmutex);
// Make sure the device does not already exist
auto item = devmap.find(name);
if (item != devmap.end()) {
pthread_mutex_unlock(&devmutex);
return -EEXIST;
}
devmap[name] = (void *)data;
PX4_DEBUG("Registered DEV %s", name);
pthread_mutex_unlock(&devmutex);
return ret;
}
int unregister_driver(const char *name)
{
PX4_DEBUG("CDev::unregister_driver %s", name);
int ret = -EINVAL;
if (name == nullptr) {
return -EINVAL;
}
pthread_mutex_lock(&devmutex);
if (devmap.erase(name) > 0) {
PX4_DEBUG("Unregistered DEV %s", name);
ret = 0;
}
pthread_mutex_unlock(&devmutex);
return ret;
}
int px4_open(const char *path, int flags, ...)
{
PX4_DEBUG("px4_open");
CDev *dev = CDev::getDev(path);
device::CDev *dev = getDev(path);
int ret = 0;
int i;
mode_t mode;
@@ -107,7 +172,7 @@ extern "C" {
// Create the file
PX4_DEBUG("Creating virtual file %s", path);
dev = VFile::createFile(path, mode);
dev = device::VFile::createFile(path, mode);
}
if (dev) {
@@ -151,7 +216,6 @@ extern "C" {
}
if (ret < 0) {
px4_errno = -ret;
return -1;
}
@@ -163,7 +227,7 @@ extern "C" {
{
int ret;
CDev *dev = get_vdev(fd);
device::CDev *dev = get_vdev(fd);
if (dev) {
pthread_mutex_lock(&filemutex);
@@ -190,7 +254,7 @@ extern "C" {
{
int ret;
CDev *dev = get_vdev(fd);
device::CDev *dev = get_vdev(fd);
if (dev) {
PX4_DEBUG("px4_read fd = %d", fd);
@@ -212,7 +276,7 @@ extern "C" {
{
int ret;
CDev *dev = get_vdev(fd);
device::CDev *dev = get_vdev(fd);
if (dev) {
PX4_DEBUG("px4_write fd = %d", fd);
@@ -235,7 +299,7 @@ extern "C" {
PX4_DEBUG("px4_ioctl fd = %d", fd);
int ret = 0;
CDev *dev = get_vdev(fd);
device::CDev *dev = get_vdev(fd);
if (dev) {
ret = dev->ioctl(&filemap[fd], cmd, arg);
@@ -294,7 +358,7 @@ extern "C" {
fds[i].revents = 0;
fds[i].priv = nullptr;
CDev *dev = get_vdev(fds[i].fd);
device::CDev *dev = get_vdev(fds[i].fd);
// If fd is valid
if (dev) {
@@ -355,7 +419,7 @@ extern "C" {
// go through all fds and count how many have data
for (i = 0; i < nfds; ++i) {
CDev *dev = get_vdev(fds[i].fd);
device::CDev *dev = get_vdev(fds[i].fd);
// If fd is valid
if (dev) {
@@ -393,23 +457,69 @@ extern "C" {
return -1;
}
CDev *dev = CDev::getDev(pathname);
device::CDev *dev = getDev(pathname);
return (dev != nullptr) ? 0 : -1;
}
void px4_show_devices()
{
CDev::showDevices();
int i = 0;
PX4_INFO("PX4 Devices:");
pthread_mutex_lock(&devmutex);
for (const auto &dev : devmap) {
if (strncmp(dev.first.c_str(), "/dev/", 5) == 0) {
PX4_INFO(" %s", dev.first.c_str());
}
}
pthread_mutex_unlock(&devmutex);
PX4_INFO("DF Devices:");
const char *dev_path;
unsigned int index = 0;
i = 0;
do {
// Each look increments index and returns -1 if end reached
i = DevMgr::getNextDeviceName(index, &dev_path);
if (i == 0) {
PX4_INFO(" %s", dev_path);
}
} while (i == 0);
}
void px4_show_topics()
{
CDev::showTopics();
PX4_INFO("Devices:");
pthread_mutex_lock(&devmutex);
for (const auto &dev : devmap) {
if (strncmp(dev.first.c_str(), "/obj/", 5) == 0) {
PX4_INFO(" %s", dev.first.c_str());
}
}
pthread_mutex_unlock(&devmutex);
}
void px4_show_files()
{
CDev::showFiles();
PX4_INFO("Files:");
pthread_mutex_lock(&devmutex);
for (const auto &dev : devmap) {
if (strncmp(dev.first.c_str(), "/obj/", 5) != 0 &&
strncmp(dev.first.c_str(), "/dev/", 5) != 0) {
PX4_INFO(" %s", dev.first.c_str());
}
}
pthread_mutex_unlock(&devmutex);
}
void px4_enable_sim_lockstep()
@@ -417,7 +527,6 @@ extern "C" {
px4_sem_init(&lockstep_sem, 0, 0);
// lockstep_sem use case is a signal
px4_sem_setprotocol(&lockstep_sem, SEM_PRIO_NONE);
sim_lockstep = true;
@@ -439,5 +548,4 @@ extern "C" {
return sim_delay;
}
}
} // extern "C"
@@ -0,0 +1,32 @@
#pragma once
#include <cinttypes>
#define ATOMIC_ENTER lock()
#define ATOMIC_LEAVE unlock()
namespace device
{
struct file_operations {
void *op;
};
using px4_file_operations_t = struct file_operations;
using mode_t = uint32_t;
struct file_t {
int flags;
void *priv;
void *vdev;
file_t() : flags(0), priv(nullptr), vdev(nullptr) {}
file_t(int f, void *c) : flags(f), priv(nullptr), vdev(c) {}
};
} // namespace device
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 unregister_driver(const char *path);
-109
View File
@@ -1,109 +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 virtual device framework.
*/
#include "device.h"
#include <px4_defines.h>
#include <px4_posix.h>
#include <drivers/drv_device.h>
#include <stdio.h>
#include <unistd.h>
#include <sys/stat.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, %s", ret, strerror(errno));
}
/* 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::dev_read(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
int
Device::dev_write(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
int
Device::dev_ioctl(unsigned operation, unsigned arg)
{
switch (operation) {
case DEVIOCGDEVICEID:
return (int)_device_id.devid;
}
return -ENODEV;
}
} // namespace device
+1 -1
View File
@@ -40,7 +40,7 @@
#ifndef _DEVICE_I2C_H
#define _DEVICE_I2C_H
#include "vdev.h"
#include "../CDev.hpp"
#include <px4_i2c.h>
#ifdef __PX4_LINUX
+6 -4
View File
@@ -39,9 +39,9 @@
*/
#include "vfile.h"
#include <stdio.h>
using namespace device;
namespace device
{
VFile::VFile(const char *fname, mode_t mode) :
CDev("vfile", fname)
@@ -51,11 +51,12 @@ VFile::VFile(const char *fname, mode_t mode) :
VFile *VFile::createFile(const char *fname, mode_t mode)
{
VFile *me = new VFile(fname, mode);
me->register_driver(fname, me);
px4_file_operations_t *fops = nullptr;
register_driver(fname, fops, 0666, (void *)me);
return me;
}
ssize_t VFile::write(device::file_t *handlep, const char *buffer, size_t buflen)
ssize_t VFile::write(file_t *handlep, const char *buffer, size_t buflen)
{
// ignore what was written, but let pollers know something was written
poll_notify(POLLIN);
@@ -63,3 +64,4 @@ ssize_t VFile::write(device::file_t *handlep, const char *buffer, size_t buflen)
return buflen;
}
} // namespace device
+8 -7
View File
@@ -40,22 +40,23 @@
#pragma once
#include <px4_tasks.h>
#include <drivers/drv_device.h>
#include "device.h"
#include <unistd.h>
#include <stdio.h>
#include "../CDev.hpp"
class VFile : public device::CDev
namespace device
{
class VFile : public CDev
{
public:
static VFile *createFile(const char *fname, mode_t mode);
~VFile() {}
virtual ssize_t write(device::file_t *handlep, const char *buffer, size_t buflen);
ssize_t write(file_t *handlep, const char *buffer, size_t buflen) override;
private:
VFile(const char *fname, mode_t mode);
VFile(const VFile &);
};
} // namespace device