aboutsummaryrefslogtreecommitdiff
path: root/apps/drivers
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
committerpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
commit8a365179eafdf3aea98e60ab9f5882b200d4c759 (patch)
tree4f38d6d4cd80bd0b6e22e2bb534c3f117ce44e56 /apps/drivers
downloadpx4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.gz
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.bz2
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.zip
Fresh import of the PX4 firmware sources.
Diffstat (limited to 'apps/drivers')
-rw-r--r--apps/drivers/bma180/Makefile42
-rw-r--r--apps/drivers/bma180/bma180.cpp774
-rw-r--r--apps/drivers/device/Makefile38
-rw-r--r--apps/drivers/device/cdev.cpp396
-rw-r--r--apps/drivers/device/device.cpp225
-rw-r--r--apps/drivers/device/device.h439
-rw-r--r--apps/drivers/device/device.h.orig430
-rw-r--r--apps/drivers/device/i2c.cpp149
-rw-r--r--apps/drivers/device/i2c.h116
-rw-r--r--apps/drivers/device/pio.cpp72
-rw-r--r--apps/drivers/device/spi.cpp142
-rw-r--r--apps/drivers/device/spi.h106
-rw-r--r--apps/drivers/drv_accel.h105
-rw-r--r--apps/drivers/drv_baro.h83
-rw-r--r--apps/drivers/drv_gpio.h64
-rw-r--r--apps/drivers/drv_gyro.h102
-rw-r--r--apps/drivers/drv_mag.h102
-rw-r--r--apps/drivers/drv_orb_dev.h84
-rw-r--r--apps/drivers/drv_pwm_output.h112
-rw-r--r--apps/drivers/drv_rc_input.h89
-rw-r--r--apps/drivers/ms5611/Makefile42
-rw-r--r--apps/drivers/ms5611/ms5611.cpp944
22 files changed, 4656 insertions, 0 deletions
diff --git a/apps/drivers/bma180/Makefile b/apps/drivers/bma180/Makefile
new file mode 100644
index 000000000..cc01b629e
--- /dev/null
+++ b/apps/drivers/bma180/Makefile
@@ -0,0 +1,42 @@
+############################################################################
+#
+# 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 BMA180 driver.
+#
+
+APPNAME = bma180
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 2048
+
+include $(APPDIR)/mk/app.mk
diff --git a/apps/drivers/bma180/bma180.cpp b/apps/drivers/bma180/bma180.cpp
new file mode 100644
index 000000000..a5d66d86b
--- /dev/null
+++ b/apps/drivers/bma180/bma180.cpp
@@ -0,0 +1,774 @@
+/****************************************************************************
+ *
+ * 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 Driver for the Bosch BMA 180 MEMS accelerometer connected via SPI.
+ */
+
+#include <nuttx/config.h>
+
+#include <device/spi.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stddef.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <arch/board/up_hrt.h>
+
+#include <drivers/drv_accel.h>
+
+extern "C" { __EXPORT int bma180_main(int argc, char *argv[]); }
+
+class BMA180 : public device::SPI
+{
+public:
+ BMA180(int bus, spi_dev_e device);
+ ~BMA180();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ virtual int open_first(struct file *filp);
+ virtual int close_last(struct file *filp);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+
+private:
+
+ struct hrt_call _call;
+ unsigned _call_interval;
+
+ unsigned _num_reports;
+ volatile unsigned _next_report;
+ volatile unsigned _oldest_report;
+ struct accel_report *_reports;
+
+ struct accel_scale _scale;
+ float _range_scale;
+
+ unsigned _reads;
+
+ /**
+ * Start automatic measurement.
+ */
+ void start();
+
+ /**
+ * Stop automatic measurement.
+ */
+ void stop();
+
+ /**
+ * Static trampoline from the hrt_call context; because we don't have a
+ * generic hrt wrapper yet.
+ *
+ * Called by the HRT in interrupt context at the specified rate if
+ * automatic polling is enabled.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void measure_trampoline(void *arg);
+
+ /**
+ * Fetch measurements from the sensor and update the report ring.
+ */
+ void measure();
+
+ /**
+ * Read a register from the BMA180
+ *
+ * @param The register to read.
+ * @return The value that was read.
+ */
+ uint8_t read_reg(unsigned reg);
+
+ /**
+ * Write a register in the BMA180
+ *
+ * @param reg The register to write.
+ * @param value The new value to write.
+ */
+ void write_reg(unsigned reg, uint8_t value);
+
+ /**
+ * Modify a register in the BMA180
+ *
+ * Bits are cleared before bits are set.
+ *
+ * @param reg The register to modify.
+ * @param clearbits Bits in the register to clear.
+ * @param setbits Bits in the register to set.
+ */
+ void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
+
+ /**
+ * Set the BMA180 measurement range.
+ *
+ * @param max_g The maximum G value the range must support.
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int set_range(unsigned max_g);
+
+ /**
+ * Set the BMA180 lowpass filter.
+ *
+ * @param frequency Set the lowpass filter cutoff frequency to no less than
+ * this frequency.
+ * @return OK if the value can be supported.
+ */
+ int set_bandwidth(unsigned frequency);
+};
+
+/* helper macro for handling report buffer indices */
+#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
+
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+
+#define ADDR_CHIP_ID 0x00
+#define CHIP_ID 0x03
+
+#define ADDR_ACC_X_LSB 0x02
+#define ADDR_ACC_Y_LSB 0x04
+#define ADDR_ACC_Z_LSB 0x06
+#define ADDR_TEMPERATURE 0x08
+
+#define ADDR_RESET 0x10
+#define SOFT_RESET 0xB6
+
+#define ADDR_BW_TCS 0x20
+#define BW_TCS_BW_MASK (0xf<<4)
+#define BW_TCS_BW_10HZ (0<<4)
+#define BW_TCS_BW_20HZ (1<<4)
+#define BW_TCS_BW_40HZ (2<<4)
+#define BW_TCS_BW_75HZ (3<<4)
+#define BW_TCS_BW_150HZ (4<<4)
+#define BW_TCS_BW_300HZ (5<<4)
+#define BW_TCS_BW_600HZ (6<<4)
+#define BW_TCS_BW_1200HZ (7<<4)
+
+#define ADDR_HIGH_DUR 0x27
+#define HIGH_DUR_DIS_I2C (1<<0)
+
+#define ADDR_TCO_Z 0x30
+#define TCO_Z_MODE_MASK 0x3
+
+#define ADDR_GAIN_Y 0x33
+#define GAIN_Y_SHADOW_DIS (1<<0)
+
+#define ADDR_OFFSET_LSB1 0x35
+#define OFFSET_LSB1_RANGE_MASK (7<<1)
+#define OFFSET_LSB1_RANGE_1G (0<<1)
+#define OFFSET_LSB1_RANGE_2G (2<<1)
+#define OFFSET_LSB1_RANGE_3G (3<<1)
+#define OFFSET_LSB1_RANGE_4G (4<<1)
+#define OFFSET_LSB1_RANGE_8G (5<<1)
+#define OFFSET_LSB1_RANGE_16G (6<<1)
+
+#define ADDR_OFFSET_T 0x37
+#define OFFSET_T_READOUT_12BIT (1<<0)
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" { int bma180_main(int argc, char *argv[]); }
+
+
+BMA180::BMA180(int bus, spi_dev_e device) :
+ SPI("BMA180", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 8000000),
+ _num_reports(0),
+ _next_report(0),
+ _oldest_report(0),
+ _reports(nullptr),
+ _reads(0)
+{
+ // enable debug() calls
+ _debug_enabled = true;
+
+ // default scale factors
+ _scale.x_offset = 0;
+ _scale.x_scale = 1.0f;
+ _scale.y_offset = 0;
+ _scale.y_scale = 1.0f;
+ _scale.z_offset = 0;
+ _scale.z_scale = 1.0f;
+}
+
+BMA180::~BMA180()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr)
+ delete[] _reports;
+}
+
+int
+BMA180::init()
+{
+ int ret;
+
+ /* do SPI init (and probe) first */
+ ret = SPI::init();
+
+ /* if probe/setup successful, finish chip init */
+ if (ret == OK) {
+
+ /* perform soft reset (p48) */
+ write_reg(ADDR_RESET, SOFT_RESET);
+
+ /* wait 10us (p49) */
+ usleep(10);
+
+ /* disable I2C interface */
+ modify_reg(ADDR_HIGH_DUR, HIGH_DUR_DIS_I2C, 0);
+
+ /* switch to low-noise mode */
+ modify_reg(ADDR_TCO_Z, TCO_Z_MODE_MASK, 0);
+
+ /* disable 12-bit mode */
+ modify_reg(ADDR_OFFSET_T, OFFSET_T_READOUT_12BIT, 0);
+
+ /* disable shadow-disable mode */
+ modify_reg(ADDR_GAIN_Y, GAIN_Y_SHADOW_DIS, 0);
+ }
+
+ return ret;
+}
+
+int
+BMA180::open_first(struct file *filp)
+{
+ /* reset to manual-poll mode */
+ _call_interval = 0;
+
+ /* allocate basic report buffers */
+ _num_reports = 2;
+ _reports = new struct accel_report[_num_reports];
+ _oldest_report = _next_report = 0;
+
+ /* set default range and lowpass */
+ set_range(4); /* 4G */
+ set_bandwidth(600); /* 600Hz */
+
+ return OK;
+}
+
+int
+BMA180::close_last(struct file *filp)
+{
+ /* stop measurement */
+ stop();
+
+ /* free report buffers */
+ if (_reports != nullptr) {
+ delete[] _reports;
+ _num_reports = 0;
+ }
+
+ return OK;
+}
+
+int
+BMA180::probe()
+{
+ if (read_reg(ADDR_CHIP_ID) == CHIP_ID)
+ return OK;
+
+ return -EIO;
+}
+
+ssize_t
+BMA180::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct accel_report);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_call_interval > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the measurement code while we are doing this;
+ * we are careful to avoid racing with it.
+ */
+ while (count--) {
+ if (_oldest_report != _next_report) {
+ memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
+ ret += sizeof(_reports[0]);
+ INCREMENT(_oldest_report, _num_reports);
+ }
+ }
+
+ _reads++;
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement */
+ _oldest_report = _next_report = 0;
+ measure();
+
+ /* measurement will have generated a report, copy it out */
+ memcpy(buffer, _reports, sizeof(*_reports));
+ ret = sizeof(*_reports);
+
+ return ret;
+}
+
+int
+BMA180::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case ACCELIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case ACC_POLLRATE_MANUAL:
+ stop();
+ _call_interval = 0;
+ return OK;
+
+ /* external signalling not supported */
+ case ACC_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_call_interval == 0);
+
+ /* convert hz to hrt interval via microseconds */
+ unsigned ticks = 1000000 / arg;
+
+ /* check against maximum sane rate */
+ if (ticks < 1000)
+ return -EINVAL;
+
+ /* update interval for next measurement */
+ /* XXX this is a bit shady, but no other way to adjust... */
+ _call.period = _call_interval;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case ACCELIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 2) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ struct accel_report *buf = new struct accel_report[arg];
+
+ if (nullptr == buf)
+ return -ENOMEM;
+
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete[] _reports;
+ _num_reports = arg;
+ _reports = buf;
+ start();
+
+ return OK;
+ }
+
+ case ACCELIOCSLOWPASS:
+ return set_bandwidth(arg);
+
+ case ACCELIORANGE:
+ return set_range(arg);
+
+ case ACCELIOCSSAMPLERATE: /* sensor sample rate is not (really) adjustable */
+ case ACCELIOCSREPORTFORMAT: /* no alternate report formats */
+ return -EINVAL;
+
+ default:
+ /* give it to the superclass */
+ return SPI::ioctl(filp, cmd, arg);
+ }
+}
+
+uint8_t
+BMA180::read_reg(unsigned reg)
+{
+ uint8_t cmd[2];
+
+ cmd[0] = reg | DIR_READ;
+
+ transfer(cmd, cmd, sizeof(cmd));
+
+ return cmd[1];
+}
+
+void
+BMA180::write_reg(unsigned reg, uint8_t value)
+{
+ uint8_t cmd[2];
+
+ cmd[0] = reg | DIR_WRITE;
+ cmd[1] = value;
+
+ transfer(cmd, nullptr, sizeof(cmd));
+}
+
+void
+BMA180::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
+{
+ uint8_t val;
+
+ val = read_reg(reg);
+ val &= ~clearbits;
+ val |= setbits;
+ write_reg(reg, val);
+}
+
+int
+BMA180::set_range(unsigned max_g)
+{
+ uint8_t rangebits;
+ float rangescale;
+
+ if (max_g > 16) {
+ return -ERANGE;
+
+ } else if (max_g > 8) { /* 16G */
+ rangebits = OFFSET_LSB1_RANGE_16G;
+ rangescale = 1.98;
+
+ } else if (max_g > 4) { /* 8G */
+ rangebits = OFFSET_LSB1_RANGE_8G;
+ rangescale = 0.99;
+
+ } else if (max_g > 3) { /* 4G */
+ rangebits = OFFSET_LSB1_RANGE_4G;
+ rangescale = 0.5;
+
+ } else if (max_g > 2) { /* 3G */
+ rangebits = OFFSET_LSB1_RANGE_3G;
+ rangescale = 0.38;
+
+ } else if (max_g > 1) { /* 2G */
+ rangebits = OFFSET_LSB1_RANGE_2G;
+ rangescale = 0.25;
+
+ } else { /* 1G */
+ rangebits = OFFSET_LSB1_RANGE_1G;
+ rangescale = 0.13;
+ }
+
+ /* adjust sensor configuration */
+ modify_reg(ADDR_OFFSET_LSB1, OFFSET_LSB1_RANGE_MASK, rangebits);
+ _range_scale = rangescale;
+
+ return OK;
+}
+
+int
+BMA180::set_bandwidth(unsigned frequency)
+{
+ uint8_t bwbits;
+
+ if (frequency > 1200) {
+ return -ERANGE;
+
+ } else if (frequency > 600) {
+ bwbits = BW_TCS_BW_1200HZ;
+
+ } else if (frequency > 300) {
+ bwbits = BW_TCS_BW_600HZ;
+
+ } else if (frequency > 150) {
+ bwbits = BW_TCS_BW_300HZ;
+
+ } else if (frequency > 75) {
+ bwbits = BW_TCS_BW_150HZ;
+
+ } else if (frequency > 40) {
+ bwbits = BW_TCS_BW_75HZ;
+
+ } else if (frequency > 20) {
+ bwbits = BW_TCS_BW_40HZ;
+
+ } else if (frequency > 10) {
+ bwbits = BW_TCS_BW_20HZ;
+
+ } else {
+ bwbits = BW_TCS_BW_10HZ;
+ }
+
+ /* adjust sensor configuration */
+ modify_reg(ADDR_BW_TCS, BW_TCS_BW_MASK, bwbits);
+
+ return OK;
+}
+
+void
+BMA180::start()
+{
+ /* make sure we are stopped first */
+ stop();
+
+ /* reset the report ring */
+ _oldest_report = _next_report = 0;
+
+ /* start polling at the specified rate */
+ hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&BMA180::measure_trampoline, this);
+}
+
+void
+BMA180::stop()
+{
+ hrt_cancel(&_call);
+}
+
+void
+BMA180::measure_trampoline(void *arg)
+{
+ BMA180 *dev = (BMA180 *)arg;
+
+ /* make another measurement */
+ dev->measure();
+}
+
+void
+BMA180::measure()
+{
+ /*
+ * This evil is to deal with the stupid layout of the BMA180
+ * measurement registers vs. the SPI transaction model.
+ */
+ union {
+ uint8_t bytes[10];
+ uint16_t words[5];
+ } buf;
+
+ /*
+ * Fetch the full set of measurements from the BMA180 in one pass;
+ * 7 bytes starting from the X LSB.
+ */
+ buf.bytes[1] = ADDR_ACC_X_LSB;
+ transfer(&buf.bytes[1], &buf.bytes[1], 8);
+
+ /*
+ * Adjust and scale results to mg.
+ *
+ * Note that we ignore the "new data" bits. At any time we read, each
+ * of the axis measurements are the "most recent", even if we've seen
+ * them before. There is no good way to synchronise with the internal
+ * measurement flow without using the external interrupt.
+ */
+ _reports[_next_report].timestamp = hrt_absolute_time();
+ _reports[_next_report].x = (buf.words[1] >> 2) * _range_scale;
+ _reports[_next_report].y = (buf.words[2] >> 2) * _range_scale;
+ _reports[_next_report].z = (buf.words[3] >> 2) * _range_scale;
+
+ /*
+ * @todo Apply additional scaling / calibration factors here.
+ */
+
+ /* post a report to the ring - note, not locked */
+ INCREMENT(_next_report, _num_reports);
+
+ /* if we are running up against the oldest report, fix it */
+ if (_next_report == _oldest_report)
+ INCREMENT(_oldest_report, _num_reports);
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+}
+
+void
+BMA180::print_info()
+{
+ printf("reads: %u\n", _reads);
+ printf("report queue: %u (%u/%u @ %p)\n",
+ _num_reports, _oldest_report, _next_report, _reports);
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace
+{
+
+BMA180 *g_dev;
+
+/*
+ * XXX this should just be part of the generic sensors test...
+ */
+
+int
+test()
+{
+ int fd = -1;
+ struct accel_report report;
+ ssize_t sz;
+ const char *reason = "test OK";
+
+ do {
+
+ /* get the driver */
+ fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ reason = "can't open driver";
+ break;
+ }
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ reason = "immediate read failed";
+ break;
+ }
+
+ printf("single read\n");
+ fflush(stdout);
+ printf("time: %lld\n", report.timestamp);
+ printf("x: %f\n", report.x);
+ printf("y: %f\n", report.y);
+ printf("z: %f\n", report.z);
+
+ } while (0);
+
+ printf("BMA180: %s\n", reason);
+
+ return OK;
+}
+
+int
+info()
+{
+ if (g_dev == nullptr) {
+ fprintf(stderr, "BMA180: driver not running\n");
+ return -ENOENT;
+ }
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ return OK;
+}
+
+
+} // namespace
+
+int
+bma180_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+ *
+ * XXX it would be nice to have a wrapper for this...
+ */
+ if (!strcmp(argv[1], "start")) {
+
+ if (g_dev != nullptr) {
+ fprintf(stderr, "BMA180: already loaded\n");
+ return -EBUSY;
+ }
+
+ /* create the driver */
+ g_dev = new BMA180(CONFIG_BMA180_SPI_BUS, (spi_dev_e)CONFIG_BMA180_SPI_DEVICE);
+
+ if (g_dev == nullptr) {
+ fprintf(stderr, "BMA180: driver alloc failed\n");
+ return -ENOMEM;
+ }
+
+ if (OK != g_dev->init()) {
+ fprintf(stderr, "BMA180: driver init failed\n");
+ usleep(100000);
+ delete g_dev;
+ g_dev = nullptr;
+ return -EIO;
+ }
+
+ printf("BMA180: driver started\n");
+ return OK;
+ }
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test"))
+ return test();
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info"))
+ return info();
+
+ fprintf(stderr, "unrecognised command, try 'start', 'test' or 'info'\n");
+ return -EINVAL;
+}
diff --git a/apps/drivers/device/Makefile b/apps/drivers/device/Makefile
new file mode 100644
index 000000000..f7b1fff88
--- /dev/null
+++ b/apps/drivers/device/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.
+#
+############################################################################
+
+#
+# Build the device driver framework.
+#
+
+include $(APPDIR)/mk/app.mk
diff --git a/apps/drivers/device/cdev.cpp b/apps/drivers/device/cdev.cpp
new file mode 100644
index 000000000..6b8bf0c2d
--- /dev/null
+++ b/apps/drivers/device/cdev.cpp
@@ -0,0 +1,396 @@
+/****************************************************************************
+ *
+ * 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 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.
+ */
+static 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, &cdev_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/apps/drivers/device/device.cpp b/apps/drivers/device/device.cpp
new file mode 100644
index 000000000..c14a3234d
--- /dev/null
+++ b/apps/drivers/device/device.cpp
@@ -0,0 +1,225 @@
+/****************************************************************************
+ *
+ * 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 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/apps/drivers/device/device.h b/apps/drivers/device/device.h
new file mode 100644
index 000000000..98dbf8bfb
--- /dev/null
+++ b/apps/drivers/device/device.h
@@ -0,0 +1,439 @@
+/****************************************************************************
+ *
+ * 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 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:
+ /**
+ * 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/apps/drivers/device/device.h.orig b/apps/drivers/device/device.h.orig
new file mode 100644
index 000000000..5030666e1
--- /dev/null
+++ b/apps/drivers/device/device.h.orig
@@ -0,0 +1,430 @@
+/****************************************************************************
+ *
+ * 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 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);
+
+protected:
+ /**
+ * 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/apps/drivers/device/i2c.cpp b/apps/drivers/device/i2c.cpp
new file mode 100644
index 000000000..8489db4bb
--- /dev/null
+++ b/apps/drivers/device/i2c.cpp
@@ -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 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
+ // 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 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(uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
+{
+ struct i2c_msg_s msgv[2];
+ unsigned msgs;
+ int ret;
+
+// 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 = 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;
+
+ ret = I2C_TRANSFER(_dev, &msgv[0], msgs);
+
+ return ret;
+}
+
+} // namespace device \ No newline at end of file
diff --git a/apps/drivers/device/i2c.h b/apps/drivers/device/i2c.h
new file mode 100644
index 000000000..d84f7bd09
--- /dev/null
+++ b/apps/drivers/device/i2c.h
@@ -0,0 +1,116 @@
+/****************************************************************************
+ *
+ * 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 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:
+ /**
+ * @ 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(uint8_t *send, unsigned send_len,
+ uint8_t *recv, unsigned recv_len);
+
+ /**
+ * 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:
+ int _bus;
+ uint16_t _address;
+ uint32_t _frequency;
+ struct i2c_dev_s *_dev;
+};
+
+} // namespace device
+
+#endif /* _DEVICE_I2C_H */
diff --git a/apps/drivers/device/pio.cpp b/apps/drivers/device/pio.cpp
new file mode 100644
index 000000000..5179752b5
--- /dev/null
+++ b/apps/drivers/device/pio.cpp
@@ -0,0 +1,72 @@
+/****************************************************************************
+ *
+ * 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 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/apps/drivers/device/spi.cpp b/apps/drivers/device/spi.cpp
new file mode 100644
index 000000000..d0647bef6
--- /dev/null
+++ b/apps/drivers/device/spi.cpp
@@ -0,0 +1,142 @@
+/****************************************************************************
+ *
+ * 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 Base class for devices connected via SPI.
+ *
+ * @todo Work out if caching the mode/frequency would save any time.
+ */
+
+#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;
+ }
+
+ // 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 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 */
+ SPI_LOCK(_dev, true);
+ SPI_SETFREQUENCY(_dev, _frequency);
+ SPI_SETMODE(_dev, _mode);
+ SPI_SELECT(_dev, _device, true);
+
+ /* do the transfer */
+ SPI_EXCHANGE(_dev, send, recv, len);
+
+ /* and clean up */
+ SPI_SELECT(_dev, _device, false);
+ SPI_LOCK(_dev, false);
+
+ return OK;
+}
+
+} // namespace device \ No newline at end of file
diff --git a/apps/drivers/device/spi.h b/apps/drivers/device/spi.h
new file mode 100644
index 000000000..ef382b03c
--- /dev/null
+++ b/apps/drivers/device/spi.h
@@ -0,0 +1,106 @@
+/****************************************************************************
+ *
+ * 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 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.
+ *
+ * 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/apps/drivers/drv_accel.h b/apps/drivers/drv_accel.h
new file mode 100644
index 000000000..bf13b2c32
--- /dev/null
+++ b/apps/drivers/drv_accel.h
@@ -0,0 +1,105 @@
+/****************************************************************************
+ *
+ * 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_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 {
+ float x;
+ float y;
+ float z;
+ uint64_t timestamp;
+};
+
+/** 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
+ */
+
+#define _ACCELIOCBASE (_SNIOCBASE + 0x20)
+#define _ACCELIOC(_n) (_IOC(_ACCELIOCBASE, _n))
+
+/** set the driver polling rate to (arg) Hz, or one of the ACC_POLLRATE constants */
+#define ACCELIOCSPOLLRATE _ACCELIOC(0)
+
+#define ACC_POLLRATE_MANUAL 1000000 /**< poll when read */
+#define ACC_POLLRATE_EXTERNAL 1000001 /**< poll when device signals ready */
+
+/** set the internal queue depth to (arg) entries, must be at least 1 */
+#define ACCELIOCSQUEUEDEPTH _ACCELIOC(1)
+
+/** set the accel internal sample rate to at least (arg) Hz */
+#define ACCELIOCSSAMPLERATE _ACCELIOC(2)
+
+/** set the accel internal lowpass filter to no lower than (arg) Hz */
+#define ACCELIOCSLOWPASS _ACCELIOC(3)
+
+/** set the report format to (arg); zero is the standard, 1-10 are reserved, all others are driver-specific. */
+#define ACCELIOCSREPORTFORMAT _ACCELIOC(4)
+
+/** set the accel scaling constants to the structure pointed to by (arg) */
+#define ACCELIOCSSCALE _ACCELIOC(5)
+
+/** set the accel measurement range to handle at least (arg) g */
+#define ACCELIORANGE _ACCELIOC(6)
+
+#endif /* _DRV_ACCEL_H */
diff --git a/apps/drivers/drv_baro.h b/apps/drivers/drv_baro.h
new file mode 100644
index 000000000..4cfb35454
--- /dev/null
+++ b/apps/drivers/drv_baro.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ *
+ * 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_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 (_SNIOCBASE + 0x10)
+#define _BAROIOC(_n) (_IOC(_BAROIOCBASE, _n))
+
+/** set the driver polling rate to (arg) Hz, or one of the BARO_POLLRATE constants */
+#define BAROIOCSPOLLRATE _BAROIOC(0)
+
+#define BARO_POLLRATE_MANUAL 1000000 /**< poll when read */
+#define BARO_POLLRATE_EXTERNAL 1000001 /**< poll when device signals ready */
+
+/** set the internal queue depth to (arg) entries, must be at least 1 */
+#define BAROIOCSQUEUEDEPTH _BAROIOC(1)
+
+/** set the report format to (arg); zero is the standard, 1-10 are reserved, all others are driver-specific. */
+#define BAROIOCSREPORTFORMAT _BAROIOC(2)
+
+#endif /* _DRV_BARO_H */
diff --git a/apps/drivers/drv_gpio.h b/apps/drivers/drv_gpio.h
new file mode 100644
index 000000000..b9684bce1
--- /dev/null
+++ b/apps/drivers/drv_gpio.h
@@ -0,0 +1,64 @@
+/****************************************************************************
+ *
+ * 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 Generic GPIO ioctl interface.
+ */
+
+#ifndef _DRV_GPIO_H
+#define _DRV_GPIO_H
+
+#include <sys/ioctl.h>
+
+/*
+ * GPIO defines come from a board-specific header, as they are shared
+ * with board-specific logic.
+ *
+ * The board-specific header must define:
+ * GPIO_DEVICE_PATH
+ * GPIO_RESET
+ * GPIO_SET_OUTPUT
+ * GPIO_SET_INPUT
+ * GPIO_SET_ALT_1
+ * GPIO_SET_ALT_2
+ * GPIO_SET_ALT_3
+ * GPIO_SET_ALT_4
+ * GPIO_SET
+ * GPIO_CLEAR
+ * GPIO_GET
+ */
+
+/* Include board-specific GPIO definitions as well. */
+#include <arch/board/drv_gpio.h>
+
+#endif /* _DRV_GPIO_H */ \ No newline at end of file
diff --git a/apps/drivers/drv_gyro.h b/apps/drivers/drv_gyro.h
new file mode 100644
index 000000000..21f6493b1
--- /dev/null
+++ b/apps/drivers/drv_gyro.h
@@ -0,0 +1,102 @@
+/****************************************************************************
+ *
+ * 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_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 {
+ float x;
+ float y;
+ float z;
+ uint64_t timestamp;
+};
+
+/** 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 (_SNIOCBASE + 0x10)
+#define _GYROIOC(_n) (_IOC(_GYROIOCBASE, _n))
+
+/** set the driver polling rate to (arg) Hz, or one of the GYRO_POLLRATE constants */
+#define GYROIOCSPOLLRATE _GYROIOC(0)
+
+#define GYRO_POLLRATE_MANUAL 1000000 /**< poll when read */
+#define GYRO_POLLRATE_EXTERNAL 1000001 /**< poll when device signals ready */
+
+/** set the internal queue depth to (arg) entries, must be at least 1 */
+#define GYROIOCSQUEUEDEPTH _GYROIOC(1)
+
+/** set the gyro internal sample rate to at least (arg) Hz */
+#define GYROIOCSSAMPLERATE _GYROIOC(2)
+
+/** set the gyro internal lowpass filter to no lower than (arg) Hz */
+#define GYROIOCSLOWPASS _GYROIOC(3)
+
+/** set the report format to (arg); zero is the standard, 1-10 are reserved, all others are driver-specific. */
+#define GYROIOCSREPORTFORMAT _GYROIOC(4)
+
+/** set the gyro scaling constants to (arg) */
+#define GYROIOCSSCALE _GYROIOC(5)
+
+#endif /* _DRV_GYRO_H */
diff --git a/apps/drivers/drv_mag.h b/apps/drivers/drv_mag.h
new file mode 100644
index 000000000..7e90e9e46
--- /dev/null
+++ b/apps/drivers/drv_mag.h
@@ -0,0 +1,102 @@
+/****************************************************************************
+ *
+ * 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_orb_dev.h"
+
+#define MAG_DEVICE_PATH "/dev/mag"
+
+/**
+ * mag report structure. Reads from the device must be in multiples of this
+ * structure.
+ */
+struct mag_report {
+ float x;
+ float y;
+ float z;
+ uint64_t timestamp;
+};
+
+/** 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 (_SNIOCBASE + 0x30)
+#define _MAGIOC(_n) (_IOC(_MAGIOBASE, _n))
+
+/** set the driver polling rate to (arg) Hz, or one of the MAG_POLLRATE constants */
+#define MAGIOCSPOLLRATE _MAGIOC(0)
+
+#define MAG_POLLRATE_MANUAL 1000000 /**< poll when read */
+#define MAG_POLLRATE_EXTERNAL 1000001 /**< poll when device signals ready */
+
+/** set the internal queue depth to (arg) entries, must be at least 1 */
+#define MAGIOCSQUEUEDEPTH _MAGIOC(1)
+
+/** set the mag internal sample rate to at least (arg) Hz */
+#define MAGIOCSSAMPLERATE _MAGIOC(2)
+
+/** set the mag internal lowpass filter to no lower than (arg) Hz */
+#define MAGIOCSLOWPASS _MAGIOC(3)
+
+/** set the report format to (arg); zero is the standard, 1-10 are reserved, all others are driver-specific. */
+#define MAGIOCSREPORTFORMAT _MAGIOC(4)
+
+/** set the mag scaling constants to the structure pointed to by (arg) */
+#define MAGIOCSSCALE _MAGIOC(5)
+
+#endif /* _DRV_MAG_H */
diff --git a/apps/drivers/drv_orb_dev.h b/apps/drivers/drv_orb_dev.h
new file mode 100644
index 000000000..bacef1cd3
--- /dev/null
+++ b/apps/drivers/drv_orb_dev.h
@@ -0,0 +1,84 @@
+/****************************************************************************
+ *
+ * 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 "../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 (_DIOCBASE + 0x80)
+#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)
+
+#endif /* _DRV_UORB_H */
diff --git a/apps/drivers/drv_pwm_output.h b/apps/drivers/drv_pwm_output.h
new file mode 100644
index 000000000..551f9b1a6
--- /dev/null
+++ b/apps/drivers/drv_pwm_output.h
@@ -0,0 +1,112 @@
+/****************************************************************************
+ *
+ * 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 ObjDev.
+ * Writing a value of 0 to a channel suppresses any output for that
+ * channel.
+ */
+
+#ifndef _DRV_PWM_OUTPUT_H
+#define _DRV_PWM_OUTPUT_H
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+#include "drv_orb_dev.h"
+
+/**
+ * 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 in the system.
+ */
+#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 servo update rate in Hz */
+ uint32_t update_rate;
+
+ /** desired pulse widths for each of the supported channels */
+ servo_position_t values[PWM_OUTPUT_MAX_CHANNELS];
+};
+
+/*
+ * ObjDev tag for PWM outputs.
+ */
+ORB_DECLARE(output_pwm);
+
+/*
+ * ioctl() definitions
+ *
+ * Note that ioctls and ObjDev updates should not be mixed, as the
+ * behaviour of the system in this case is not defined.
+ */
+#define _PWM_SERVO_BASE 0x7500
+
+/** 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 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)
+
+
+#endif /* _DRV_PWM_OUTPUT_H */
diff --git a/apps/drivers/drv_rc_input.h b/apps/drivers/drv_rc_input.h
new file mode 100644
index 000000000..532e95fb5
--- /dev/null
+++ b/apps/drivers/drv_rc_input.h
@@ -0,0 +1,89 @@
+/****************************************************************************
+ *
+ * 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.
+ */
+#define RC_INPUT_MAX_CHANNELS 16
+
+/**
+ * Input signal type, value is a control position from zero to 100
+ * percent.
+ */
+typedef uint8_t rc_input_t;
+
+/**
+ * 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 {
+ /** number of channels actually being seen */
+ uint32_t channel_count;
+
+ /** desired 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);
+
+#endif /* _DRV_RC_INPUT_H */
diff --git a/apps/drivers/ms5611/Makefile b/apps/drivers/ms5611/Makefile
new file mode 100644
index 000000000..d8e67cba2
--- /dev/null
+++ b/apps/drivers/ms5611/Makefile
@@ -0,0 +1,42 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# MS5611 driver
+#
+
+APPNAME = ms5611
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 2048
+
+include $(APPDIR)/mk/app.mk
diff --git a/apps/drivers/ms5611/ms5611.cpp b/apps/drivers/ms5611/ms5611.cpp
new file mode 100644
index 000000000..d3c75f755
--- /dev/null
+++ b/apps/drivers/ms5611/ms5611.cpp
@@ -0,0 +1,944 @@
+/****************************************************************************
+ *
+ * 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 Driver for the MS5611 barometric pressure sensor connected via I2C
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <arch/board/up_hrt.h>
+
+#include <drivers/drv_baro.h>
+
+/**
+ * Calibration PROM as reported by the device.
+ */
+#pragma pack(push,1)
+struct ms5611_prom_s {
+ uint16_t factory_setup;
+ uint16_t c1_pressure_sens;
+ uint16_t c2_pressure_offset;
+ uint16_t c3_temp_coeff_pres_sens;
+ uint16_t c4_temp_coeff_pres_offset;
+ uint16_t c5_reference_temp;
+ uint16_t c6_temp_coeff_temp;
+ uint16_t serial_and_crc;
+};
+
+/**
+ * Grody hack for crc4()
+ */
+union ms5611_prom_u {
+ uint16_t c[8];
+ struct ms5611_prom_s s;
+};
+#pragma pack(pop)
+
+class MS5611 : public device::I2C
+{
+public:
+ MS5611(int bus);
+ ~MS5611();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ virtual int open_first(struct file *filp);
+ virtual int close_last(struct file *filp);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+
+private:
+ union ms5611_prom_u _prom;
+
+ struct work_s _work;
+ unsigned _measure_ticks;
+
+ unsigned _num_reports;
+ volatile unsigned _next_report;
+ volatile unsigned _oldest_report;
+ struct baro_report *_reports;
+
+ bool _collect_phase;
+ unsigned _measure_phase;
+
+ int32_t _dT;
+ int64_t _temp64;
+
+ int _orbject;
+
+ unsigned _reads;
+ unsigned _measure_errors;
+ unsigned _read_errors;
+ unsigned _buf_overflows;
+
+ /**
+ * Test whether the device supported by the driver is present at a
+ * specific address.
+ *
+ * @param address The I2C bus address to probe.
+ * @return True if the device is present.
+ */
+ int probe_address(uint8_t address);
+
+ /**
+ * Initialise the automatic measurement state machine and start it.
+ *
+ * @note This function is called at open and error time. It might make sense
+ * to make it more aggressive about resetting the bus in case of errors.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ *
+ * This is the heart of the measurement state machine. This function
+ * alternately starts a measurement, or collects the data from the
+ * previous measurement.
+ *
+ * When the interval between measurements is greater than the minimum
+ * measurement interval, a gap is inserted between collection
+ * and measurement to provide the most recent measurement possible
+ * at the next interval.
+ */
+ void cycle();
+
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+ /**
+ * Issue a measurement command for the current state.
+ *
+ * @return OK if the measurement command was successful.
+ */
+ int measure();
+
+ /**
+ * Collect the result of the most recent measurement.
+ */
+ int collect();
+
+ /**
+ * Read the MS5611 PROM
+ *
+ * @return OK if the PROM reads successfully.
+ */
+ int read_prom();
+
+ /**
+ * PROM CRC routine ported from MS5611 application note
+ *
+ * @param n_prom Pointer to words read from PROM.
+ * @return True if the CRC matches.
+ */
+ bool crc4(uint16_t *n_prom);
+
+};
+
+/* helper macro for handling report buffer indices */
+#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
+
+/*
+ * MS5611 internal constants and data structures.
+ */
+
+/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
+#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
+#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
+
+#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
+#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
+
+#define ADDR_RESET_CMD 0x1E /* read from this address to reset chip (0b0011110 on bus) */
+#define ADDR_CMD_CONVERT_D1 0x48 /* 4096 samples to this address to start conversion (0b01001000 on bus) */
+#define ADDR_CMD_CONVERT_D2 0x58 /* 4096 samples */
+#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
+#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
+#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int ms5611_main(int argc, char *argv[]);
+
+
+MS5611::MS5611(int bus) :
+ I2C("MS5611", BARO_DEVICE_PATH, bus, 0, 400000),
+ _measure_ticks(0),
+ _num_reports(0),
+ _next_report(0),
+ _oldest_report(0),
+ _reports(nullptr),
+ _collect_phase(false),
+ _measure_phase(0),
+ _dT(0),
+ _temp64(0),
+ _reads(0),
+ _measure_errors(0),
+ _read_errors(0),
+ _buf_overflows(0)
+{
+ // enable debug() calls
+ _debug_enabled = true;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ _work.worker = nullptr;
+}
+
+MS5611::~MS5611()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr)
+ delete[] _reports;
+}
+
+int
+MS5611::init()
+{
+ int ret;
+
+ /* do I2C init (and probe) first */
+ ret = I2C::init();
+
+ /* assuming we're good, advertise the object */
+ if (ret == OK) {
+ struct baro_report b;
+
+ /* if this fails (e.g. no object in the system) that's OK */
+ memset(&b, 0, sizeof(b));
+ _orbject = orb_advertise(ORB_ID(sensor_baro), &b);
+
+ if (_orbject < 0)
+ debug("failed to create sensor_baro object");
+ }
+
+ return ret;
+}
+
+int
+MS5611::open_first(struct file *filp)
+{
+ /* reset to manual-poll mode */
+ _measure_ticks = 0;
+
+ /* allocate basic report buffers */
+ _num_reports = 2;
+ _reports = new struct baro_report[_num_reports];
+ _oldest_report = _next_report = 0;
+
+ return OK;
+}
+
+int
+MS5611::close_last(struct file *filp)
+{
+ /* stop measurement */
+ stop();
+
+ /* free report buffers */
+ if (_reports != nullptr) {
+ delete[] _reports;
+ _num_reports = 0;
+ }
+
+ _measure_ticks = 0;
+
+ return OK;
+}
+
+int
+MS5611::probe()
+{
+ if (OK == probe_address(MS5611_ADDRESS_1))
+ return OK;
+
+ if (OK == probe_address(MS5611_ADDRESS_2))
+ return OK;
+
+ return -EIO;
+}
+
+int
+MS5611::probe_address(uint8_t address)
+{
+ uint8_t cmd = ADDR_RESET_CMD;
+
+ /* select the address we are going to try */
+ set_address(address);
+
+ /* send reset command */
+ if (OK != transfer(&cmd, 1, nullptr, 0))
+ return -EIO;
+
+ /* wait for PROM contents to be in the device (2.8 ms) */
+ usleep(3000);
+
+ /* read PROM */
+ if (OK != read_prom())
+ return -EIO;
+
+ return OK;
+}
+
+ssize_t
+MS5611::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct baro_report);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_measure_ticks > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the workq thread while we are doing this;
+ * we are careful to avoid racing with them.
+ */
+ while (count--) {
+ if (_oldest_report != _next_report) {
+ memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
+ ret += sizeof(_reports[0]);
+ INCREMENT(_oldest_report, _num_reports);
+ }
+ }
+
+ _reads++;
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement - run one conversion */
+ /* XXX really it'd be nice to lock against other readers here */
+ do {
+ _measure_phase = 0;
+ _oldest_report = _next_report = 0;
+
+ /* do temperature first */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ usleep(MS5611_CONVERSION_INTERVAL);
+
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* now do a pressure measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ usleep(MS5611_CONVERSION_INTERVAL);
+
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* state machine will have generated a report, copy it out */
+ memcpy(buffer, _reports, sizeof(*_reports));
+ ret = sizeof(*_reports);
+ _reads++;
+
+ } while (0);
+
+ return ret;
+}
+
+int
+MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case BAROIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case BARO_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
+
+ /* external signalling not supported */
+ case BARO_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
+
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(MS5611_CONVERSION_INTERVAL))
+ return -EINVAL;
+
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case BAROIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 2) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ struct baro_report *buf = new struct baro_report[arg];
+
+ if (nullptr == buf)
+ return -ENOMEM;
+
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete[] _reports;
+ _num_reports = arg;
+ _reports = buf;
+ start();
+
+ return OK;
+ }
+
+ case BAROIOCSREPORTFORMAT:
+ return -EINVAL;
+
+ default:
+ /* give it to the superclass */
+ return I2C::ioctl(filp, cmd, arg);
+ }
+}
+
+void
+MS5611::start()
+{
+ /* make sure we are stopped first */
+ stop();
+
+ /* reset the report ring and state machine */
+ _collect_phase = false;
+ _measure_phase = 0;
+ _oldest_report = _next_report = 0;
+
+ /* schedule a cycle to start things */
+ work_queue(&_work, (worker_t)&MS5611::cycle_trampoline, this, 1);
+}
+
+void
+MS5611::stop()
+{
+ work_cancel(&_work);
+}
+
+void
+MS5611::cycle_trampoline(void *arg)
+{
+ MS5611 *dev = (MS5611 *)arg;
+
+ dev->cycle();
+}
+
+void
+MS5611::cycle()
+{
+ /* collection phase? */
+ if (_collect_phase) {
+
+ /* perform collection */
+ if (OK != collect()) {
+ log("FATAL collection error - restarting\n");
+ start();
+ return;
+ }
+
+ /* next phase is measurement */
+ _collect_phase = false;
+
+ /*
+ * Is there a collect->measure gap?
+ * Don't inject one after temperature measurements, so we can keep
+ * doing pressure measurements at something close to the desired rate.
+ */
+ if ((_measure_phase != 0) &&
+ (_measure_ticks > USEC2TICK(MS5611_CONVERSION_INTERVAL))) {
+
+ /* schedule a fresh cycle call when we are ready to measure again */
+ work_queue(&_work,
+ (worker_t)&MS5611::cycle_trampoline,
+ this,
+ _measure_ticks - USEC2TICK(MS5611_CONVERSION_INTERVAL));
+
+ return;
+ }
+ }
+
+ /* measurement phase */
+ if (OK != measure()) {
+ log("FATAL measure error - restarting\n");
+ start();
+ }
+
+ /* next phase is collection */
+ _collect_phase = true;
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(&_work,
+ (worker_t)&MS5611::cycle_trampoline,
+ this,
+ USEC2TICK(MS5611_CONVERSION_INTERVAL));
+}
+
+int
+MS5611::measure()
+{
+ int ret;
+
+ /*
+ * In phase zero, request temperature; in other phases, request pressure.
+ */
+ uint8_t cmd_data = (_measure_phase == 0) ? ADDR_CMD_CONVERT_D2 : ADDR_CMD_CONVERT_D1;
+
+ /*
+ * Send the command to begin measuring.
+ */
+ ret = transfer(&cmd_data, 1, nullptr, 0);
+
+ if (OK != ret)
+ _measure_errors++;
+
+ return ret;
+}
+
+int
+MS5611::collect()
+{
+ uint8_t cmd;
+ uint8_t data[3];
+
+ /* read the most recent measurement */
+ cmd = 0;
+
+ /* this should be fairly close to the end of the conversion, so the best approximation of the time */
+ _reports[_next_report].timestamp = hrt_absolute_time();
+
+ if (OK != transfer(&cmd, 1, &data[0], 3)) {
+ _read_errors++;
+ return -EIO;
+ }
+
+ /* fetch the raw value */
+ uint32_t raw = (((uint32_t)data[0]) << 16) | (((uint32_t)data[1]) << 8) | ((uint32_t)data[2]);
+
+ /* handle a measurement */
+ if (_measure_phase == 0) {
+
+ /* temperature calculation */
+ _dT = raw - (((int32_t)_prom.s.c5_reference_temp) * 256);
+ _temp64 = 2000 + (((int64_t)_dT) * _prom.s.c6_temp_coeff_temp) / 8388608;
+
+ } else {
+
+ /* pressure calculation */
+ int64_t offset = (int64_t)_prom.s.c2_pressure_offset * 65536 + ((int64_t)_dT * _prom.s.c4_temp_coeff_pres_offset) / 128;
+ int64_t sens = (int64_t)_prom.s.c1_pressure_sens * 32768 + ((int64_t)_dT * _prom.s.c3_temp_coeff_pres_sens) / 256;
+
+ /* it's pretty cold, second order temperature compensation needed */
+ if (_temp64 < 2000) {
+ /* second order temperature compensation */
+ int64_t temp2 = (((int64_t)_dT) * _dT) >> 31;
+ int64_t tmp_64 = (_temp64 - 2000) * (_temp64 - 2000);
+ int64_t offset2 = (5 * tmp_64) >> 1;
+ int64_t sens2 = (5 * tmp_64) >> 2;
+ _temp64 = _temp64 - temp2;
+ offset = offset - offset2;
+ sens = sens - sens2;
+ }
+
+ int64_t press_int64 = (((raw * sens) / 2097152 - offset) / 32768);
+
+ /* generate a new report */
+ _reports[_next_report].temperature = _temp64 / 100.0f;
+ _reports[_next_report].pressure = press_int64 / 100.0f;
+ /* convert as double for max. precision, store as float (more than enough precision) */
+ _reports[_next_report].altitude = (44330.0 * (1.0 - pow((press_int64 / 101325.0), 0.190295)));
+
+ /* publish it */
+ orb_publish(ORB_ID(sensor_baro), _orbject, &_reports[_next_report]);
+
+ /* post a report to the ring - note, not locked */
+ INCREMENT(_next_report, _num_reports);
+
+ /* if we are running up against the oldest report, toss it */
+ if (_next_report == _oldest_report) {
+ _buf_overflows++;
+ INCREMENT(_oldest_report, _num_reports);
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+ }
+
+
+ /* update the measurement state machine */
+ INCREMENT(_measure_phase, MS5611_MEASUREMENT_RATIO + 1);
+
+ return OK;
+}
+
+int
+MS5611::read_prom()
+{
+ /* read PROM data */
+ uint8_t prom_buf[2] = {255, 255};
+
+ for (int i = 0; i < 8; i++) {
+ uint8_t cmd = ADDR_PROM_SETUP + (i * 2);
+
+ if (OK != transfer(&cmd, 1, &prom_buf[0], 2))
+ break;
+
+ /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
+ _prom.c[i] = (((uint16_t)prom_buf[0]) << 8) | ((uint16_t)prom_buf[1]);
+
+ }
+
+ /* calculate CRC and return false */
+ return crc4(&_prom.c[0]) ? OK : -EIO;
+}
+
+bool
+MS5611::crc4(uint16_t *n_prom)
+{
+ int16_t cnt;
+ uint16_t n_rem;
+ uint16_t crc_read;
+ uint8_t n_bit;
+
+ n_rem = 0x00;
+
+ /* save the read crc */
+ crc_read = n_prom[7];
+
+ /* remove CRC byte */
+ n_prom[7] = (0xFF00 & (n_prom[7]));
+
+ for (cnt = 0; cnt < 16; cnt++) {
+ /* uneven bytes */
+ if (cnt & 1) {
+ n_rem ^= (uint8_t)((n_prom[cnt >> 1]) & 0x00FF);
+
+ } else {
+ n_rem ^= (uint8_t)(n_prom[cnt >> 1] >> 8);
+ }
+
+ for (n_bit = 8; n_bit > 0; n_bit--) {
+ if (n_rem & 0x8000) {
+ n_rem = (n_rem << 1) ^ 0x3000;
+
+ } else {
+ n_rem = (n_rem << 1);
+ }
+ }
+ }
+
+ /* final 4 bit remainder is CRC value */
+ n_rem = (0x000F & (n_rem >> 12));
+ n_prom[7] = crc_read;
+
+ /* return true if CRCs match */
+ return (0x000F & crc_read) == (n_rem ^ 0x00);
+}
+
+void
+MS5611::print_info()
+{
+ printf("reads: %u\n", _reads);
+ printf("measure errors: %u\n", _measure_errors);
+ printf("read errors: %u\n", _read_errors);
+ printf("read overflows: %u\n", _buf_overflows);
+ printf("poll interval: %u ticks\n", _measure_ticks);
+ printf("report queue: %u (%u/%u @ %p)\n",
+ _num_reports, _oldest_report, _next_report, _reports);
+ printf("dT/temp64: %d/%lld\n", _dT, _temp64);
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+MS5611 *g_dev;
+
+/*
+ * XXX this should just be part of the generic sensors test...
+ */
+
+
+int
+test_fail(const char *fmt, ...)
+{
+ va_list ap;
+
+ fprintf(stderr, "FAIL: ");
+ va_start(ap, fmt);
+ vfprintf(stderr, fmt, ap);
+ va_end(ap);
+ fprintf(stderr, "\n");
+ fflush(stderr);
+ return ERROR;
+}
+
+int
+test_note(const char *fmt, ...)
+{
+ va_list ap;
+
+ fprintf(stderr, "note: ");
+ va_start(ap, fmt);
+ vfprintf(stderr, fmt, ap);
+ va_end(ap);
+ fprintf(stderr, "\n");
+ fflush(stderr);
+ return OK;
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ *
+ * @param fd An open file descriptor on the driver.
+ */
+int
+test(int fd)
+{
+ struct baro_report report;
+ ssize_t sz;
+ int ret;
+
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report))
+ return test_fail("immediate read failed: %d", errno);
+
+ test_note("single read");
+ test_note("pressure: %u", (unsigned)report.pressure);
+ test_note("altitude: %u", (unsigned)report.altitude);
+ test_note("temperature: %u", (unsigned)report.temperature);
+ test_note("time: %lld", report.timestamp);
+ usleep(1000000);
+
+ /* set the queue depth to 10 */
+ if (OK != ioctl(fd, BAROIOCSQUEUEDEPTH, 10))
+ return test_fail("failed to set queue depth");
+
+ /* start the sensor polling at 2Hz */
+ if (OK != ioctl(fd, BAROIOCSPOLLRATE, 2))
+ return test_fail("failed to set 2Hz poll rate");
+
+ /* read the sensor 5x and report each value */
+ for (unsigned i = 0; i < 5; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 2000);
+
+ if (ret != 1)
+ return test_fail("timed out waiting for sensor data");
+
+ /* now go get it */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report))
+ return test_fail("periodic read failed: %d", errno);
+
+ test_note("periodic read %u", i);
+ test_note("pressure: %u", (unsigned)report.pressure);
+ test_note("altitude: %u", (unsigned)report.altitude);
+ test_note("temperature: %u", (unsigned)report.temperature);
+ test_note("time: %lld", report.timestamp);
+ }
+
+ return test_note("PASS");
+ return OK;
+}
+
+int
+info()
+{
+ if (g_dev == nullptr) {
+ fprintf(stderr, "MS5611: driver not running\n");
+ return -ENOENT;
+ }
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ return OK;
+}
+
+
+} // namespace
+
+int
+ms5611_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+ *
+ * XXX it would be nice to have a wrapper for this...
+ */
+ if (!strcmp(argv[1], "start")) {
+
+ if (g_dev != nullptr) {
+ fprintf(stderr, "MS5611: already loaded\n");
+ return -EBUSY;
+ }
+
+ /* create the driver */
+ /* XXX HORRIBLE hack - the bus number should not come from here */
+ g_dev = new MS5611(2);
+
+ if (g_dev == nullptr) {
+ fprintf(stderr, "MS5611: driver alloc failed\n");
+ return -ENOMEM;
+ }
+
+ if (OK != g_dev->init()) {
+ fprintf(stderr, "MS5611: driver init failed\n");
+ usleep(100000);
+ delete g_dev;
+ g_dev = nullptr;
+ return -EIO;
+ }
+
+ return OK;
+ }
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test")) {
+ int fd, ret;
+
+ fd = open(BARO_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ return test_fail("driver open failed: %d", errno);
+
+ ret = test(fd);
+ close(fd);
+ return ret;
+ }
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info"))
+ return info();
+
+ fprintf(stderr, "unrecognised command, try 'start', 'test' or 'info'\n");
+ return -EINVAL;
+}