diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-04-28 09:54:11 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-04-28 09:54:11 +0200 |
commit | 13fc6703862862f4263d8d5d085b7a16b87190e1 (patch) | |
tree | 47f3a17cb6f38b1aafe22e1cdef085cd73cd3a1d /src/drivers | |
parent | f57439b90e23de260259dec051d3e2ead2d61c8c (diff) | |
download | px4-firmware-13fc6703862862f4263d8d5d085b7a16b87190e1.tar.gz px4-firmware-13fc6703862862f4263d8d5d085b7a16b87190e1.tar.bz2 px4-firmware-13fc6703862862f4263d8d5d085b7a16b87190e1.zip |
Moved last libs, drivers and headers, cleaned up IO build
Diffstat (limited to 'src/drivers')
28 files changed, 3752 insertions, 0 deletions
diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp new file mode 100644 index 000000000..422321850 --- /dev/null +++ b/src/drivers/device/cdev.cpp @@ -0,0 +1,398 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 <sys/ioctl.h> +#include <arch/irq.h> + +#include <stdlib.h> +#include <stdio.h> + +#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(struct file *filp); +static int cdev_close(struct file *filp); +static ssize_t cdev_read(struct file *filp, char *buffer, size_t buflen); +static ssize_t cdev_write(struct file *filp, const char *buffer, size_t buflen); +static off_t cdev_seek(struct file *filp, off_t offset, int whence); +static int cdev_ioctl(struct file *filp, int cmd, unsigned long arg); +static int cdev_poll(struct file *filp, struct pollfd *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, + int irq) : + // base class + Device(name, irq), + // public + // protected + // private + _devname(devname), + _registered(false), + _open_count(0) +{ + for (unsigned i = 0; i < _max_pollwaiters; i++) + _pollset[i] = nullptr; +} + +CDev::~CDev() +{ + if (_registered) + unregister_driver(_devname); +} + +int +CDev::init() +{ + int ret = OK; + + // base class init first + ret = Device::init(); + + if (ret != OK) + goto out; + + // now register the driver + 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(struct file *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(struct file *filp) +{ + return OK; +} + +int +CDev::close(struct file *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(struct file *filp) +{ + return OK; +} + +ssize_t +CDev::read(struct file *filp, char *buffer, size_t buflen) +{ + return -ENOSYS; +} + +ssize_t +CDev::write(struct file *filp, const char *buffer, size_t buflen) +{ + return -ENOSYS; +} + +off_t +CDev::seek(struct file *filp, off_t offset, int whence) +{ + return -ENOSYS; +} + +int +CDev::ioctl(struct file *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; + } + + return -ENOTTY; +} + +int +CDev::poll(struct file *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) + 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 = irqsave(); + + for (unsigned i = 0; i < _max_pollwaiters; i++) + if (nullptr != _pollset[i]) + poll_notify_one(_pollset[i], events); + + irqrestore(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)) + sem_post(fds->sem); +} + +pollevent_t +CDev::poll_state(struct file *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; + } + } + + return ENOMEM; +} + +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(struct file *filp) +{ + CDev *cdev = (CDev *)(filp->f_inode->i_private); + + return cdev->open(filp); +} + +static int +cdev_close(struct file *filp) +{ + CDev *cdev = (CDev *)(filp->f_inode->i_private); + + return cdev->close(filp); +} + +static ssize_t +cdev_read(struct file *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(struct file *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(struct file *filp, off_t offset, int whence) +{ + CDev *cdev = (CDev *)(filp->f_inode->i_private); + + return cdev->seek(filp, offset, whence); +} + +static int +cdev_ioctl(struct file *filp, int cmd, unsigned long arg) +{ + CDev *cdev = (CDev *)(filp->f_inode->i_private); + + return cdev->ioctl(filp, cmd, arg); +} + +static int +cdev_poll(struct file *filp, struct pollfd *fds, bool setup) +{ + CDev *cdev = (CDev *)(filp->f_inode->i_private); + + return cdev->poll(filp, fds, setup); +} + +} // namespace device
\ No newline at end of file diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp new file mode 100644 index 000000000..04a5222c3 --- /dev/null +++ b/src/drivers/device/device.cpp @@ -0,0 +1,227 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file device.cpp + * + * Fundamental driver base class for the device framework. + */ + +#include "device.h" + +#include <nuttx/arch.h> +#include <stdio.h> +#include <unistd.h> + +namespace device +{ + +/** + * Interrupt dispatch table entry. + */ +struct irq_entry { + int irq; + Device *owner; +}; + +static const unsigned irq_nentries = 8; /**< size of the interrupt dispatch table */ +static irq_entry irq_entries[irq_nentries]; /**< interrupt dispatch table (XXX should be a vector) */ + +/** + * Register an interrupt to a specific device. + * + * @param irq The interrupt number to register. + * @param owner The device receiving the interrupt. + * @return OK if the interrupt was registered. + */ +static int register_interrupt(int irq, Device *owner); + +/** + * Unregister an interrupt. + * + * @param irq The previously-registered interrupt to be de-registered. + */ +static void unregister_interrupt(int irq); + +/** + * Handle an interrupt. + * + * @param irq The interrupt being invoked. + * @param context The interrupt register context. + * @return Always returns OK. + */ +static int interrupt(int irq, void *context); + +Device::Device(const char *name, + int irq) : + // public + // protected + _name(name), + _debug_enabled(false), + // private + _irq(irq), + _irq_attached(false) +{ + sem_init(&_lock, 0, 1); +} + +Device::~Device() +{ + sem_destroy(&_lock); + + if (_irq_attached) + unregister_interrupt(_irq); +} + +int +Device::init() +{ + int ret = OK; + + // If assigned an interrupt, connect it + if (_irq) { + /* ensure it's disabled */ + up_disable_irq(_irq); + + /* register */ + ret = register_interrupt(_irq, this); + + if (ret != OK) + goto out; + + _irq_attached = true; + } + +out: + return ret; +} + +void +Device::interrupt_enable() +{ + if (_irq_attached) + up_enable_irq(_irq); +} + +void +Device::interrupt_disable() +{ + if (_irq_attached) + up_disable_irq(_irq); +} + +void +Device::interrupt(void *context) +{ + // default action is to disable the interrupt so we don't get called again + interrupt_disable(); +} + +void +Device::log(const char *fmt, ...) +{ + va_list ap; + + printf("[%s] ", _name); + va_start(ap, fmt); + vprintf(fmt, ap); + va_end(ap); + printf("\n"); + fflush(stdout); +} + +void +Device::debug(const char *fmt, ...) +{ + va_list ap; + + if (_debug_enabled) { + printf("<%s> ", _name); + va_start(ap, fmt); + vprintf(fmt, ap); + va_end(ap); + printf("\n"); + fflush(stdout); + } +} + +static int +register_interrupt(int irq, Device *owner) +{ + int ret = -ENOMEM; + + // look for a slot where we can register the interrupt + for (unsigned i = 0; i < irq_nentries; i++) { + if (irq_entries[i].irq == 0) { + + // great, we could put it here; try attaching it + ret = irq_attach(irq, &interrupt); + + if (ret == OK) { + irq_entries[i].irq = irq; + irq_entries[i].owner = owner; + } + + break; + } + } + + return ret; +} + +static void +unregister_interrupt(int irq) +{ + for (unsigned i = 0; i < irq_nentries; i++) { + if (irq_entries[i].irq == irq) { + irq_entries[i].irq = 0; + irq_entries[i].owner = nullptr; + } + } +} + +static int +interrupt(int irq, void *context) +{ + for (unsigned i = 0; i < irq_nentries; i++) { + if (irq_entries[i].irq == irq) { + irq_entries[i].owner->interrupt(context); + break; + } + } + + return OK; +} + + +} // namespace device
\ No newline at end of file diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h new file mode 100644 index 000000000..7d375aab9 --- /dev/null +++ b/src/drivers/device/device.h @@ -0,0 +1,447 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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.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 <nuttx/config.h> + +#include <errno.h> +#include <stdbool.h> +#include <stddef.h> +#include <stdint.h> +#include <poll.h> + +#include <nuttx/fs/fs.h> + +/** + * Namespace encapsulating all device framework classes, functions and data. + */ +namespace device __EXPORT +{ + +/** + * 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: + /** + * Interrupt handler. + */ + virtual void interrupt(void *ctx); /**< interrupt handler */ + +protected: + const char *_name; /**< driver name */ + bool _debug_enabled; /**< if true, debug messages are printed */ + + /** + * Constructor + * + * @param name Driver name + * @param irq Interrupt assigned to the device. + */ + Device(const char *name, + int irq = 0); + ~Device(); + + /** + * Initialise the driver and make it ready for use. + * + * @return OK if the driver initialised OK. + */ + virtual int init(); + + /** + * 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. + */ + void lock() { + do {} while (sem_wait(&_lock) != 0); + } + + /** + * Release the driver lock. + */ + void unlock() { + sem_post(&_lock); + } + + /** + * Log a message. + * + * The message is prefixed with the driver name, and followed + * by a newline. + */ + void log(const char *fmt, ...); + + /** + * Print a debug message. + * + * The message is prefixed with the driver name, and followed + * by a newline. + */ + void debug(const char *fmt, ...); + +private: + int _irq; + bool _irq_attached; + sem_t _lock; + + /** disable copy construction for this and all subclasses */ + Device(const Device &); + + /** disable assignment for this and all subclasses */ + Device &operator = (const Device &); + + /** + * Register ourselves as a handler for an interrupt + * + * @param irq The interrupt to claim + * @return OK if the interrupt was registered + */ + int dev_register_interrupt(int irq); + + /** + * Unregister ourselves as a handler for any interrupt + */ + void dev_unregister_interrupt(); + + /** + * Interrupt dispatcher + * + * @param irq The interrupt that has been triggered. + * @param context Pointer to the interrupted context. + */ + static void dev_interrupt(int irq, void *context); +}; + +/** + * Abstract class for any character device + */ +class __EXPORT CDev : public Device +{ +public: + /** + * Constructor + * + * @param name Driver name + * @param devname Device node name + * @param irq Interrupt assigned to the device + */ + CDev(const char *name, const char *devname, int irq = 0); + + /** + * Destructor + */ + ~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(struct file *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(struct file *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(struct file *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(struct file *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(struct file *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(struct file *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(struct file *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. + * + * @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(struct file *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(struct pollfd *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(struct file *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(struct file *filp); + +private: + static const unsigned _max_pollwaiters = 8; + + const char *_devname; /**< device node name */ + bool _registered; /**< true if device name was registered */ + unsigned _open_count; /**< number of successful opens */ + + struct pollfd *_pollset[_max_pollwaiters]; + + /** + * 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(struct pollfd *fds); + + /** + * Remove a poll waiter. + * + * @return OK, or -errno on error. + */ + int remove_poll_waiter(struct pollfd *fds); +}; + +/** + * Abstract class for character device accessed via PIO + */ +class __EXPORT PIO : public CDev +{ +public: + /** + * Constructor + * + * @param name Driver name + * @param devname Device node name + * @param base Base address of the device PIO area + * @param irq Interrupt assigned to the device (or zero if none) + */ + PIO(const char *name, + const char *devname, + uint32_t base, + int irq = 0); + ~PIO(); + + int init(); + +protected: + + /** + * Read a register + * + * @param offset Register offset in bytes from the base address. + */ + uint32_t reg(uint32_t offset) { + return *(volatile uint32_t *)(_base + offset); + } + + /** + * Write a register + * + * @param offset Register offset in bytes from the base address. + * @param value Value to write. + */ + void reg(uint32_t offset, uint32_t value) { + *(volatile uint32_t *)(_base + offset) = value; + } + + /** + * Modify a register + * + * Note that there is a risk of a race during the read/modify/write cycle + * that must be taken care of by the caller. + * + * @param offset Register offset in bytes from the base address. + * @param clearbits Bits to clear in the register + * @param setbits Bits to set in the register + */ + void modify(uint32_t offset, uint32_t clearbits, uint32_t setbits) { + uint32_t val = reg(offset); + val &= ~clearbits; + val |= setbits; + reg(offset, val); + } + +private: + uint32_t _base; +}; + +} // namespace device + +#endif /* _DEVICE_DEVICE_H */
\ No newline at end of file diff --git a/src/drivers/device/i2c.cpp b/src/drivers/device/i2c.cpp new file mode 100644 index 000000000..a416801eb --- /dev/null +++ b/src/drivers/device/i2c.cpp @@ -0,0 +1,204 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 i2c.cpp + * + * Base class for devices attached via the I2C bus. + * + * @todo Bus frequency changes; currently we do nothing with the value + * that is supplied. Should we just depend on the bus knowing? + */ + +#include "i2c.h" + +namespace device +{ + +I2C::I2C(const char *name, + const char *devname, + int bus, + uint16_t address, + uint32_t frequency, + int irq) : + // base class + CDev(name, devname, irq), + // public + // protected + _retries(0), + // private + _bus(bus), + _address(address), + _frequency(frequency), + _dev(nullptr) +{ +} + +I2C::~I2C() +{ + if (_dev) + up_i2cuninitialize(_dev); +} + +int +I2C::init() +{ + int ret = OK; + + /* attach to the i2c bus */ + _dev = up_i2cinitialize(_bus); + + if (_dev == nullptr) { + debug("failed to init I2C"); + ret = -ENOENT; + goto out; + } + + // call the probe function to check whether the device is present + ret = probe(); + + if (ret != OK) { + debug("probe failed"); + goto out; + } + + // do base class init, which will create device node, etc + ret = CDev::init(); + + if (ret != OK) { + debug("cdev init failed"); + goto out; + } + + // tell the world where we are + log("on I2C bus %d at 0x%02x", _bus, _address); + +out: + return ret; +} + +int +I2C::probe() +{ + // Assume the device is too stupid to be discoverable. + return OK; +} + +int +I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len) +{ + struct i2c_msg_s msgv[2]; + unsigned msgs; + int ret; + unsigned retry_count = 0; + + do { + // debug("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len); + + msgs = 0; + + if (send_len > 0) { + msgv[msgs].addr = _address; + msgv[msgs].flags = 0; + msgv[msgs].buffer = const_cast<uint8_t *>(send); + msgv[msgs].length = send_len; + msgs++; + } + + if (recv_len > 0) { + msgv[msgs].addr = _address; + msgv[msgs].flags = I2C_M_READ; + msgv[msgs].buffer = recv; + msgv[msgs].length = recv_len; + msgs++; + } + + if (msgs == 0) + return -EINVAL; + + /* + * I2C architecture means there is an unavoidable race here + * if there are any devices on the bus with a different frequency + * preference. Really, this is pointless. + */ + I2C_SETFREQUENCY(_dev, _frequency); + ret = I2C_TRANSFER(_dev, &msgv[0], msgs); + + /* success */ + if (ret == OK) + break; + + /* if we have already retried once, or we are going to give up, then reset the bus */ + if ((retry_count >= 1) || (retry_count >= _retries)) + up_i2creset(_dev); + + } while (retry_count++ < _retries); + + return ret; + +} + +int +I2C::transfer(i2c_msg_s *msgv, unsigned msgs) +{ + int ret; + unsigned retry_count = 0; + + /* force the device address into the message vector */ + for (unsigned i = 0; i < msgs; i++) + msgv[i].addr = _address; + + + do { + /* + * I2C architecture means there is an unavoidable race here + * if there are any devices on the bus with a different frequency + * preference. Really, this is pointless. + */ + I2C_SETFREQUENCY(_dev, _frequency); + ret = I2C_TRANSFER(_dev, msgv, msgs); + + /* success */ + if (ret == OK) + break; + + /* if we have already retried once, or we are going to give up, then reset the bus */ + if ((retry_count >= 1) || (retry_count >= _retries)) + up_i2creset(_dev); + + } while (retry_count++ < _retries); + + return ret; +} + +} // namespace device
\ No newline at end of file diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h new file mode 100644 index 000000000..7daba31be --- /dev/null +++ b/src/drivers/device/i2c.h @@ -0,0 +1,138 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 i2c.h + * + * Base class for devices connected via I2C. + */ + +#ifndef _DEVICE_I2C_H +#define _DEVICE_I2C_H + +#include "device.h" + +#include <nuttx/i2c.h> + +namespace device __EXPORT +{ + +/** + * Abstract class for character device on I2C + */ +class __EXPORT I2C : public CDev +{ + +protected: + /** + * The number of times a read or write operation will be retried on + * error. + */ + unsigned _retries; + + /** + * The I2C bus number the device is attached to. + */ + int _bus; + + /** + * @ Constructor + * + * @param name Driver name + * @param devname Device node name + * @param bus I2C bus on which the device lives + * @param address I2C bus address, or zero if set_address will be used + * @param frequency I2C bus frequency for the device (currently not used) + * @param irq Interrupt assigned to the device (or zero if none) + */ + I2C(const char *name, + const char *devname, + int bus, + uint16_t address, + uint32_t frequency, + int irq = 0); + ~I2C(); + + virtual int init(); + + /** + * Check for the presence of the device on the bus. + */ + virtual int probe(); + + /** + * Perform an I2C transaction to the device. + * + * At least one of send_len and recv_len must be non-zero. + * + * @param send Pointer to bytes to send. + * @param send_len Number of bytes to send. + * @param recv Pointer to buffer for bytes received. + * @param recv_len Number of bytes to receive. + * @return OK if the transfer was successful, -errno + * otherwise. + */ + int transfer(const uint8_t *send, unsigned send_len, + uint8_t *recv, unsigned recv_len); + + /** + * Perform a multi-part I2C transaction to the device. + * + * @param msgv An I2C message vector. + * @param msgs The number of entries in the message vector. + * @return OK if the transfer was successful, -errno + * otherwise. + */ + int transfer(i2c_msg_s *msgv, unsigned msgs); + + /** + * Change the bus address. + * + * Most often useful during probe() when the driver is testing + * several possible bus addresses. + * + * @param address The new bus address to set. + */ + void set_address(uint16_t address) { + _address = address; + } + +private: + uint16_t _address; + uint32_t _frequency; + struct i2c_dev_s *_dev; +}; + +} // namespace device + +#endif /* _DEVICE_I2C_H */ diff --git a/src/drivers/device/module.mk b/src/drivers/device/module.mk new file mode 100644 index 000000000..8c716d9cd --- /dev/null +++ b/src/drivers/device/module.mk @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2012, 2013 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. +# +############################################################################ + +# +# Build the device driver framework. +# + +SRCS = cdev.cpp \ + device.cpp \ + i2c.cpp \ + pio.cpp \ + spi.cpp diff --git a/src/drivers/device/pio.cpp b/src/drivers/device/pio.cpp new file mode 100644 index 000000000..f3a805a5e --- /dev/null +++ b/src/drivers/device/pio.cpp @@ -0,0 +1,74 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 pio.cpp + * + * Base class for devices accessed via PIO to registers. + */ + +#include "device.h" + +namespace device +{ + +PIO::PIO(const char *name, + const char *devname, + uint32_t base, + int irq) : + // base class + CDev(name, devname, irq), + // public + // protected + // private + _base(base) +{ +} + +PIO::~PIO() +{ + // nothing to do here... +} + +int +PIO::init() +{ + int ret = OK; + + // base class init first + ret = CDev::init(); + + return ret; +} + +} // namespace device
\ No newline at end of file diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp new file mode 100644 index 000000000..8fffd60cb --- /dev/null +++ b/src/drivers/device/spi.cpp @@ -0,0 +1,160 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 spi.cpp + * + * Base class for devices connected via SPI. + * + * @todo Work out if caching the mode/frequency would save any time. + * + * @todo A separate bus/device abstraction would allow for mixed interrupt-mode + * and non-interrupt-mode clients to arbitrate for the bus. As things stand, + * a bus shared between clients of both kinds is vulnerable to races between + * the two, where an interrupt-mode client will ignore the lock held by the + * non-interrupt-mode client. + */ + +#include <nuttx/arch.h> + +#include "spi.h" + +#ifndef CONFIG_SPI_EXCHANGE +# error This driver requires CONFIG_SPI_EXCHANGE +#endif + +namespace device +{ + +SPI::SPI(const char *name, + const char *devname, + int bus, + enum spi_dev_e device, + enum spi_mode_e mode, + uint32_t frequency, + int irq) : + // base class + CDev(name, devname, irq), + // public + // protected + // private + _bus(bus), + _device(device), + _mode(mode), + _frequency(frequency), + _dev(nullptr) +{ +} + +SPI::~SPI() +{ + // XXX no way to let go of the bus... +} + +int +SPI::init() +{ + int ret = OK; + + /* attach to the spi bus */ + if (_dev == nullptr) + _dev = up_spiinitialize(_bus); + + if (_dev == nullptr) { + debug("failed to init SPI"); + ret = -ENOENT; + goto out; + } + + /* deselect device to ensure high to low transition of pin select */ + SPI_SELECT(_dev, _device, false); + + /* call the probe function to check whether the device is present */ + ret = probe(); + + if (ret != OK) { + debug("probe failed"); + goto out; + } + + /* do base class init, which will create the device node, etc. */ + ret = CDev::init(); + + if (ret != OK) { + debug("cdev init failed"); + goto out; + } + + /* tell the workd where we are */ + log("on SPI bus %d at %d", _bus, _device); + +out: + return ret; +} + +int +SPI::probe() +{ + // assume the device is too stupid to be discoverable + return OK; +} + +int +SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len) +{ + + if ((send == nullptr) && (recv == nullptr)) + return -EINVAL; + + /* do common setup */ + if (!up_interrupt_context()) + SPI_LOCK(_dev, true); + + SPI_SETFREQUENCY(_dev, _frequency); + SPI_SETMODE(_dev, _mode); + SPI_SETBITS(_dev, 8); + SPI_SELECT(_dev, _device, true); + + /* do the transfer */ + SPI_EXCHANGE(_dev, send, recv, len); + + /* and clean up */ + SPI_SELECT(_dev, _device, false); + + if (!up_interrupt_context()) + SPI_LOCK(_dev, false); + + return OK; +} + +} // namespace device diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h new file mode 100644 index 000000000..d2d01efb3 --- /dev/null +++ b/src/drivers/device/spi.h @@ -0,0 +1,114 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 spi.h + * + * Base class for devices connected via SPI. + */ + +#ifndef _DEVICE_SPI_H +#define _DEVICE_SPI_H + +#include "device.h" + +#include <nuttx/spi.h> + +namespace device __EXPORT +{ + +/** + * Abstract class for character device on SPI + */ +class __EXPORT SPI : public CDev +{ +protected: + /** + * Constructor + * + * @param name Driver name + * @param devname Device node name + * @param bus SPI bus on which the device lives + * @param device Device handle (used by SPI_SELECT) + * @param mode SPI clock/data mode + * @param frequency SPI clock frequency + * @param irq Interrupt assigned to the device (or zero if none) + */ + SPI(const char *name, + const char *devname, + int bus, + enum spi_dev_e device, + enum spi_mode_e mode, + uint32_t frequency, + int irq = 0); + ~SPI(); + + virtual int init(); + + /** + * Check for the presence of the device on the bus. + */ + virtual int probe(); + + /** + * Perform a SPI transfer. + * + * If called from interrupt context, this interface does not lock + * the bus and may interfere with non-interrupt-context callers. + * + * Clients in a mixed interrupt/non-interrupt configuration must + * ensure appropriate interlocking. + * + * At least one of send or recv must be non-null. + * + * @param send Bytes to send to the device, or nullptr if + * no data is to be sent. + * @param recv Buffer for receiving bytes from the device, + * or nullptr if no bytes are to be received. + * @param len Number of bytes to transfer. + * @return OK if the exchange was successful, -errno + * otherwise. + */ + int transfer(uint8_t *send, uint8_t *recv, unsigned len); + +private: + int _bus; + enum spi_dev_e _device; + enum spi_mode_e _mode; + uint32_t _frequency; + struct spi_dev_s *_dev; +}; + +} // namespace device + +#endif /* _DEVICE_SPI_H */ diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h new file mode 100644 index 000000000..794de584b --- /dev/null +++ b/src/drivers/drv_accel.h @@ -0,0 +1,121 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 Accelerometer driver interface. + */ + +#ifndef _DRV_ACCEL_H +#define _DRV_ACCEL_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define ACCEL_DEVICE_PATH "/dev/accel" + +/** + * accel report structure. Reads from the device must be in multiples of this + * structure. + */ +struct accel_report { + uint64_t timestamp; + float x; /**< acceleration in the NED X board axis in m/s^2 */ + float y; /**< acceleration in the NED Y board axis in m/s^2 */ + float z; /**< acceleration in the NED Z board axis in m/s^2 */ + float temperature; /**< temperature in degrees celsius */ + float range_m_s2; /**< range in m/s^2 (+- this value) */ + float scaling; + + int16_t x_raw; + int16_t y_raw; + int16_t z_raw; + int16_t temperature_raw; +}; + +/** accel scaling factors; Vout = (Vin * Vscale) + Voffset */ +struct accel_scale { + float x_offset; + float x_scale; + float y_offset; + float y_scale; + float z_offset; + float z_scale; +}; + +/* + * ObjDev tag for raw accelerometer data. + */ +ORB_DECLARE(sensor_accel); + +/* + * ioctl() definitions + * + * Accelerometer drivers also implement the generic sensor driver + * interfaces from drv_sensor.h + */ + +#define _ACCELIOCBASE (0x2100) +#define _ACCELIOC(_n) (_IOC(_ACCELIOCBASE, _n)) + + +/** set the accel internal sample rate to at least (arg) Hz */ +#define ACCELIOCSSAMPLERATE _ACCELIOC(0) + +/** return the accel internal sample rate in Hz */ +#define ACCELIOCGSAMPLERATE _ACCELIOC(1) + +/** set the accel internal lowpass filter to no lower than (arg) Hz */ +#define ACCELIOCSLOWPASS _ACCELIOC(2) + +/** return the accel internal lowpass filter in Hz */ +#define ACCELIOCGLOWPASS _ACCELIOC(3) + +/** set the accel scaling constants to the structure pointed to by (arg) */ +#define ACCELIOCSSCALE _ACCELIOC(5) + +/** get the accel scaling constants into the structure pointed to by (arg) */ +#define ACCELIOCGSCALE _ACCELIOC(6) + +/** set the accel measurement range to handle at least (arg) g */ +#define ACCELIOCSRANGE _ACCELIOC(7) + +/** get the current accel measurement range in g */ +#define ACCELIOCGRANGE _ACCELIOC(8) + +/** get the result of a sensor self-test */ +#define ACCELIOCSELFTEST _ACCELIOC(9) + +#endif /* _DRV_ACCEL_H */ diff --git a/src/drivers/drv_adc.h b/src/drivers/drv_adc.h new file mode 100644 index 000000000..8ec6d1233 --- /dev/null +++ b/src/drivers/drv_adc.h @@ -0,0 +1,52 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 drv_adc.h + * + * ADC driver interface. + * + * This defines additional operations over and above the standard NuttX + * ADC API. + */ + +#pragma once + +#include <stdint.h> +#include <sys/ioctl.h> + +#define ADC_DEVICE_PATH "/dev/adc0" + +/* + * ioctl definitions + */ diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h new file mode 100644 index 000000000..176f798c0 --- /dev/null +++ b/src/drivers/drv_baro.h @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 Barometric pressure sensor driver interface. + */ + +#ifndef _DRV_BARO_H +#define _DRV_BARO_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define BARO_DEVICE_PATH "/dev/baro" + +/** + * baro report structure. Reads from the device must be in multiples of this + * structure. + */ +struct baro_report { + float pressure; + float altitude; + float temperature; + uint64_t timestamp; +}; + +/* + * ObjDev tag for raw barometer data. + */ +ORB_DECLARE(sensor_baro); + +/* + * ioctl() definitions + */ + +#define _BAROIOCBASE (0x2200) +#define _BAROIOC(_n) (_IOC(_BAROIOCBASE, _n)) + +/** set corrected MSL pressure in pascals */ +#define BAROIOCSMSLPRESSURE _BAROIOC(0) + +/** get current MSL pressure in pascals */ +#define BAROIOCGMSLPRESSURE _BAROIOC(1) + +#endif /* _DRV_BARO_H */ diff --git a/src/drivers/drv_blinkm.h b/src/drivers/drv_blinkm.h new file mode 100644 index 000000000..9c278f6c5 --- /dev/null +++ b/src/drivers/drv_blinkm.h @@ -0,0 +1,69 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 drv_blinkm.h + * + * BlinkM driver API + * + * This could probably become a more generalised API for multi-colour LED + * driver systems, or be merged with the generic LED driver. + */ + +#pragma once + +#include <stdint.h> +#include <sys/ioctl.h> + +#define BLINKM_DEVICE_PATH "/dev/blinkm" + +/* + * ioctl() definitions + */ + +#define _BLINKMIOCBASE (0x2900) +#define _BLINKMIOC(_n) (_IOC(_BLINKMIOCBASE, _n)) + +/** play the named script in *(char *)arg, repeating forever */ +#define BLINKM_PLAY_SCRIPT_NAMED _BLINKMIOC(1) + +/** play the numbered script in (arg), repeating forever */ +#define BLINKM_PLAY_SCRIPT _BLINKMIOC(2) + +/** + * Set the user script; (arg) is a pointer to an array of script lines, + * where each line is an array of four bytes giving <duration>, <command>, arg[0-2] + * + * The script is terminated by a zero command. + */ +#define BLINKM_SET_USER_SCRIPT _BLINKMIOC(3) diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h new file mode 100644 index 000000000..92d184326 --- /dev/null +++ b/src/drivers/drv_gpio.h @@ -0,0 +1,148 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 drv_gpio.h + * + * Generic GPIO ioctl interface. + */ + +#ifndef _DRV_GPIO_H +#define _DRV_GPIO_H + +#include <sys/ioctl.h> + +#ifdef CONFIG_ARCH_BOARD_PX4FMU +/* + * PX4FMU GPIO numbers. + * + * For shared pins, alternate function 1 selects the non-GPIO mode + * (USART2, CAN2, etc.) + */ +# define GPIO_EXT_1 (1<<0) /**< high-power GPIO 1 */ +# define GPIO_EXT_2 (1<<1) /**< high-power GPIO 1 */ +# define GPIO_MULTI_1 (1<<2) /**< USART2 CTS */ +# define GPIO_MULTI_2 (1<<3) /**< USART2 RTS */ +# define GPIO_MULTI_3 (1<<4) /**< USART2 TX */ +# define GPIO_MULTI_4 (1<<5) /**< USART2 RX */ +# define GPIO_CAN_TX (1<<6) /**< CAN2 TX */ +# define GPIO_CAN_RX (1<<7) /**< CAN2 RX */ + +/** + * Default GPIO device - other devices may also support this protocol if + * they also export GPIO-like things. This is always the GPIOs on the + * main board. + */ +# define GPIO_DEVICE_PATH "/dev/px4fmu" + +#endif + +#ifdef CONFIG_ARCH_BOARD_PX4IO +/* + * PX4IO GPIO numbers. + * + * XXX note that these are here for reference/future use; currently + * there is no good way to wire these up without a common STM32 GPIO + * driver, which isn't implemented yet. + */ +/* outputs */ +# define GPIO_ACC1_POWER (1<<0) /**< accessory power 1 */ +# define GPIO_ACC2_POWER (1<<1) /**< accessory power 2 */ +# define GPIO_SERVO_POWER (1<<2) /**< servo power */ +# define GPIO_RELAY1 (1<<3) /**< relay 1 */ +# define GPIO_RELAY2 (1<<4) /**< relay 2 */ +# define GPIO_LED_BLUE (1<<5) /**< blue LED */ +# define GPIO_LED_AMBER (1<<6) /**< amber/red LED */ +# define GPIO_LED_SAFETY (1<<7) /**< safety LED */ + +/* inputs */ +# define GPIO_ACC_OVERCURRENT (1<<8) /**< accessory 1/2 overcurrent detect */ +# define GPIO_SERVO_OVERCURRENT (1<<9) /**< servo overcurrent detect */ +# define GPIO_SAFETY_BUTTON (1<<10) /**< safety button pressed */ + +/** + * Default GPIO device - other devices may also support this protocol if + * they also export GPIO-like things. This is always the GPIOs on the + * main board. + */ +# define GPIO_DEVICE_PATH "/dev/px4io" + +#endif + +#ifndef GPIO_DEVICE_PATH +# error No GPIO support for this board. +#endif + +/* + * IOCTL definitions. + * + * For all ioctls, the (arg) argument is a bitmask of GPIOs to be affected + * by the operation, with the LSB being the lowest-numbered GPIO. + * + * Note that there may be board-specific relationships between GPIOs; + * applications using GPIOs should be aware of this. + */ +#define _GPIOCBASE 0x2700 +#define GPIOC(_x) _IOC(_GPIOCBASE, _x) + +/** reset all board GPIOs to their default state */ +#define GPIO_RESET GPIOC(0) + +/** configure the board GPIOs in (arg) as outputs */ +#define GPIO_SET_OUTPUT GPIOC(1) + +/** configure the board GPIOs in (arg) as inputs */ +#define GPIO_SET_INPUT GPIOC(2) + +/** configure the board GPIOs in (arg) for the first alternate function (if supported) */ +#define GPIO_SET_ALT_1 GPIOC(3) + +/** configure the board GPIO (arg) for the second alternate function (if supported) */ +#define GPIO_SET_ALT_2 GPIOC(4) + +/** configure the board GPIO (arg) for the third alternate function (if supported) */ +#define GPIO_SET_ALT_3 GPIOC(5) + +/** configure the board GPIO (arg) for the fourth alternate function (if supported) */ +#define GPIO_SET_ALT_4 GPIOC(6) + +/** set the GPIOs in (arg) */ +#define GPIO_SET GPIOC(10) + +/** clear the GPIOs in (arg) */ +#define GPIO_CLEAR GPIOC(11) + +/** read all the GPIOs and return their values in *(uint32_t *)arg */ +#define GPIO_GET GPIOC(12) + +#endif /* _DRV_GPIO_H */
\ No newline at end of file diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h new file mode 100644 index 000000000..1dda8ef0b --- /dev/null +++ b/src/drivers/drv_gps.h @@ -0,0 +1,70 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 GPS driver interface. + */ + +#ifndef _DRV_GPS_H +#define _DRV_GPS_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define GPS_DEFAULT_UART_PORT "/dev/ttyS3" + +#define GPS_DEVICE_PATH "/dev/gps" + +typedef enum { + GPS_DRIVER_MODE_NONE = 0, + GPS_DRIVER_MODE_UBX, + GPS_DRIVER_MODE_MTK, + GPS_DRIVER_MODE_NMEA, +} gps_driver_mode_t; + + +/* + * ObjDev tag for GPS data. + */ +ORB_DECLARE(gps); + +/* + * ioctl() definitions + */ +#define _GPSIOCBASE (0x2800) //TODO: arbitrary choice... +#define _GPSIOC(_n) (_IOC(_GPSIOCBASE, _n)) + +#endif /* _DRV_GPS_H */ diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h new file mode 100644 index 000000000..1d0fef6fc --- /dev/null +++ b/src/drivers/drv_gyro.h @@ -0,0 +1,117 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 Gyroscope driver interface. + */ + +#ifndef _DRV_GYRO_H +#define _DRV_GYRO_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define GYRO_DEVICE_PATH "/dev/gyro" + +/** + * gyro report structure. Reads from the device must be in multiples of this + * structure. + */ +struct gyro_report { + uint64_t timestamp; + float x; /**< angular velocity in the NED X board axis in rad/s */ + float y; /**< angular velocity in the NED Y board axis in rad/s */ + float z; /**< angular velocity in the NED Z board axis in rad/s */ + float temperature; /**< temperature in degrees celcius */ + float range_rad_s; + float scaling; + + int16_t x_raw; + int16_t y_raw; + int16_t z_raw; + int16_t temperature_raw; +}; + +/** gyro scaling factors; Vout = (Vin * Vscale) + Voffset */ +struct gyro_scale { + float x_offset; + float x_scale; + float y_offset; + float y_scale; + float z_offset; + float z_scale; +}; + +/* + * ObjDev tag for raw gyro data. + */ +ORB_DECLARE(sensor_gyro); + +/* + * ioctl() definitions + */ + +#define _GYROIOCBASE (0x2300) +#define _GYROIOC(_n) (_IOC(_GYROIOCBASE, _n)) + +/** set the gyro internal sample rate to at least (arg) Hz */ +#define GYROIOCSSAMPLERATE _GYROIOC(0) + +/** return the gyro internal sample rate in Hz */ +#define GYROIOCGSAMPLERATE _GYROIOC(1) + +/** set the gyro internal lowpass filter to no lower than (arg) Hz */ +#define GYROIOCSLOWPASS _GYROIOC(2) + +/** set the gyro internal lowpass filter to no lower than (arg) Hz */ +#define GYROIOCGLOWPASS _GYROIOC(3) + +/** set the gyro scaling constants to (arg) */ +#define GYROIOCSSCALE _GYROIOC(4) + +/** get the gyro scaling constants into (arg) */ +#define GYROIOCGSCALE _GYROIOC(5) + +/** set the gyro measurement range to handle at least (arg) degrees per second */ +#define GYROIOCSRANGE _GYROIOC(6) + +/** get the current gyro measurement range in degrees per second */ +#define GYROIOCGRANGE _GYROIOC(7) + +/** check the status of the sensor */ +#define GYROIOCSELFTEST _GYROIOC(8) + +#endif /* _DRV_GYRO_H */ diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h new file mode 100644 index 000000000..8a99eeca7 --- /dev/null +++ b/src/drivers/drv_hrt.h @@ -0,0 +1,149 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 drv_hrt.h + * + * High-resolution timer with callouts and timekeeping. + */ + +#pragma once + +#include <sys/types.h> +#include <stdbool.h> + +#include <time.h> +#include <queue.h> + +__BEGIN_DECLS + +/* + * Absolute time, in microsecond units. + * + * Absolute time is measured from some arbitrary epoch shortly after + * system startup. It should never wrap or go backwards. + */ +typedef uint64_t hrt_abstime; + +/* + * Callout function type. + * + * Note that callouts run in the timer interrupt context, so + * they are serialised with respect to each other, and must not + * block. + */ +typedef void (* hrt_callout)(void *arg); + +/* + * Callout record. + */ +typedef struct hrt_call { + struct sq_entry_s link; + + hrt_abstime deadline; + hrt_abstime period; + hrt_callout callout; + void *arg; +} *hrt_call_t; + +/* + * Get absolute time. + */ +__EXPORT extern hrt_abstime hrt_absolute_time(void); + +/* + * Convert a timespec to absolute time. + */ +__EXPORT extern hrt_abstime ts_to_abstime(struct timespec *ts); + +/* + * Convert absolute time to a timespec. + */ +__EXPORT extern void abstime_to_ts(struct timespec *ts, hrt_abstime abstime); + +/* + * Compute the delta between a timestamp taken in the past + * and now. + * + * This function is safe to use even if the timestamp is updated + * by an interrupt during execution. + */ +__EXPORT extern hrt_abstime hrt_elapsed_time(const volatile hrt_abstime *then); + +/* + * Store the absolute time in an interrupt-safe fashion. + * + * This function ensures that the timestamp cannot be seen half-written by an interrupt handler. + */ +__EXPORT extern hrt_abstime hrt_store_absolute_time(volatile hrt_abstime *now); + +/* + * Call callout(arg) after delay has elapsed. + * + * If callout is NULL, this can be used to implement a timeout by testing the call + * with hrt_called(). + */ +__EXPORT extern void hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg); + +/* + * Call callout(arg) at absolute time calltime. + */ +__EXPORT extern void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg); + +/* + * Call callout(arg) after delay, and then after every interval. + * + * Note thet the interval is timed between scheduled, not actual, call times, so the call rate may + * jitter but should not drift. + */ +__EXPORT extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg); + +/* + * If this returns true, the entry has been invoked and removed from the callout list, + * or it has never been entered. + * + * Always returns false for repeating callouts. + */ +__EXPORT extern bool hrt_called(struct hrt_call *entry); + +/* + * Remove the entry from the callout list. + */ +__EXPORT extern void hrt_cancel(struct hrt_call *entry); + +/* + * Initialise the HRT. + */ +__EXPORT extern void hrt_init(void); + +__END_DECLS diff --git a/src/drivers/drv_led.h b/src/drivers/drv_led.h new file mode 100644 index 000000000..21044f620 --- /dev/null +++ b/src/drivers/drv_led.h @@ -0,0 +1,65 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 drv_led.h + * + * LED driver API + */ + +#pragma once + +#include <stdint.h> +#include <sys/ioctl.h> + +#define LED_DEVICE_PATH "/dev/led" + +#define _LED_BASE 0x2800 + +/* PX4 LED colour codes */ +#define LED_AMBER 1 +#define LED_RED 1 /* some boards have red rather than amber */ +#define LED_BLUE 0 +#define LED_SAFETY 2 + +#define LED_ON _IOC(_LED_BASE, 0) +#define LED_OFF _IOC(_LED_BASE, 1) + +__BEGIN_DECLS + +/* + * Initialise the LED driver. + */ +__EXPORT extern void drv_led_start(void); + +__END_DECLS diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h new file mode 100644 index 000000000..9aab995a1 --- /dev/null +++ b/src/drivers/drv_mag.h @@ -0,0 +1,114 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 Magnetometer driver interface. + */ + +#ifndef _DRV_MAG_H +#define _DRV_MAG_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define MAG_DEVICE_PATH "/dev/mag" + +/** + * mag report structure. Reads from the device must be in multiples of this + * structure. + * + * Output values are in gauss. + */ +struct mag_report { + uint64_t timestamp; + float x; + float y; + float z; + float range_ga; + float scaling; + + int16_t x_raw; + int16_t y_raw; + int16_t z_raw; +}; + +/** mag scaling factors; Vout = (Vin * Vscale) + Voffset */ +struct mag_scale { + float x_offset; + float x_scale; + float y_offset; + float y_scale; + float z_offset; + float z_scale; +}; + +/* + * ObjDev tag for raw magnetometer data. + */ +ORB_DECLARE(sensor_mag); + +/* + * ioctl() definitions + */ + +#define _MAGIOCBASE (0x2400) +#define _MAGIOC(_n) (_IOC(_MAGIOCBASE, _n)) + +/** set the mag internal sample rate to at least (arg) Hz */ +#define MAGIOCSSAMPLERATE _MAGIOC(0) + +/** set the mag internal lowpass filter to no lower than (arg) Hz */ +#define MAGIOCSLOWPASS _MAGIOC(1) + +/** set the mag scaling constants to the structure pointed to by (arg) */ +#define MAGIOCSSCALE _MAGIOC(2) + +/** copy the mag scaling constants to the structure pointed to by (arg) */ +#define MAGIOCGSCALE _MAGIOC(3) + +/** set the measurement range to handle (at least) arg Gauss */ +#define MAGIOCSRANGE _MAGIOC(4) + +/** perform self-calibration, update scale factors to canonical units */ +#define MAGIOCCALIBRATE _MAGIOC(5) + +/** excite strap */ +#define MAGIOCEXSTRAP _MAGIOC(6) + +/** perform self test and report status */ +#define MAGIOCSELFTEST _MAGIOC(7) + +#endif /* _DRV_MAG_H */ diff --git a/src/drivers/drv_mixer.h b/src/drivers/drv_mixer.h new file mode 100644 index 000000000..9f43015d9 --- /dev/null +++ b/src/drivers/drv_mixer.h @@ -0,0 +1,118 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 drv_mixer.h + * + * Mixer ioctl interfaces. + * + * Normal workflow is: + * + * - open mixer device + * - add mixer(s) + * loop: + * - mix actuators to array + * + * Each client has its own configuration. + * + * When mixing, outputs are produced by mixers in the order they are + * added. A simple mixer produces one output; a multotor mixer will + * produce several outputs, etc. + */ + +#ifndef _DRV_MIXER_H +#define _DRV_MIXER_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#define MIXER_DEVICE_PATH "/dev/mixer" + +/* + * ioctl() definitions + */ +#define _MIXERIOCBASE (0x2500) +#define _MIXERIOC(_n) (_IOC(_MIXERIOCBASE, _n)) + +/** get the number of mixable outputs */ +#define MIXERIOCGETOUTPUTCOUNT _MIXERIOC(0) + +/** reset (clear) the mixer configuration */ +#define MIXERIOCRESET _MIXERIOC(1) + +/** simple channel scaler */ +struct mixer_scaler_s { + float negative_scale; + float positive_scale; + float offset; + float min_output; + float max_output; +}; + +/** mixer input */ +struct mixer_control_s { + uint8_t control_group; /**< group from which the input reads */ + uint8_t control_index; /**< index within the control group */ + struct mixer_scaler_s scaler; /**< scaling applied to the input before use */ +}; + +/** simple mixer */ +struct mixer_simple_s { + uint8_t control_count; /**< number of inputs */ + struct mixer_scaler_s output_scaler; /**< scaling for the output */ + struct mixer_control_s controls[0]; /**< actual size of the array is set by control_count */ +}; + +#define MIXER_SIMPLE_SIZE(_icount) (sizeof(struct mixer_simple_s) + (_icount) * sizeof(struct mixer_control_s)) + +/** + * add a simple mixer in (struct mixer_simple_s *)arg + */ +#define MIXERIOCADDSIMPLE _MIXERIOC(2) + +/* _MIXERIOC(3) was deprecated */ +/* _MIXERIOC(4) was deprecated */ + +/** + * Add mixer(s) from the buffer in (const char *)arg + */ +#define MIXERIOCLOADBUF _MIXERIOC(5) + +/* + * XXX Thoughts for additional operations: + * + * - get/set output scale, for tuning center/limit values. + * - save/serialise for saving tuned mixers. + */ + +#endif /* _DRV_ACCEL_H */ diff --git a/src/drivers/drv_orb_dev.h b/src/drivers/drv_orb_dev.h new file mode 100644 index 000000000..713618545 --- /dev/null +++ b/src/drivers/drv_orb_dev.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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. + * + ****************************************************************************/ + +#ifndef _DRV_UORB_H +#define _DRV_UORB_H + +/** + * @file uORB published object driver. + */ + +#include <sys/types.h> +#include <sys/ioctl.h> +#include <stdint.h> + +/* XXX for ORB_DECLARE used in many drivers */ +#include "../modules/uORB/uORB.h" + +/* + * ioctl() definitions + */ + +/** path to the uORB control device for pub/sub topics */ +#define TOPIC_MASTER_DEVICE_PATH "/obj/_obj_" + +/** path to the uORB control device for parameter topics */ +#define PARAM_MASTER_DEVICE_PATH "/param/_param_" + +/** maximum ogbject name length */ +#define ORB_MAXNAME 32 + +#define _ORBIOCBASE (0x2600) +#define _ORBIOC(_n) (_IOC(_ORBIOCBASE, _n)) + +/* + * IOCTLs for the uORB control device + */ + +/** Advertise a new topic described by *(uorb_metadata *)arg */ +#define ORBIOCADVERTISE _ORBIOC(0) + +/* + * IOCTLs for individual topics. + */ + +/** Fetch the time at which the topic was last updated into *(uint64_t *)arg */ +#define ORBIOCLASTUPDATE _ORBIOC(10) + +/** Check whether the topic has been updated since it was last read, sets *(bool *)arg */ +#define ORBIOCUPDATED _ORBIOC(11) + +/** Set the minimum interval at which the topic can be seen to be updated for this subscription */ +#define ORBIOCSETINTERVAL _ORBIOC(12) + +/** Get the global advertiser handle for the topic */ +#define ORBIOCGADVERTISER _ORBIOC(13) + +#endif /* _DRV_UORB_H */ diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h new file mode 100644 index 000000000..07831f20c --- /dev/null +++ b/src/drivers/drv_pwm_output.h @@ -0,0 +1,201 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 PWM servo output interface. + * + * Servo values can be set with the PWM_SERVO_SET ioctl, by writing a + * pwm_output_values structure to the device, or by publishing to the + * output_pwm ORB topic. + * Writing a value of 0 to a channel suppresses any output for that + * channel. + */ + +#pragma once + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_orb_dev.h" + +__BEGIN_DECLS + +/** + * Path for the default PWM output device. + * + * Note that on systems with more than one PWM output path (e.g. + * PX4FMU with PX4IO connected) there may be other devices that + * respond to this protocol. + */ +#define PWM_OUTPUT_DEVICE_PATH "/dev/pwm_output" + +/** + * Maximum number of PWM output channels supported by the device. + */ +#define PWM_OUTPUT_MAX_CHANNELS 16 + +/** + * Servo output signal type, value is actual servo output pulse + * width in microseconds. + */ +typedef uint16_t servo_position_t; + +/** + * Servo output status structure. + * + * May be published to output_pwm, or written to a PWM output + * device. + */ +struct pwm_output_values { + /** desired pulse widths for each of the supported channels */ + servo_position_t values[PWM_OUTPUT_MAX_CHANNELS]; +}; + +/* + * ORB tag for PWM outputs. + */ +ORB_DECLARE(output_pwm); + +/* + * ioctl() definitions + * + * Note that ioctls and ORB updates should not be mixed, as the + * behaviour of the system in this case is not defined. + */ +#define _PWM_SERVO_BASE 0x2a00 + +/** arm all servo outputs handle by this driver */ +#define PWM_SERVO_ARM _IOC(_PWM_SERVO_BASE, 0) + +/** disarm all servo outputs (stop generating pulses) */ +#define PWM_SERVO_DISARM _IOC(_PWM_SERVO_BASE, 1) + +/** set alternate servo update rate */ +#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2) + +/** get the number of servos in *(unsigned *)arg */ +#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 3) + +/** selects servo update rates, one bit per servo. 0 = default (50Hz), 1 = alternate */ +#define PWM_SERVO_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4) + +/** set a single servo to a specific value */ +#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo) + +/** get a single specific servo value */ +#define PWM_SERVO_GET(_servo) _IOC(_PWM_SERVO_BASE, 0x40 + _servo) + +/** get the _n'th rate group's channels; *(uint32_t *)arg returns a bitmap of channels + * whose update rates must be the same. + */ +#define PWM_SERVO_GET_RATEGROUP(_n) _IOC(_PWM_SERVO_BASE, 0x60 + _n) + +/* + * Low-level PWM output interface. + * + * This is the low-level API to the platform-specific PWM driver. + */ + +/** + * Intialise the PWM servo outputs using the specified configuration. + * + * @param channel_mask Bitmask of channels (LSB = channel 0) to enable. + * This allows some of the channels to remain configured + * as GPIOs or as another function. + * @return OK on success. + */ +__EXPORT extern int up_pwm_servo_init(uint32_t channel_mask); + +/** + * De-initialise the PWM servo outputs. + */ +__EXPORT extern void up_pwm_servo_deinit(void); + +/** + * Arm or disarm servo outputs. + * + * When disarmed, servos output no pulse. + * + * @bug This function should, but does not, guarantee that any pulse + * currently in progress is cleanly completed. + * + * @param armed If true, outputs are armed; if false they + * are disarmed. + */ +__EXPORT extern void up_pwm_servo_arm(bool armed); + +/** + * Set the servo update rate for all rate groups. + * + * @param rate The update rate in Hz to set. + * @return OK on success, -ERANGE if an unsupported update rate is set. + */ +__EXPORT extern int up_pwm_servo_set_rate(unsigned rate); + +/** + * Get a bitmap of output channels assigned to a given rate group. + * + * @param group The rate group to query. Rate groups are assigned contiguously + * starting from zero. + * @return A bitmap of channels assigned to the rate group, or zero if + * the group number has no channels. + */ +__EXPORT extern uint32_t up_pwm_servo_get_rate_group(unsigned group); + +/** + * Set the update rate for a given rate group. + * + * @param group The rate group whose update rate will be changed. + * @param rate The update rate in Hz. + * @return OK if the group was adjusted, -ERANGE if an unsupported update rate is set. + */ +__EXPORT extern int up_pwm_servo_set_rate_group_update(unsigned group, unsigned rate); + +/** + * Set the current output value for a channel. + * + * @param channel The channel to set. + * @param value The output pulse width in microseconds. + */ +__EXPORT extern int up_pwm_servo_set(unsigned channel, servo_position_t value); + +/** + * Get the current output value for a channel. + * + * @param channel The channel to read. + * @return The output pulse width in microseconds, or zero if + * outputs are not armed or not configured. + */ +__EXPORT extern servo_position_t up_pwm_servo_get(unsigned channel); + +__END_DECLS diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h new file mode 100644 index 000000000..03a82ec5d --- /dev/null +++ b/src/drivers/drv_range_finder.h @@ -0,0 +1,81 @@ +/**************************************************************************** + * + * Copyright (C) 2013 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 Rangefinder driver interface. + */ + +#ifndef _DRV_RANGEFINDER_H +#define _DRV_RANGEFINDER_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define RANGE_FINDER_DEVICE_PATH "/dev/range_finder" + +/** + * range finder report structure. Reads from the device must be in multiples of this + * structure. + */ +struct range_finder_report { + uint64_t timestamp; + float distance; /** in meters */ + uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */ +}; + +/* + * ObjDev tag for raw range finder data. + */ +ORB_DECLARE(sensor_range_finder); + +/* + * ioctl() definitions + * + * Rangefinder drivers also implement the generic sensor driver + * interfaces from drv_sensor.h + */ + +#define _RANGEFINDERIOCBASE (0x7900) +#define __RANGEFINDERIOC(_n) (_IOC(_RANGEFINDERIOCBASE, _n)) + +/** set the minimum effective distance of the device */ +#define RANGEFINDERIOCSETMINIUMDISTANCE __RANGEFINDERIOC(1) + +/** set the maximum effective distance of the device */ +#define RANGEFINDERIOCSETMAXIUMDISTANCE __RANGEFINDERIOC(2) + + +#endif /* _DRV_RANGEFINDER_H */ diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h new file mode 100644 index 000000000..4decc324e --- /dev/null +++ b/src/drivers/drv_rc_input.h @@ -0,0 +1,110 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 R/C input interface. + * + */ + +#ifndef _DRV_RC_INPUT_H +#define _DRV_RC_INPUT_H + +#include <stdint.h> +#include <sys/ioctl.h> + +#include "drv_orb_dev.h" + +/** + * Path for the default R/C input device. + * + * Note that on systems with more than one R/C input path (e.g. + * PX4FMU with PX4IO connected) there may be other devices that + * respond to this protocol. + * + * Input data may be obtained by subscribing to the input_rc + * object, or by poll/reading from the device. + */ +#define RC_INPUT_DEVICE_PATH "/dev/input_rc" + +/** + * Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. + */ +#define RC_INPUT_MAX_CHANNELS 18 + +/** + * Input signal type, value is a control position from zero to 100 + * percent. + */ +typedef uint16_t rc_input_t; + +enum RC_INPUT_SOURCE { + RC_INPUT_SOURCE_UNKNOWN = 0, + RC_INPUT_SOURCE_PX4FMU_PPM, + RC_INPUT_SOURCE_PX4IO_PPM, + RC_INPUT_SOURCE_PX4IO_SPEKTRUM, + RC_INPUT_SOURCE_PX4IO_SBUS +}; + +/** + * R/C input status structure. + * + * Published to input_rc, may also be published to other names depending + * on the board involved. + */ +struct rc_input_values { + /** decoding time */ + uint64_t timestamp; + + /** number of channels actually being seen */ + uint32_t channel_count; + + /** Input source */ + enum RC_INPUT_SOURCE input_source; + + /** measured pulse widths for each of the supported channels */ + rc_input_t values[RC_INPUT_MAX_CHANNELS]; +}; + +/* + * ObjDev tag for R/C inputs. + */ +ORB_DECLARE(input_rc); + +#define _RC_INPUT_BASE 0x2b00 + +/** Fetch R/C input values into (rc_input_values *)arg */ + +#define RC_INPUT_GET _IOC(_RC_INPUT_BASE, 0) + + +#endif /* _DRV_RC_INPUT_H */ diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h new file mode 100644 index 000000000..3a89cab9d --- /dev/null +++ b/src/drivers/drv_sensor.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 Common sensor API and ioctl definitions. + */ + +#ifndef _DRV_SENSOR_H +#define _DRV_SENSOR_H + +#include <stdint.h> +#include <sys/ioctl.h> + +/* + * ioctl() definitions + * + * Note that a driver may not implement all of these operations, but + * if the operation is implemented it should conform to this API. + */ + +#define _SENSORIOCBASE (0x2000) +#define _SENSORIOC(_n) (_IOC(_SENSORIOCBASE, _n)) + +/** + * Set the driver polling rate to (arg) Hz, or one of the SENSOR_POLLRATE + * constants + */ +#define SENSORIOCSPOLLRATE _SENSORIOC(0) + +/** + * Return the driver's approximate polling rate in Hz, or one of the + * SENSOR_POLLRATE values. + */ +#define SENSORIOCGPOLLRATE _SENSORIOC(1) + +#define SENSOR_POLLRATE_MANUAL 1000000 /**< poll when read */ +#define SENSOR_POLLRATE_EXTERNAL 1000001 /**< poll when device signals ready */ +#define SENSOR_POLLRATE_MAX 1000002 /**< poll at device maximum rate */ +#define SENSOR_POLLRATE_DEFAULT 1000003 /**< poll at driver normal rate */ + +/** + * Set the internal queue depth to (arg) entries, must be at least 1 + * + * This sets the upper bound on the number of readings that can be + * read from the driver. + */ +#define SENSORIOCSQUEUEDEPTH _SENSORIOC(2) + +/** return the internal queue depth */ +#define SENSORIOCGQUEUEDEPTH _SENSORIOC(3) + +/** + * Reset the sensor to its default configuration. + */ +#define SENSORIOCRESET _SENSORIOC(4) + +#endif /* _DRV_SENSOR_H */
\ No newline at end of file diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h new file mode 100644 index 000000000..0c6afc64c --- /dev/null +++ b/src/drivers/drv_tone_alarm.h @@ -0,0 +1,128 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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. + * + ****************************************************************************/ + +/* + * Driver for the PX4 audio alarm port, /dev/tone_alarm. + * + * The tone_alarm driver supports a set of predefined "alarm" + * patterns and one user-supplied pattern. Patterns are ordered by + * priority, with a higher-priority pattern interrupting any + * lower-priority pattern that might be playing. + * + * The TONE_SET_ALARM ioctl can be used to select a predefined + * alarm pattern, from 1 - <TBD>. Selecting pattern zero silences + * the alarm. + * + * To supply a custom pattern, write an array of 1 - <TBD> tone_note + * structures to /dev/tone_alarm. The custom pattern has a priority + * of zero. + * + * Patterns will normally play once and then silence (if a pattern + * was overridden it will not resume). A pattern may be made to + * repeat by inserting a note with the duration set to + * DURATION_REPEAT. This pattern will loop until either a + * higher-priority pattern is started or pattern zero is requested + * via the ioctl. + */ + +#ifndef DRV_TONE_ALARM_H_ +#define DRV_TONE_ALARM_H_ + +#include <sys/ioctl.h> + +#define _TONE_ALARM_BASE 0x7400 +#define TONE_SET_ALARM _IOC(_TONE_ALARM_BASE, 1) + +/* structure describing one note in a tone pattern */ +struct tone_note { + uint8_t pitch; + uint8_t duration; /* duration in multiples of 10ms */ +#define DURATION_END 0 /* ends the pattern */ +#define DURATION_REPEAT 255 /* resets the note counter to zero */ +}; + +enum tone_pitch { + TONE_NOTE_E4, /* E4 */ + TONE_NOTE_F4, /* F4 */ + TONE_NOTE_F4S, /* F#4/Gb4 */ + TONE_NOTE_G4, /* G4 */ + TONE_NOTE_G4S, /* G#4/Ab4 */ + TONE_NOTE_A4, /* A4 */ + TONE_NOTE_A4S, /* A#4/Bb4 */ + TONE_NOTE_B4, /* B4 */ + TONE_NOTE_C5, /* C5 */ + TONE_NOTE_C5S, /* C#5/Db5 */ + TONE_NOTE_D5, /* D5 */ + TONE_NOTE_D5S, /* D#5/Eb5 */ + TONE_NOTE_E5, /* E5 */ + TONE_NOTE_F5, /* F5 */ + TONE_NOTE_F5S, /* F#5/Gb5 */ + TONE_NOTE_G5, /* G5 */ + TONE_NOTE_G5S, /* G#5/Ab5 */ + TONE_NOTE_A5, /* A5 */ + TONE_NOTE_A5S, /* A#5/Bb5 */ + TONE_NOTE_B5, /* B5 */ + TONE_NOTE_C6, /* C6 */ + TONE_NOTE_C6S, /* C#6/Db6 */ + TONE_NOTE_D6, /* D6 */ + TONE_NOTE_D6S, /* D#6/Eb6 */ + TONE_NOTE_E6, /* E6 */ + TONE_NOTE_F6, /* F6 */ + TONE_NOTE_F6S, /* F#6/Gb6 */ + TONE_NOTE_G6, /* G6 */ + TONE_NOTE_G6S, /* G#6/Ab6 */ + TONE_NOTE_A6, /* A6 */ + TONE_NOTE_A6S, /* A#6/Bb6 */ + TONE_NOTE_B6, /* B6 */ + TONE_NOTE_C7, /* C7 */ + TONE_NOTE_C7S, /* C#7/Db7 */ + TONE_NOTE_D7, /* D7 */ + TONE_NOTE_D7S, /* D#7/Eb7 */ + TONE_NOTE_E7, /* E7 */ + TONE_NOTE_F7, /* F7 */ + TONE_NOTE_F7S, /* F#7/Gb7 */ + TONE_NOTE_G7, /* G7 */ + TONE_NOTE_G7S, /* G#7/Ab7 */ + TONE_NOTE_A7, /* A7 */ + TONE_NOTE_A7S, /* A#7/Bb7 */ + TONE_NOTE_B7, /* B7 */ + TONE_NOTE_C8, /* C8 */ + TONE_NOTE_C8S, /* C#8/Db8 */ + TONE_NOTE_D8, /* D8 */ + TONE_NOTE_D8S, /* D#8/Eb8 */ + + TONE_NOTE_SILENCE, + TONE_NOTE_MAX +}; + +#endif /* DRV_TONE_ALARM_H_ */ diff --git a/src/drivers/led/Makefile b/src/drivers/led/Makefile new file mode 100644 index 000000000..7de188259 --- /dev/null +++ b/src/drivers/led/Makefile @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (C) 2012 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. +# +############################################################################ + +# +# Makefile to build the LED driver. +# + +include $(APPDIR)/mk/app.mk diff --git a/src/drivers/led/led.cpp b/src/drivers/led/led.cpp new file mode 100644 index 000000000..c7c45525e --- /dev/null +++ b/src/drivers/led/led.cpp @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 led.cpp + * + * LED driver. + */ + +#include <nuttx/config.h> +#include <drivers/device/device.h> +#include <drivers/drv_led.h> + +/* Ideally we'd be able to get these from up_internal.h */ +//#include <up_internal.h> +__BEGIN_DECLS +extern void up_ledinit(); +extern void up_ledon(int led); +extern void up_ledoff(int led); +__END_DECLS + +class LED : device::CDev +{ +public: + LED(); + virtual ~LED(); + + virtual int init(); + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); +}; + +LED::LED() : + CDev("led", LED_DEVICE_PATH) +{ + // force immediate init/device registration + init(); +} + +LED::~LED() +{ +} + +int +LED::init() +{ + CDev::init(); + up_ledinit(); + + return 0; +} + +int +LED::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + int result = OK; + + switch (cmd) { + case LED_ON: + up_ledon(arg); + break; + + case LED_OFF: + up_ledoff(arg); + break; + + default: + result = CDev::ioctl(filp, cmd, arg); + } + return result; +} + +namespace +{ +LED *gLED; +} + +void +drv_led_start() +{ + if (gLED == nullptr) { + gLED = new LED; + if (gLED != nullptr) + gLED->init(); + } +}
\ No newline at end of file |