aboutsummaryrefslogtreecommitdiff
path: root/nuttx/configs/px4fmu/src
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 /nuttx/configs/px4fmu/src
downloadpx4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.gz
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.bz2
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.zip
Fresh import of the PX4 firmware sources.
Diffstat (limited to 'nuttx/configs/px4fmu/src')
-rw-r--r--nuttx/configs/px4fmu/src/Makefile102
-rw-r--r--nuttx/configs/px4fmu/src/drv_bma180.c341
-rw-r--r--nuttx/configs/px4fmu/src/drv_eeprom.c522
-rw-r--r--nuttx/configs/px4fmu/src/drv_gpio.c195
-rw-r--r--nuttx/configs/px4fmu/src/drv_hmc5833l.c352
-rw-r--r--nuttx/configs/px4fmu/src/drv_l3gd20.c364
-rw-r--r--nuttx/configs/px4fmu/src/drv_led.c113
-rw-r--r--nuttx/configs/px4fmu/src/drv_lis331.c272
-rw-r--r--nuttx/configs/px4fmu/src/drv_mpu6000.c411
-rw-r--r--nuttx/configs/px4fmu/src/drv_ms5611.c493
-rw-r--r--nuttx/configs/px4fmu/src/drv_tone_alarm.c511
-rw-r--r--nuttx/configs/px4fmu/src/px4fmu-internal.h166
-rw-r--r--nuttx/configs/px4fmu/src/up_adc.c173
-rw-r--r--nuttx/configs/px4fmu/src/up_boot.c76
-rw-r--r--nuttx/configs/px4fmu/src/up_can.c142
-rw-r--r--nuttx/configs/px4fmu/src/up_cpuload.c182
-rw-r--r--nuttx/configs/px4fmu/src/up_hrt.c801
-rw-r--r--nuttx/configs/px4fmu/src/up_leds.c127
-rw-r--r--nuttx/configs/px4fmu/src/up_nsh.c392
-rw-r--r--nuttx/configs/px4fmu/src/up_pwm_servo.c344
-rw-r--r--nuttx/configs/px4fmu/src/up_spi.c192
-rw-r--r--nuttx/configs/px4fmu/src/up_usbdev.c105
22 files changed, 6376 insertions, 0 deletions
diff --git a/nuttx/configs/px4fmu/src/Makefile b/nuttx/configs/px4fmu/src/Makefile
new file mode 100644
index 000000000..2e3138aaa
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/Makefile
@@ -0,0 +1,102 @@
+############################################################################
+# configs/px4fmu/src/Makefile
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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 NuttX 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = up_boot.c up_leds.c up_spi.c up_hrt.c \
+ drv_gpio.c drv_bma180.c drv_l3gd20.c \
+ drv_led.c drv_hmc5833l.c drv_ms5611.c drv_eeprom.c \
+ drv_tone_alarm.c up_pwm_servo.c up_usbdev.c \
+ up_cpuload.c drv_mpu6000.c
+
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+CSRCS += up_nsh.c
+endif
+
+ifeq ($(CONFIG_ADC),y)
+CSRCS += up_adc.c
+endif
+
+ifeq ($(CONFIG_CAN),y)
+CSRCS += up_can.c
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f libboard$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
+
diff --git a/nuttx/configs/px4fmu/src/drv_bma180.c b/nuttx/configs/px4fmu/src/drv_bma180.c
new file mode 100644
index 000000000..da80cc2e2
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_bma180.c
@@ -0,0 +1,341 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Bosch BMA 180 MEMS accelerometer
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include <stdio.h>
+
+#include "chip.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_bma180.h>
+
+/*
+ * BMA180 registers
+ */
+
+/* Important Notes:
+ *
+ * - MAX SPI clock: 25 MHz
+ * - Readout time: 0.417 ms in high accuracy mode
+ * - Boot / ready time: 1.27 ms
+ *
+ */
+
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define ADDR_CHIP_ID 0x00
+#define CHIP_ID 0x03
+#define ADDR_VERSION 0x01
+
+#define ADDR_CTRL_REG0 0x0D
+#define ADDR_CTRL_REG1 0x0E
+#define ADDR_CTRL_REG2 0x0F
+#define ADDR_BWTCS 0x20
+#define ADDR_CTRL_REG3 0x21
+#define ADDR_CTRL_REG4 0x22
+#define ADDR_OLSB1 0x35
+
+#define ADDR_ACC_X_LSB 0x02
+#define ADDR_ACC_Z_MSB 0x07
+#define ADDR_TEMPERATURE 0x08
+
+#define ADDR_STATUS_REG1 0x09
+#define ADDR_STATUS_REG2 0x0A
+#define ADDR_STATUS_REG3 0x0B
+#define ADDR_STATUS_REG4 0x0C
+
+#define ADDR_RESET 0x10
+#define SOFT_RESET 0xB6
+
+#define ADDR_DIS_I2C 0x27
+
+#define REG0_WRITE_ENABLE 0x10
+
+#define RANGEMASK 0x0E
+#define BWMASK 0xF0
+
+
+static ssize_t bma180_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int bma180_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations bma180_fops = {
+ .read = bma180_read,
+ .ioctl = bma180_ioctl,
+};
+
+struct bma180_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+ uint8_t rate;
+ struct bma180_buffer *buffer;
+};
+
+static struct bma180_dev_s bma180_dev;
+
+static void bma180_write_reg(uint8_t address, uint8_t data);
+static uint8_t bma180_read_reg(uint8_t address);
+static bool read_fifo(uint16_t *data);
+static int bma180_set_range(uint8_t range);
+static int bma180_set_rate(uint8_t rate);
+
+static void
+bma180_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, true);
+ SPI_SNDBLOCK(bma180_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, false);
+}
+
+static uint8_t
+bma180_read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, true);
+ SPI_EXCHANGE(bma180_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, false);
+
+ return data[1];
+}
+
+static bool
+read_fifo(uint16_t *data)
+{
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ uint8_t temp;
+ } __attribute__((packed)) report;
+
+ report.cmd = ADDR_ACC_X_LSB | DIR_READ | ADDR_INCREMENT;
+
+ SPI_LOCK(bma180_dev.spi, true);
+ report.x = bma180_read_reg(ADDR_ACC_X_LSB);
+ report.x |= (bma180_read_reg(ADDR_ACC_X_LSB+1) << 8);
+ report.y = bma180_read_reg(ADDR_ACC_X_LSB+2);
+ report.y |= (bma180_read_reg(ADDR_ACC_X_LSB+3) << 8);
+ report.z = bma180_read_reg(ADDR_ACC_X_LSB+4);
+ report.z |= (bma180_read_reg(ADDR_ACC_X_LSB+5) << 8);
+ report.temp = bma180_read_reg(ADDR_ACC_X_LSB+6);
+ SPI_LOCK(bma180_dev.spi, false);
+
+ /* Collect status and remove two top bits */
+
+ uint8_t new_data = (report.x & 0x01) + (report.x & 0x01) + (report.x & 0x01);
+ report.x = (report.x >> 2);
+ report.y = (report.y >> 2);
+ report.z = (report.z >> 2);
+
+ data[0] = report.x;
+ data[1] = report.y;
+ data[2] = report.z;
+
+ /* return 1 for all three axes new */
+ return (new_data > 0); // bit funky, depends on timing
+}
+
+static int
+bma180_set_range(uint8_t range)
+{
+ /* enable writing to chip config */
+ uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 |= REG0_WRITE_ENABLE;
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ /* set range */
+ uint8_t olsb1 = bma180_read_reg(ADDR_OLSB1);
+ olsb1 &= (~RANGEMASK);
+ olsb1 |= (range);// & RANGEMASK);
+ bma180_write_reg(ADDR_OLSB1, olsb1);
+
+ // up_udelay(500);
+
+ /* block writing to chip config */
+ ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 &= (~REG0_WRITE_ENABLE);
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ uint8_t new_olsb1 = bma180_read_reg(ADDR_OLSB1);
+
+ /* return 0 on success, 1 on failure */
+ return !(olsb1 == new_olsb1);
+}
+
+static int
+bma180_set_rate(uint8_t rate)
+{
+ /* enable writing to chip config */
+ uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 |= REG0_WRITE_ENABLE;
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ /* set rate / bandwidth */
+ uint8_t bwtcs = bma180_read_reg(ADDR_BWTCS);
+ bwtcs &= (~BWMASK);
+ bwtcs |= (rate);// & BWMASK);
+ bma180_write_reg(ADDR_BWTCS, bwtcs);
+
+ // up_udelay(500);
+
+ /* block writing to chip config */
+ ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 &= (~REG0_WRITE_ENABLE);
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ uint8_t new_bwtcs = bma180_read_reg(ADDR_BWTCS);
+
+ /* return 0 on success, 1 on failure */
+ return !(bwtcs == new_bwtcs);
+}
+
+static ssize_t
+bma180_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ if (read_fifo((uint16_t *)buffer))
+ return 6;
+
+ /* no data */
+ return 0;
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return ERROR;
+}
+
+static int
+bma180_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case BMA180_SETRATE:
+ result = bma180_set_rate(arg);
+ break;
+
+ case BMA180_SETRANGE:
+ result = bma180_set_range(arg);
+ break;
+
+ case BMA180_SETBUFFER:
+ bma180_dev.buffer = (struct bma180_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+bma180_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ bma180_dev.spi = spi;
+ bma180_dev.spi_id = spi_id;
+
+ SPI_LOCK(bma180_dev.spi, true);
+
+ /* verify that the device is attached and functioning */
+ if (bma180_read_reg(ADDR_CHIP_ID) == CHIP_ID) {
+
+ bma180_write_reg(ADDR_RESET, SOFT_RESET); // page 48
+
+ up_udelay(13000); // wait 12 ms, see page 49
+
+ /* Configuring the BMA180 */
+
+ /* enable writing to chip config */
+ uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 |= REG0_WRITE_ENABLE;
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ /* disable I2C interface, datasheet page 31 */
+ uint8_t disi2c = bma180_read_reg(ADDR_DIS_I2C);
+ disi2c |= 0x01;
+ bma180_write_reg(ADDR_DIS_I2C, disi2c);
+
+ /* block writing to chip config */
+ ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 &= (~REG0_WRITE_ENABLE);
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ // up_udelay(500);
+
+ /* set rate */
+ result = bma180_set_rate(BMA180_RATE_LP_600HZ);
+
+ // up_udelay(500);
+
+ /* set range */
+ result += bma180_set_range(BMA180_RANGE_4G);
+
+ // up_udelay(500);
+
+ if (result == 0) {
+ /* make ourselves available */
+ register_driver("/dev/bma180", &bma180_fops, 0666, NULL);
+ }
+ } else {
+ errno = EIO;
+ }
+
+ SPI_LOCK(bma180_dev.spi, false);
+
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_eeprom.c b/nuttx/configs/px4fmu/src/drv_eeprom.c
new file mode 100644
index 000000000..c22062ec5
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_eeprom.c
@@ -0,0 +1,522 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of 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.
+ */
+
+/*
+ * Generic driver for I2C EEPROMs with 8 bit or 16 bit addressing
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+#include <unistd.h>
+
+#include <nuttx/i2c.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_eeprom.h>
+
+/* Split I2C transfers into smaller chunks to make sure to stay within tight timeout limits */
+
+/* check defines */
+#ifndef MAX_EEPROMS
+ #error MAX_EEPROMS number must be defined (1-3)
+#endif
+
+#if (MAX_EEPROMS > 3)
+ #error Currently only a maximum of three EEPROMS is supported, add missing code around here: __FILE__:__LINE__
+#endif
+static int eeprom_open0(FAR struct file *filp);
+static int eeprom_close0(FAR struct file *filp);
+static ssize_t eeprom_read0(struct file *filp, FAR char *buffer, size_t buflen);
+static ssize_t eeprom_write0(struct file *filp, FAR const char *buffer, size_t buflen);
+static off_t eeprom_seek0(FAR struct file *filp, off_t offset, int whence);
+#if (MAX_EEPROMS > 1)
+static int eeprom_open1(FAR struct file *filp);
+static int eeprom_close1(FAR struct file *filp);
+static ssize_t eeprom_read1(struct file *filp, FAR char *buffer, size_t buflen);
+static ssize_t eeprom_write1(struct file *filp, FAR const char *buffer, size_t buflen);
+static off_t eeprom_seek1(FAR struct file *filp, off_t offset, int whence);
+#endif
+#if (MAX_EEPROMS > 2)
+static int eeprom_open2(FAR struct file *filp);
+static int eeprom_close2(FAR struct file *filp);
+static ssize_t eeprom_read2(struct file *filp, FAR char *buffer, size_t buflen);
+static ssize_t eeprom_write2(struct file *filp, FAR const char *buffer, size_t buflen);
+static off_t eeprom_seek2(FAR struct file *filp, off_t offset, int whence);
+#endif
+
+static const struct file_operations eeprom_fops[MAX_EEPROMS] = {{
+ .open = eeprom_open0,
+ .close = eeprom_close0,
+ .read = eeprom_read0,
+ .write = eeprom_write0,
+ .seek = eeprom_seek0,
+ .ioctl = 0,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+}
+#if (MAX_EEPROMS > 1)
+,{
+ .open = eeprom_open1,
+ .close = eeprom_close1,
+ .read = eeprom_read1,
+ .write = eeprom_write1,
+ .seek = eeprom_seek1,
+}
+#endif
+#if (MAX_EEPROMS > 2)
+,{
+ .open = eeprom_open2,
+ .close = eeprom_close2,
+ .read = eeprom_read2,
+ .write = eeprom_write2,
+ .seek = eeprom_seek2,
+}
+#endif
+};
+
+static FAR struct eeprom_dev_s
+{
+ struct i2c_dev_s *i2c;
+ uint8_t eeprom_address;
+ uint16_t eeprom_size_bytes;
+ uint16_t eeprom_page_size_bytes;
+ uint16_t eeprom_page_write_time;
+ off_t offset;
+ bool is_open;
+} eeprom_dev[MAX_EEPROMS];
+
+static int
+eeprom_open0(FAR struct file *filp)
+{
+ /* only allow one open at a time */
+ if (eeprom_dev[0].is_open) {
+ errno = EBUSY;
+ return -EBUSY;
+ }
+ /* reset pointer */
+ //eeprom_dev[0].is_open = true;
+ eeprom_dev[0].offset = 0;
+ return OK;
+}
+#if (MAX_EEPROMS > 1)
+static int
+eeprom_open1(FAR struct file *filp)
+{
+ /* only allow one open at a time */
+ if (eeprom_dev[1].is_open) {
+ errno = EBUSY;
+ return -EBUSY;
+ }
+ /* reset pointer */
+ //eeprom_dev[1].is_open = true;
+ eeprom_dev[1].offset = 0;
+ return OK;
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static int
+eeprom_open2(FAR struct file *filp)
+{
+ /* only allow one open at a time */
+ if (eeprom_dev[2].is_open) {
+ errno = EBUSY;
+ return -EBUSY;
+ }
+ /* reset pointer */
+ //eeprom_dev[2].is_open = true;
+ eeprom_dev[2].offset = 0;
+ return OK;
+}
+#endif
+
+static int
+eeprom_close0(FAR struct file *filp)
+{
+ eeprom_dev[0].is_open = false;
+ return OK;
+}
+#if (MAX_EEPROMS > 1)
+static int
+eeprom_close1(FAR struct file *filp)
+{
+ eeprom_dev[1].is_open = false;
+ return OK;
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static int
+eeprom_close2(FAR struct file *filp)
+{
+ eeprom_dev[2].is_open = false;
+ return OK;
+}
+#endif
+
+static int
+eeprom_read_internal(int dev, uint16_t len, uint8_t *data)
+{
+ /* abort if the number of requested bytes exceeds the EEPROM size */
+ if (eeprom_dev[dev].offset + len > eeprom_dev[dev].eeprom_size_bytes)
+ {
+ errno = ENOSPC;
+ return -ENOSPC;
+ }
+
+ /* set device address */
+ I2C_SETADDRESS(eeprom_dev[dev].i2c, eeprom_dev[dev].eeprom_address, 7);
+
+ uint8_t cmd[2] = {0, 0}; /* first (or only) part of address */
+ /* second part of address, omitted if eeprom has 256 bytes or less */
+ int ret = 0;
+ int remaining = len;
+ int readcounts = 0;
+
+ while (remaining > 0)
+ {
+ /* read all requested bytes over potentially multiple pages */
+ //int readlen = (remaining < eeprom_dev[dev].eeprom_page_size_bytes) ? remaining : eeprom_dev[dev].eeprom_page_size_bytes;
+ int read_offset = eeprom_dev[dev].offset + len - remaining;//+ write_counts*eeprom_dev[dev].eeprom_page_size_bytes;
+ /* set read length to page border */
+ int readlen = eeprom_dev[dev].eeprom_page_size_bytes - (read_offset % eeprom_dev[dev].eeprom_page_size_bytes);//(remaining < eeprom_dev[dev].eeprom_page_size_bytes) ? remaining : eeprom_dev[dev].eeprom_page_size_bytes;
+ /* cap read length if not a full page read is needed */
+ if (readlen > remaining) readlen = remaining;
+
+ if (eeprom_dev[dev].eeprom_size_bytes <= 256)
+ {
+ cmd[0] = (read_offset); /* set at first byte */
+ /* 8 bit addresses */
+ ret = I2C_WRITEREAD(eeprom_dev[dev].i2c, cmd, 1, (data+(readcounts*eeprom_dev[dev].eeprom_page_size_bytes)), readlen);
+ }
+ else
+ {
+ /* 16 bit addresses */
+ /* EEPROM: first address high, then address low */
+ cmd[0] = (((uint16_t)read_offset) >> 8);
+ cmd[1] = (((uint8_t)read_offset));
+ ret = I2C_WRITEREAD(eeprom_dev[dev].i2c, cmd, 2, (data+(readcounts*eeprom_dev[dev].eeprom_page_size_bytes)), readlen);
+ }
+
+ /* abort on error */
+ if (ret < 0) break;
+
+ /* handled another chunk */
+ remaining -= readlen;
+ readcounts++;
+ }
+
+ /* use the negated value from I2C_TRANSFER to fill errno */
+ errno = -ret;
+
+ /* return len if data was read, < 0 else */
+ if (ret == OK)
+ eeprom_dev[dev].offset += len;
+ return len;
+
+ /* no data, return negated value from I2C_TRANSFER */
+ return ret;
+}
+
+static int
+eeprom_write_internal(int dev, uint16_t len, const uint8_t *data)
+{
+ /* abort if the number of requested bytes exceeds the EEPROM size */
+ if (eeprom_dev[dev].offset + len > eeprom_dev[dev].eeprom_size_bytes)
+ {
+ errno = ENOSPC;
+ return -ENOSPC;
+ }
+
+ int ret = 0;
+ int remaining = len;
+ int write_counts = 0;
+
+ uint8_t write_buf[2];
+
+ while (remaining > 0)
+ {
+ /* write all requested bytes over potentially multiple pages */
+ int write_offset = eeprom_dev[dev].offset + len - remaining;//+ write_counts*eeprom_dev[dev].eeprom_page_size_bytes;
+ /* set write length to page border */
+ int writelen = eeprom_dev[dev].eeprom_page_size_bytes - (write_offset % eeprom_dev[dev].eeprom_page_size_bytes);//(remaining < eeprom_dev[dev].eeprom_page_size_bytes) ? remaining : eeprom_dev[dev].eeprom_page_size_bytes;
+ /* cap write length if not a full page write is requested */
+ if (writelen > remaining) writelen = remaining;
+
+ if (eeprom_dev[dev].eeprom_size_bytes <= 256)
+ {
+ write_buf[0] = (write_offset); /* set at first byte */
+ /* 8 bit addresses */
+
+ const uint8_t* data_ptr = (data+(write_offset));
+
+ struct i2c_msg_s msgv_eeprom_write[2] = {
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = write_buf,
+ .length = 1
+ },
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = (uint8_t*)data_ptr,
+ .length = writelen
+ }
+ };
+
+
+ if ( (ret = I2C_TRANSFER(eeprom_dev[dev].i2c, msgv_eeprom_write, 2)) == OK )
+ {
+ //printf("SUCCESS WRITING EEPROM 8BIT ADDR: %d, bytes: %d\n", ret, writelen);
+ }
+ }
+ else
+ {
+ /* 16 bit addresses */
+ /* EEPROM: first address high, then address low */
+ write_buf[0] = (((uint16_t)write_offset) >> 8);
+ write_buf[1] = (((uint8_t)write_offset));
+
+ const uint8_t* data_ptr = data+(write_counts*eeprom_dev[dev].eeprom_page_size_bytes);
+
+ struct i2c_msg_s msgv_eeprom_write[2] = {
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = write_buf,
+ .length = 2
+ },
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = (uint8_t*)data_ptr,
+ .length = writelen
+ }
+ };
+
+
+ if ( (ret = I2C_TRANSFER(eeprom_dev[dev].i2c, msgv_eeprom_write, 2)) == OK )
+ {
+ //printf("SUCCESS WRITING EEPROM 16BIT ADDR: %d, bytes: %d\n", ret, writelen);
+ }
+ }
+
+ /* abort on error */
+ if (ret < 0) break;
+
+ /* handled another chunk */
+ remaining -= writelen;
+ write_counts++;
+ /* wait for the device to write the page */
+ usleep(eeprom_dev[dev].eeprom_page_write_time);
+ }
+
+ /* use the negated value from I2C_TRANSFER to fill errno */
+ errno = -ret;
+
+ /* return length if data was written, < 0 else */
+ if (ret == OK)
+ eeprom_dev[dev].offset += len;
+ return len;
+
+ /* no data, return negated value from I2C_TRANSFER */
+ return ret;
+}
+
+static ssize_t
+eeprom_read0(struct file *filp, char *buffer, size_t buflen)
+{
+ return eeprom_read_internal(0, buflen, (uint8_t *)buffer);
+}
+#if (MAX_EEPROMS > 1)
+static ssize_t
+eeprom_read1(struct file *filp, char *buffer, size_t buflen)
+{
+ return eeprom_read_internal(1, buflen, (uint8_t *)buffer);
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static ssize_t
+eeprom_read2(struct file *filp, char *buffer, size_t buflen)
+{
+ return eeprom_read_internal(2, buflen, (uint8_t *)buffer);
+}
+#endif
+
+static ssize_t
+eeprom_write0(struct file *filp, const char *buffer, size_t buflen)
+{
+ return eeprom_write_internal(0, buflen, (const uint8_t *)buffer);
+}
+#if (MAX_EEPROMS > 1)
+static ssize_t
+eeprom_write1(struct file *filp, const char *buffer, size_t buflen)
+{
+ return eeprom_write_internal(1, buflen, (const uint8_t *)buffer);
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static ssize_t
+eeprom_write2(struct file *filp, const char *buffer, size_t buflen)
+{
+ return eeprom_write_internal(2, buflen, (const uint8_t *)buffer);
+}
+#endif
+
+static off_t eeprom_seek0(FAR struct file *filp, off_t offset, int whence)
+{
+ switch (whence)
+ {
+ case SEEK_SET:
+ if (offset < eeprom_dev[0].eeprom_size_bytes - 1) {
+ eeprom_dev[0].offset = offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_CUR:
+ if (eeprom_dev[0].offset + offset < eeprom_dev[0].eeprom_size_bytes - 1) {
+ eeprom_dev[0].offset = eeprom_dev[0].offset + offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_END:
+ errno = ESPIPE;
+ return -ESPIPE;
+ break;
+ }
+ return eeprom_dev[0].offset;
+}
+#if (MAX_EEPROMS > 1)
+static off_t eeprom_seek1(FAR struct file *filp, off_t offset, int whence)
+{
+ switch (whence)
+ {
+ case SEEK_SET:
+ if (offset < eeprom_dev[1].eeprom_size_bytes - 1) {
+ eeprom_dev[1].offset = offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_CUR:
+ if (eeprom_dev[1].offset + offset < eeprom_dev[1].eeprom_size_bytes - 1) {
+ eeprom_dev[1].offset = eeprom_dev[1].offset + offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_END:
+ errno = ESPIPE;
+ return -ESPIPE;
+ break;
+ }
+ return eeprom_dev[1].offset;
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static off_t eeprom_seek2(FAR struct file *filp, off_t offset, int whence)
+{
+ switch (whence)
+ {
+ case SEEK_SET:
+ if (offset < eeprom_dev[2].eeprom_size_bytes - 1) {
+ eeprom_dev[2].offset = offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_CUR:
+ if (eeprom_dev[2].offset + offset < eeprom_dev[2].eeprom_size_bytes - 1) {
+ eeprom_dev[2].offset = eeprom_dev[2].offset + offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_END:
+ errno = ESPIPE;
+ return -ESPIPE;
+ break;
+ }
+ return eeprom_dev[2].offset;
+}
+#endif
+
+int
+eeprom_attach(struct i2c_dev_s *i2c, uint8_t device_address, uint16_t total_size_bytes, uint16_t page_size_bytes, uint16_t page_write_time_us, const char* device_name, uint8_t fail_if_missing)
+{
+ static int eeprom_dev_counter = 0;
+ eeprom_dev[eeprom_dev_counter].i2c = i2c;
+ eeprom_dev[eeprom_dev_counter].eeprom_address = device_address;
+ eeprom_dev[eeprom_dev_counter].eeprom_size_bytes = total_size_bytes;
+ eeprom_dev[eeprom_dev_counter].eeprom_page_size_bytes = page_size_bytes;
+ eeprom_dev[eeprom_dev_counter].eeprom_page_write_time = page_write_time_us;
+ eeprom_dev[eeprom_dev_counter].offset = 0;
+ eeprom_dev[eeprom_dev_counter].is_open = false;
+
+ int ret;
+
+ if (fail_if_missing) {
+ /* read first value */
+ uint8_t read_test;
+ ret = (eeprom_read_internal(eeprom_dev_counter, 1, &read_test) == 1) ? OK : ERROR;
+ } else {
+ ret = OK;
+ }
+
+ /* make ourselves available */
+ if (ret == OK)
+ {
+ register_driver(device_name, &(eeprom_fops[eeprom_dev_counter]), 0666, NULL);
+ eeprom_dev_counter++;
+ }
+
+ /* Return 0 for device found, error number else */
+ return ret;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_gpio.c b/nuttx/configs/px4fmu/src/drv_gpio.c
new file mode 100644
index 000000000..be95420dd
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_gpio.c
@@ -0,0 +1,195 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/*
+ * GPIO driver for PX4FMU.
+ *
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_gpio.h>
+
+static int px4fmu_gpio_ioctl(struct file *filep, int cmd, unsigned long arg);
+
+static const struct file_operations px4fmu_gpio_fops = {
+ .ioctl = px4fmu_gpio_ioctl,
+};
+
+static struct {
+ uint32_t input;
+ uint32_t output;
+ uint32_t alt;
+} gpio_tab[] = {
+ {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
+ {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
+ {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
+ {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1},
+ {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1},
+ {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1},
+ {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
+ {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
+};
+
+#define NGPIO (sizeof(gpio_tab) / sizeof(gpio_tab[0]))
+
+
+static void
+px4fmu_gpio_reset(void)
+{
+ /*
+ * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
+ * to input mode.
+ */
+ for (unsigned i = 0; i < NGPIO; i++)
+ stm32_configgpio(gpio_tab[i].input);
+
+ stm32_gpiowrite(GPIO_GPIO_DIR, 0);
+ stm32_configgpio(GPIO_GPIO_DIR);
+}
+
+static void
+px4fmu_gpio_set_function(uint32_t gpios, int function)
+{
+ /*
+ * GPIOs 0 and 1 must have the same direction as they are buffered
+ * by a shared 2-port driver. Any attempt to set either sets both.
+ */
+ if (gpios & 3) {
+ gpios |= 3;
+
+ /* flip the buffer to output mode if required */
+ if (GPIO_SET_OUTPUT == function)
+ stm32_gpiowrite(GPIO_GPIO_DIR, 1);
+ }
+
+ /* configure selected GPIOs as required */
+ for (unsigned i = 0; i < NGPIO; i++) {
+ if (gpios & (1<<i)) {
+ switch (function) {
+ case GPIO_SET_INPUT:
+ stm32_configgpio(gpio_tab[i].input);
+ break;
+ case GPIO_SET_OUTPUT:
+ stm32_configgpio(gpio_tab[i].output);
+ break;
+ case GPIO_SET_ALT_1:
+ if (gpio_tab[i].alt != 0)
+ stm32_configgpio(gpio_tab[i].alt);
+ break;
+ }
+ }
+ }
+
+ /* flip buffer to input mode if required */
+ if ((GPIO_SET_INPUT == function) && (gpios & 3))
+ stm32_gpiowrite(GPIO_GPIO_DIR, 0);
+}
+
+static void
+px4fmu_gpio_write(uint32_t gpios, int function)
+{
+ int value = (function == GPIO_SET) ? 1 : 0;
+
+ for (unsigned i = 0; i < NGPIO; i++)
+ if (gpios & (1<<i))
+ stm32_gpiowrite(gpio_tab[i].output, value);
+}
+
+static uint32_t
+px4fmu_gpio_read(void)
+{
+ uint32_t bits = 0;
+
+ for (unsigned i = 0; i < NGPIO; i++)
+ if (stm32_gpioread(gpio_tab[i].input))
+ bits |= (1 << i);
+
+ return bits;
+}
+
+void
+px4fmu_gpio_init(void)
+{
+ /* reset all GPIOs to default state */
+ px4fmu_gpio_reset();
+
+ /* register the driver */
+ register_driver(GPIO_DEVICE_PATH, &px4fmu_gpio_fops, 0666, NULL);
+}
+
+static int
+px4fmu_gpio_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ int result = OK;
+
+ switch (cmd) {
+
+ case GPIO_RESET:
+ px4fmu_gpio_reset();
+ break;
+
+ case GPIO_SET_OUTPUT:
+ case GPIO_SET_INPUT:
+ case GPIO_SET_ALT_1:
+ px4fmu_gpio_set_function(arg, cmd);
+ break;
+
+ case GPIO_SET:
+ case GPIO_CLEAR:
+ px4fmu_gpio_write(arg, cmd);
+ break;
+
+ case GPIO_GET:
+ *(uint32_t *)arg = px4fmu_gpio_read();
+ break;
+
+ default:
+ result = -ENOTTY;
+ }
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_hmc5833l.c b/nuttx/configs/px4fmu/src/drv_hmc5833l.c
new file mode 100644
index 000000000..0e6dbe2ac
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_hmc5833l.c
@@ -0,0 +1,352 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Honeywell/ST HMC5883L MEMS magnetometer
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/i2c.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_hmc5883l.h>
+
+#define ADDR_CONF_A 0x00
+#define ADDR_CONF_B 0x01
+#define ADDR_MODE 0x02
+#define ADDR_DATA_OUT_X_MSB 0x03
+#define ADDR_DATA_OUT_X_LSB 0x04
+#define ADDR_DATA_OUT_Z_MSB 0x05
+#define ADDR_DATA_OUT_Z_LSB 0x06
+#define ADDR_DATA_OUT_Y_MSB 0x07
+#define ADDR_DATA_OUT_Y_LSB 0x08
+#define ADDR_STATUS 0x09
+#define ADDR_ID_A 0x10
+#define ADDR_ID_B 0x11
+#define ADDR_ID_C 0x12
+
+#define HMC5883L_ADDRESS 0x1E
+
+/* modes not changeable outside of driver */
+#define HMC5883L_MODE_NORMAL (0 << 0) /* default */
+#define HMC5883L_MODE_POSITIVE_BIAS (1 << 0) /* positive bias */
+#define HMC5883L_MODE_NEGATIVE_BIAS (1 << 1) /* negative bias */
+
+#define HMC5883L_AVERAGING_1 (0 << 5) /* conf a register */
+#define HMC5883L_AVERAGING_2 (1 << 5)
+#define HMC5883L_AVERAGING_4 (2 << 5)
+#define HMC5883L_AVERAGING_8 (3 << 5)
+
+#define MODE_REG_CONTINOUS_MODE (0 << 0)
+#define MODE_REG_SINGLE_MODE (1 << 0) /* default */
+
+#define STATUS_REG_DATA_OUT_LOCK (1 << 1) /* page 16: set if data is only partially read, read device to reset */
+#define STATUS_REG_DATA_READY (1 << 0) /* page 16: set if all axes have valid measurements */
+
+#define ID_A_WHO_AM_I 'H'
+#define ID_B_WHO_AM_I '4'
+#define ID_C_WHO_AM_I '3'
+
+static FAR struct hmc5883l_dev_s hmc5883l_dev;
+
+static ssize_t hmc5883l_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int hmc5883l_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations hmc5883l_fops = {
+ .open = 0,
+ .close = 0,
+ .read = hmc5883l_read,
+ .write = 0,
+ .seek = 0,
+ .ioctl = hmc5883l_ioctl,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+};
+
+struct hmc5883l_dev_s
+{
+ struct i2c_dev_s *i2c;
+ uint8_t rate;
+ struct hmc5883l_buffer *buffer;
+};
+
+static int hmc5883l_write_reg(uint8_t address, uint8_t data);
+static int hmc5883l_read_reg(uint8_t address);
+static int hmc5883l_reset(void);
+
+static int
+hmc5883l_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[] = {address, data};
+ return I2C_WRITE(hmc5883l_dev.i2c, cmd, 2);
+}
+
+static int
+hmc5883l_read_reg(uint8_t address)
+{
+ uint8_t cmd = address;
+ uint8_t data;
+
+ int ret = I2C_WRITEREAD(hmc5883l_dev.i2c, &cmd, 1, &data, 1);
+ /* return data on success, error code on failure */
+ if (ret == OK) {
+ ret = data;
+ }
+ return ret;
+}
+
+static int
+hmc5883l_set_range(uint8_t range)
+{
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+
+
+ /* mask out illegal bit positions */
+ uint8_t write_range = range; //& REG4_RANGE_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_range != range) return EINVAL;
+ /* set remaining bits to a sane value */
+// write_range |= REG4_BDU;
+ /* write to device */
+ hmc5883l_write_reg(ADDR_CONF_B, write_range);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(hmc5883l_read_reg(ADDR_CONF_B) == write_range);
+}
+
+static int
+hmc5883l_set_rate(uint8_t rate)
+{
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+ /* mask out illegal bit positions */
+ uint8_t write_rate = rate;// & REG1_RATE_LP_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_rate != rate) return EINVAL;
+ /* set remaining bits to a sane value */
+// write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
+ write_rate |= HMC5883L_AVERAGING_8;
+ /* write to device */
+ hmc5883l_write_reg(ADDR_CONF_A, write_rate);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(hmc5883l_read_reg(ADDR_CONF_A) == write_rate);
+}
+
+static bool
+read_values(int16_t *data)
+{
+ struct { /* status register and data as read back from the device */
+ int16_t x;
+ int16_t z;
+ int16_t y;
+ uint8_t status;
+ } __attribute__((packed)) hmc_report;
+ hmc_report.status = 0;
+
+ static int read_err_count = 0;
+
+ /* exchange the report structure with the device */
+
+ uint8_t cmd = ADDR_DATA_OUT_X_MSB;
+
+ int ret = 0;
+
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+
+ /* set device into single mode, trigger next measurement */
+ ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
+
+ /* Only execute consecutive steps on success */
+ if (ret == OK)
+ {
+ cmd = ADDR_DATA_OUT_X_MSB;
+ ret = I2C_WRITEREAD(hmc5883l_dev.i2c, &cmd, 1, (uint8_t*)&hmc_report, 6);
+ if (ret == OK)
+ {
+ /* Six bytes to read, stop if timed out */
+ int hmc_status = hmc5883l_read_reg(ADDR_STATUS);
+ if (hmc_status < 0)
+ {
+ if (ret == ETIMEDOUT) hmc5883l_reset();
+ ret = hmc_status;
+ }
+ else
+ {
+ hmc_report.status = hmc_status;
+ ret = OK;
+ }
+ }
+ else
+ {
+ if (ret == ETIMEDOUT) hmc5883l_reset();
+ }
+ }
+ else
+ {
+ if (ret == ETIMEDOUT) hmc5883l_reset();
+ }
+
+ if (ret != OK)
+ {
+ read_err_count++;
+ /* If the last reads failed as well, reset the bus and chip */
+ if (read_err_count > 3) hmc5883l_reset();
+
+ *get_errno_ptr() = -ret;
+ } else {
+ read_err_count = 0;
+ /* write values, and exchange the two 8bit blocks (big endian to little endian) */
+ data[0] = ((hmc_report.x & 0x00FF) << 8) | ((hmc_report.x & 0xFF00) >> 8);
+ data[1] = ((hmc_report.y & 0x00FF) << 8) | ((hmc_report.y & 0xFF00) >> 8);
+ data[2] = ((hmc_report.z & 0x00FF) << 8) | ((hmc_report.z & 0xFF00) >> 8);
+ if ((hmc_report.status & STATUS_REG_DATA_READY) > 0)
+ {
+ ret = 6;
+ } else {
+ ret = -EAGAIN;
+ }
+ }
+
+ /* return len if new data is available, error else. hmc_report.status is 0 on errors */
+ return ret;
+}
+
+static ssize_t
+hmc5883l_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ return read_values((int16_t *)buffer);
+ }
+
+ /* buffer too small */
+ *get_errno_ptr() = ENOSPC;
+ return -ERROR;
+}
+
+static int
+hmc5883l_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case HMC5883L_SETRATE:
+ result = hmc5883l_set_rate(arg);
+ break;
+
+ case HMC5883L_SETRANGE:
+ result = hmc5883l_set_range(arg);
+ break;
+//
+// case HMC5883L_SETBUFFER:
+// hmc5883l_dev.buffer = (struct hmc5883l_buffer *)arg;
+// result = 0;
+// break;
+
+ case HMC5883L_RESET:
+ result = hmc5883l_reset();
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int hmc5883l_reset()
+{
+ int ret;
+ printf("[hmc5883l drv] Resettet I2C2 BUS\n");
+ up_i2cuninitialize(hmc5883l_dev.i2c);
+ hmc5883l_dev.i2c = up_i2cinitialize(2);
+ I2C_SETFREQUENCY(hmc5883l_dev.i2c, 400000);
+ // up_i2creset(hmc5883l_dev.i2c);
+ //I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+ //hmc5883l_set_range(HMC5883L_RANGE_0_88GA);
+ //hmc5883l_set_rate(HMC5883L_RATE_75HZ);
+ /* set device into single mode, start measurement */
+ //ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
+ return ret;
+}
+
+int
+hmc5883l_attach(struct i2c_dev_s *i2c)
+{
+ int result = ERROR;
+
+ hmc5883l_dev.i2c = i2c;
+
+// I2C_LOCK(hmc5883l_dev.i2c, true);
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+
+ uint8_t cmd = ADDR_STATUS;
+ uint8_t status_id[4] = {0, 0, 0, 0};
+
+
+ int ret = I2C_WRITEREAD(i2c, &cmd, 1, status_id, 4);
+
+ /* verify that the device is attached and functioning */
+ if ((ret >= 0) && (status_id[1] == ID_A_WHO_AM_I) && (status_id[2] == ID_B_WHO_AM_I) && (status_id[3] == ID_C_WHO_AM_I)) {
+
+ /* set update rate to 75 Hz */
+ /* set 0.88 Ga range */
+ if ((ret != 0) || (hmc5883l_set_range(HMC5883L_RANGE_0_88GA) != 0) ||
+ (hmc5883l_set_rate(HMC5883L_RATE_75HZ) != 0))
+ {
+ errno = EIO;
+ } else {
+
+ /* set device into single mode, start measurement */
+ ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
+
+ /* make ourselves available */
+ register_driver("/dev/hmc5883l", &hmc5883l_fops, 0666, NULL);
+
+ result = 0;
+ }
+
+ } else {
+ errno = EIO;
+ }
+
+
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_l3gd20.c b/nuttx/configs/px4fmu/src/drv_l3gd20.c
new file mode 100644
index 000000000..1c6c05449
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_l3gd20.c
@@ -0,0 +1,364 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the ST L3GD20 MEMS gyroscope
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+#include <nuttx/arch.h>
+#include <arch/board/drv_l3gd20.h>
+
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define ADDR_WHO_AM_I 0x0F
+#define WHO_I_AM 0xD4
+#define ADDR_CTRL_REG1 0x20
+#define ADDR_CTRL_REG2 0x21
+#define ADDR_CTRL_REG3 0x22
+#define ADDR_CTRL_REG4 0x23
+#define ADDR_CTRL_REG5 0x24
+#define ADDR_REFERENCE 0x25
+#define ADDR_OUT_TEMP 0x26
+#define ADDR_STATUS_REG 0x27
+#define ADDR_OUT_X_L 0x28
+#define ADDR_OUT_X_H 0x29
+#define ADDR_OUT_Y_L 0x2A
+#define ADDR_OUT_Y_H 0x2B
+#define ADDR_OUT_Z_L 0x2C
+#define ADDR_OUT_Z_H 0x2D
+#define ADDR_FIFO_CTRL_REG 0x2E
+#define ADDR_FIFO_SRC_REG 0x2F
+#define ADDR_INT1_CFG 0x30
+#define ADDR_INT1_SRC 0x31
+#define ADDR_INT1_TSH_XH 0x32
+#define ADDR_INT1_TSH_XL 0x33
+#define ADDR_INT1_TSH_YH 0x34
+#define ADDR_INT1_TSH_YL 0x35
+#define ADDR_INT1_TSH_ZH 0x36
+#define ADDR_INT1_TSH_ZL 0x37
+#define ADDR_INT1_DURATION 0x38
+
+#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
+#define REG4_RANGE_MASK 0x30 /* Mask to guard partial register update */
+
+/* Internal configuration values */
+#define REG1_POWER_NORMAL (1<<3)
+#define REG1_Z_ENABLE (1<<2)
+#define REG1_Y_ENABLE (1<<1)
+#define REG1_X_ENABLE (1<<0)
+
+#define REG4_BDU (1<<7)
+#define REG4_BLE (1<<6)
+//#define REG4_SPI_3WIRE (1<<0)
+
+#define REG5_FIFO_ENABLE (1<<6)
+#define REG5_REBOOT_MEMORY (1<<7)
+
+#define STATUS_ZYXOR (1<<7)
+#define STATUS_ZOR (1<<6)
+#define STATUS_YOR (1<<5)
+#define STATUS_XOR (1<<4)
+#define STATUS_ZYXDA (1<<3)
+#define STATUS_ZDA (1<<2)
+#define STATUS_YDA (1<<1)
+#define STATUS_XDA (1<<0)
+
+#define FIFO_CTRL_BYPASS_MODE (0<<5)
+#define FIFO_CTRL_FIFO_MODE (1<<5)
+#define FIFO_CTRL_STREAM_MODE (1<<6)
+#define FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
+#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
+
+static FAR struct l3gd20_dev_s l3gd20_dev;
+
+static ssize_t l3gd20_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int l3gd20_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations l3gd20_fops = {
+ .open = 0,
+ .close = 0,
+ .read = l3gd20_read,
+ .write = 0,
+ .seek = 0,
+ .ioctl = l3gd20_ioctl,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+};
+
+struct l3gd20_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+ uint8_t rate;
+ struct l3gd20_buffer *buffer;
+};
+
+static void l3gd20_write_reg(uint8_t address, uint8_t data);
+static uint8_t l3gd20_read_reg(uint8_t address);
+
+static void
+l3gd20_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, true);
+ SPI_SNDBLOCK(l3gd20_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, false);
+}
+
+static uint8_t
+l3gd20_read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, true);
+ SPI_EXCHANGE(l3gd20_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, false);
+
+ return data[1];
+}
+
+static int
+set_range(uint8_t range)
+{
+ /* mask out illegal bit positions */
+ uint8_t write_range = range & REG4_RANGE_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_range != range) return EINVAL;
+ /* set remaining bits to a sane value */
+ write_range |= REG4_BDU;
+ /* write to device */
+ l3gd20_write_reg(ADDR_CTRL_REG4, write_range);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(l3gd20_read_reg(ADDR_CTRL_REG4) == write_range);
+}
+
+static int
+set_rate(uint8_t rate)
+{
+ /* mask out illegal bit positions */
+ uint8_t write_rate = rate & REG1_RATE_LP_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_rate != rate) return EINVAL;
+ /* set remaining bits to a sane value */
+ write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
+ /* write to device */
+ l3gd20_write_reg(ADDR_CTRL_REG1, write_rate);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(l3gd20_read_reg(ADDR_CTRL_REG1) == write_rate);
+}
+
+static int
+read_fifo(int16_t *data)
+{
+
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t temp;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } __attribute__((packed)) report = {.status = 11};
+
+ report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
+
+ SPI_LOCK(l3gd20_dev.spi, true);
+ SPI_SELECT(l3gd20_dev.spi, PX4_SPIDEV_GYRO, true);
+ SPI_SETFREQUENCY(l3gd20_dev.spi, 25000000);
+
+ SPI_EXCHANGE(l3gd20_dev.spi, &report, &report, sizeof(report));
+
+ /* XXX if the status value is unchanged, attempt a second exchange */
+ if (report.status == 11) SPI_EXCHANGE(l3gd20_dev.spi, &report, &report, sizeof(report));
+ /* XXX set magic error value if this still didn't succeed */
+ if (report.status == 11) report.status = 12;
+
+ SPI_SETFREQUENCY(l3gd20_dev.spi, 10000000);
+ SPI_SELECT(l3gd20_dev.spi, PX4_SPIDEV_GYRO, false);
+ SPI_LOCK(l3gd20_dev.spi, false);
+
+ data[0] = report.x;
+ data[1] = report.y;
+ data[2] = report.z;
+
+ /* if all axes are valid, return buflen (6), else return negative status */
+ int ret = -((int)report.status);
+ if (STATUS_ZYXDA == (report.status & STATUS_ZYXDA) || STATUS_ZYXOR == (report.status & STATUS_ZYXOR))
+ {
+ ret = 6;
+ }
+
+ return ret;
+}
+
+static ssize_t
+l3gd20_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ /* return buflen or a negative value */
+ int ret = read_fifo((int16_t *)buffer);
+ if (ret != 6) *get_errno_ptr() = EAGAIN;
+ return ret;
+ }
+
+ /* buffer too small */
+ *get_errno_ptr() = ENOSPC;
+ return ERROR;
+}
+
+static int
+l3gd20_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case L3GD20_SETRATE:
+ if ((arg & REG1_RATE_LP_MASK) == arg) {
+ SPI_LOCK(l3gd20_dev.spi, true);
+ set_rate(arg);
+ SPI_LOCK(l3gd20_dev.spi, false);
+ result = 0;
+ l3gd20_dev.rate = arg;
+ }
+ break;
+
+ case L3GD20_SETRANGE:
+ if ((arg & REG4_RANGE_MASK) == arg) {
+ SPI_LOCK(l3gd20_dev.spi, true);
+ set_range(arg);
+ SPI_LOCK(l3gd20_dev.spi, false);
+ result = 0;
+ }
+ break;
+
+ case L3GD20_SETBUFFER:
+ l3gd20_dev.buffer = (struct l3gd20_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+l3gd20_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ l3gd20_dev.spi = spi;
+ l3gd20_dev.spi_id = spi_id;
+
+ SPI_LOCK(l3gd20_dev.spi, true);
+ /* read dummy value to void to clear SPI statemachine on sensor */
+ (void)l3gd20_read_reg(ADDR_WHO_AM_I);
+
+ /* verify that the device is attached and functioning */
+ if (l3gd20_read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
+
+ /* reset device memory */
+ //l3gd20_write_reg(ADDR_CTRL_REG5, REG5_REBOOT_MEMORY);
+ //up_udelay(1000);
+
+ /* set default configuration */
+ l3gd20_write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
+ l3gd20_write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
+ l3gd20_write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
+ l3gd20_write_reg(ADDR_CTRL_REG4, 0x10);
+ l3gd20_write_reg(ADDR_CTRL_REG5, 0);
+
+ l3gd20_write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
+ l3gd20_write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */
+
+ if ((set_range(L3GD20_RANGE_500DPS) != 0) ||
+ (set_rate(L3GD20_RATE_760HZ_LP_100HZ) != 0)) /* takes device out of low-power mode */
+ {
+ errno = EIO;
+ } else {
+ /* Read out the first few funky values */
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t temp;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } __attribute__((packed)) report;
+
+ report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
+
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
+ SPI_EXCHANGE(spi, &report, &report, sizeof(report));
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
+ up_udelay(500);
+ /* And read another set */
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
+ SPI_EXCHANGE(spi, &report, &report, sizeof(report));
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
+
+
+ /* make ourselves available */
+ register_driver("/dev/l3gd20", &l3gd20_fops, 0666, NULL);
+
+ result = 0;
+ }
+
+ } else {
+
+ errno = EIO;
+ }
+
+ SPI_LOCK(l3gd20_dev.spi, false);
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_led.c b/nuttx/configs/px4fmu/src/drv_led.c
new file mode 100644
index 000000000..13d8eb22a
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_led.c
@@ -0,0 +1,113 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/*
+ * led driver for PX4FMU
+ *
+ * This is something of an experiment currently (ha, get it?)
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_led.h>
+
+static int px4fmu_led_ioctl(struct file *filep, int cmd, unsigned long arg);
+static ssize_t px4fmu_led_pseudoread(struct file *filp, FAR char *buffer, size_t buflen);
+
+static const struct file_operations px4fmu_led_fops = {
+ .read = px4fmu_led_pseudoread,
+ .ioctl = px4fmu_led_ioctl,
+};
+
+int
+px4fmu_led_init(void)
+{
+ /* register the driver */
+ return register_driver("/dev/led", &px4fmu_led_fops, 0666, NULL);
+}
+
+static ssize_t
+px4fmu_led_pseudoread(struct file *filp, FAR char *buffer, size_t buflen)
+{
+ return 0;
+}
+
+static int
+px4fmu_led_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ int result = 0;
+
+ switch (cmd) {
+
+ case LED_ON:
+ switch (arg) {
+ case 0:
+ case 1:
+ up_ledon(arg);
+ break;
+ default:
+ result = -1;
+ break;
+ }
+ break;
+
+ case LED_OFF:
+ switch (arg) {
+ case 0:
+ case 1:
+ up_ledoff(arg);
+ break;
+ default:
+ result = -1;
+ break;
+ }
+ break;
+ default:
+ result = -1;
+ break;
+ }
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_lis331.c b/nuttx/configs/px4fmu/src/drv_lis331.c
new file mode 100644
index 000000000..fd477b46f
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_lis331.c
@@ -0,0 +1,272 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the ST LIS331 MEMS accelerometer
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_lis331.h>
+
+/*
+ * LIS331 registers
+ */
+
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define ADDR_WHO_AM_I 0x0f
+#define WHO_I_AM 0x32
+
+#define ADDR_CTRL_REG1 0x20 /* sample rate constants are in the public header */
+#define REG1_POWER_NORMAL (1<<5)
+#define REG1_RATE_MASK (3<<3)
+#define REG1_Z_ENABLE (1<<2)
+#define REG1_Y_ENABLE (1<<1)
+#define REG1_X_ENABLE (1<<0)
+
+#define ADDR_CTRL_REG2 0x21
+
+#define ADDR_CTRL_REG3 0x22
+
+#define ADDR_CTRL_REG4 0x23
+#define REG4_BDU (1<<7)
+#define REG4_BIG_ENDIAN (1<<6)
+#define REG4_RANGE_MASK (3<<4)
+#define REG4_SPI_3WIRE (1<<0)
+
+#define ADDR_CTRL_REG5 0x24
+
+#define ADDR_HP_FILTER_RESET 0x25
+#define ADDR_REFERENCE 0x26
+#define ADDR_STATUS_REG 0x27
+#define STATUS_ZYXOR (1<<7)
+#define STATUS_ZOR (1<<6)
+#define STATUS_YOR (1<<5)
+#define STATUS_XOR (1<<4)
+#define STATUS_ZYXDA (1<<3)
+#define STATUS_ZDA (1<<2)
+#define STATUS_YDA (1<<1)
+#define STATUS_XDA (1<<0)
+
+#define ADDR_OUT_X 0x28 /* 16 bits */
+#define ADDR_OUT_Y 0x2A /* 16 bits */
+#define ADDR_OUT_Z 0x2C /* 16 bits */
+
+
+static ssize_t lis331_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int lis331_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations lis331_fops = {
+ .read = lis331_read,
+ .ioctl = lis331_ioctl,
+};
+
+struct lis331_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+
+ uint8_t rate;
+ struct lis331_buffer *buffer;
+};
+
+static struct lis331_dev_s lis331_dev;
+
+static void write_reg(uint8_t address, uint8_t data);
+static uint8_t read_reg(uint8_t address);
+static bool read_fifo(uint16_t *data);
+static void set_range(uint8_t range);
+static void set_rate(uint8_t rate);
+
+static void
+write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
+ SPI_SNDBLOCK(lis331_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
+}
+
+static uint8_t
+read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
+ SPI_EXCHANGE(lis331_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
+
+ return data[1];
+}
+
+static bool
+read_fifo(uint16_t *data)
+{
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } __attribute__((packed)) report;
+
+ report.cmd = ADDR_STATUS_REG | DIR_READ | ADDR_INCREMENT;
+
+ /* exchange the report structure with the device */
+ SPI_LOCK(lis331_dev.spi, true);
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
+ SPI_EXCHANGE(lis331_dev.spi, &report, &report, sizeof(report));
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
+ SPI_LOCK(lis331_dev.spi, false);
+
+ data[0] = report.x;
+ data[1] = report.y;
+ data[2] = report.z;
+
+ return report.status & STATUS_ZYXDA;
+}
+
+static void
+set_range(uint8_t range)
+{
+ range &= REG4_RANGE_MASK;
+ write_reg(ADDR_CTRL_REG4, range | REG4_BDU);
+}
+
+static void
+set_rate(uint8_t rate)
+{
+ rate &= REG1_RATE_MASK;
+ write_reg(ADDR_CTRL_REG1, rate | REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
+}
+
+static ssize_t
+lis331_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 12) {
+ if (read_fifo((uint16_t *)buffer))
+ return 12;
+
+ /* no data */
+ return 0;
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return ERROR;
+}
+
+static int
+lis331_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case LIS331_SETRATE:
+ if ((arg & REG1_RATE_MASK) == arg) {
+ set_rate(arg);
+ result = 0;
+ lis331_dev.rate = arg;
+ }
+ break;
+
+ case LIS331_SETRANGE:
+ if ((arg & REG4_RANGE_MASK) == arg) {
+ set_range(arg);
+ result = 0;
+ }
+ break;
+
+ case LIS331_SETBUFFER:
+ lis331_dev.buffer = (struct lis331_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+lis331_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ lis331_dev.spi = spi;
+
+ SPI_LOCK(lis331_dev.spi, true);
+
+ /* verify that the device is attached and functioning */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
+
+ /* set default configuration */
+ write_reg(ADDR_CTRL_REG2, 0); /* disable interrupt-generating high-pass filters */
+ write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
+ write_reg(ADDR_CTRL_REG5, 0); /* disable wake-on-interrupt */
+
+ set_range(LIS331_RANGE_4G);
+ set_rate(LIS331_RATE_400Hz); /* takes device out of low-power mode */
+
+ /* make ourselves available */
+ register_driver("/dev/lis331", &lis331_fops, 0666, NULL);
+
+ result = 0;
+ } else {
+ errno = EIO;
+ }
+
+ SPI_LOCK(lis331_dev.spi, false);
+
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_mpu6000.c b/nuttx/configs/px4fmu/src/drv_mpu6000.c
new file mode 100644
index 000000000..47f655563
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_mpu6000.c
@@ -0,0 +1,411 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the ST mpu6000 MEMS gyroscope
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+#include <stdio.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+#include <nuttx/arch.h>
+
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_mpu6000.h>
+
+#define DIR_READ (0x80)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define WHO_I_AM 0xD4
+
+// MPU 6000 registers
+#define MPUREG_WHOAMI 0x75 //
+#define MPUREG_SMPLRT_DIV 0x19 //
+#define MPUREG_CONFIG 0x1A //
+#define MPUREG_GYRO_CONFIG 0x1B
+#define MPUREG_ACCEL_CONFIG 0x1C
+#define MPUREG_FIFO_EN 0x23
+#define MPUREG_INT_PIN_CFG 0x37
+#define MPUREG_INT_ENABLE 0x38
+#define MPUREG_INT_STATUS 0x3A
+#define MPUREG_ACCEL_XOUT_H 0x3B //
+#define MPUREG_ACCEL_XOUT_L 0x3C //
+#define MPUREG_ACCEL_YOUT_H 0x3D //
+#define MPUREG_ACCEL_YOUT_L 0x3E //
+#define MPUREG_ACCEL_ZOUT_H 0x3F //
+#define MPUREG_ACCEL_ZOUT_L 0x40 //
+#define MPUREG_TEMP_OUT_H 0x41//
+#define MPUREG_TEMP_OUT_L 0x42//
+#define MPUREG_GYRO_XOUT_H 0x43 //
+#define MPUREG_GYRO_XOUT_L 0x44 //
+#define MPUREG_GYRO_YOUT_H 0x45 //
+#define MPUREG_GYRO_YOUT_L 0x46 //
+#define MPUREG_GYRO_ZOUT_H 0x47 //
+#define MPUREG_GYRO_ZOUT_L 0x48 //
+#define MPUREG_USER_CTRL 0x6A //
+#define MPUREG_PWR_MGMT_1 0x6B //
+#define MPUREG_PWR_MGMT_2 0x6C //
+#define MPUREG_FIFO_COUNTH 0x72
+#define MPUREG_FIFO_COUNTL 0x73
+#define MPUREG_FIFO_R_W 0x74
+#define MPUREG_PRODUCT_ID 0x0C // Product ID Register
+
+
+// Configuration bits MPU 3000 and MPU 6000 (not revised)?
+#define BIT_SLEEP 0x40
+#define BIT_H_RESET 0x80
+#define BITS_CLKSEL 0x07
+#define MPU_CLK_SEL_PLLGYROX 0x01
+#define MPU_CLK_SEL_PLLGYROZ 0x03
+#define MPU_EXT_SYNC_GYROX 0x02
+#define BITS_FS_250DPS 0x00
+#define BITS_FS_500DPS 0x08
+#define BITS_FS_1000DPS 0x10
+#define BITS_FS_2000DPS 0x18
+#define BITS_FS_MASK 0x18
+#define BITS_DLPF_CFG_256HZ_NOLPF2 0x00
+#define BITS_DLPF_CFG_188HZ 0x01
+#define BITS_DLPF_CFG_98HZ 0x02
+#define BITS_DLPF_CFG_42HZ 0x03
+#define BITS_DLPF_CFG_20HZ 0x04
+#define BITS_DLPF_CFG_10HZ 0x05
+#define BITS_DLPF_CFG_5HZ 0x06
+#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
+#define BITS_DLPF_CFG_MASK 0x07
+#define BIT_INT_ANYRD_2CLEAR 0x10
+#define BIT_RAW_RDY_EN 0x01
+#define BIT_I2C_IF_DIS 0x10
+#define BIT_INT_STATUS_DATA 0x01
+ // Product ID Description for MPU6000
+ // high 4 bits low 4 bits
+ // Product Name Product Revision
+#define MPU6000ES_REV_C4 0x14 // 0001 0100
+#define MPU6000ES_REV_C5 0x15 // 0001 0101
+#define MPU6000ES_REV_D6 0x16 // 0001 0110
+#define MPU6000ES_REV_D7 0x17 // 0001 0111
+#define MPU6000ES_REV_D8 0x18 // 0001 1000
+#define MPU6000_REV_C4 0x54 // 0101 0100
+#define MPU6000_REV_C5 0x55 // 0101 0101
+#define MPU6000_REV_D6 0x56 // 0101 0110
+#define MPU6000_REV_D7 0x57 // 0101 0111
+#define MPU6000_REV_D8 0x58 // 0101 1000
+#define MPU6000_REV_D9 0x59 // 0101 1001
+#define MPU6000_REV_D10 0x5A // 0101 1010
+
+static FAR struct mpu6000_dev_s mpu6000_dev;
+
+static ssize_t mpu6000_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int mpu6000_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations mpu6000_fops = {
+ .open = 0,
+ .close = 0,
+ .read = mpu6000_read,
+ .write = 0,
+ .seek = 0,
+ .ioctl = mpu6000_ioctl,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+};
+
+struct mpu6000_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+ uint8_t rate;
+ struct mpu6000_buffer *buffer;
+};
+
+static void mpu6000_write_reg(uint8_t address, uint8_t data);
+static uint8_t mpu6000_read_reg(uint8_t address);
+
+static void
+mpu6000_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, true);
+ SPI_SNDBLOCK(mpu6000_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, false);
+}
+
+static uint8_t
+mpu6000_read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, true);
+ SPI_EXCHANGE(mpu6000_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, false);
+
+ return data[1];
+}
+
+static int
+mpu6000_set_range(uint8_t range)
+{
+// /* mask out illegal bit positions */
+// uint8_t write_range = range & REG4_RANGE_MASK;
+// /* immediately return if user supplied invalid value */
+// if (write_range != range) return EINVAL;
+// /* set remaining bits to a sane value */
+// write_range |= REG4_BDU;
+// /* write to device */
+// write_reg(ADDR_CTRL_REG4, write_range);
+// /* return 0 if register value is now written value, 1 if unchanged */
+// return !(read_reg(ADDR_CTRL_REG4) == write_range);
+}
+
+static int
+mpu6000_set_rate(uint8_t rate)
+{
+// /* mask out illegal bit positions */
+// uint8_t write_rate = rate & REG1_RATE_LP_MASK;
+// /* immediately return if user supplied invalid value */
+// if (write_rate != rate) return EINVAL;
+// /* set remaining bits to a sane value */
+// write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
+// /* write to device */
+// write_reg(ADDR_CTRL_REG1, write_rate);
+// /* return 0 if register value is now written value, 1 if unchanged */
+// return !(read_reg(ADDR_CTRL_REG1) == write_rate);
+}
+
+static int
+mpu6000_read_fifo(int16_t *data)
+{
+// struct { /* status register and data as read back from the device */
+// uint8_t cmd;
+// uint8_t temp;
+// uint8_t status;
+// int16_t x;
+// int16_t y;
+// int16_t z;
+// } __attribute__((packed)) report;
+//
+// report.cmd = ADDR_OUT_TEMP | DIR_READ | ADDR_INCREMENT;
+//
+// /* exchange the report structure with the device */
+// SPI_LOCK(mpu6000_dev.spi, true);
+//
+// SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, true);
+//
+// read_reg(ADDR_WHO_AM_I);
+//
+// SPI_EXCHANGE(mpu6000_dev.spi, &report, &report, sizeof(report));
+// SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, false);
+//
+// SPI_LOCK(mpu6000_dev.spi, false);
+//
+//
+//
+ //
+
+ // Device has MSB first at lower address (big endian)
+
+
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t int_status;
+ int16_t xacc;
+ int16_t yacc;
+ int16_t zacc;
+ int8_t temp;
+ int16_t rollspeed;
+ int16_t pitchspeed;
+ int16_t yawspeed;
+ } __attribute__((packed)) report;
+
+ report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
+
+ SPI_LOCK(mpu6000_dev.spi, true);
+ SPI_SELECT(mpu6000_dev.spi, PX4_SPIDEV_MPU, true);
+ SPI_EXCHANGE(mpu6000_dev.spi, &report, &report, sizeof(report));
+ SPI_SELECT(mpu6000_dev.spi, PX4_SPIDEV_MPU, false);
+ SPI_LOCK(mpu6000_dev.spi, false);
+
+ data[0] = report.xacc;
+ data[1] = report.yacc;
+ data[2] = report.zacc;
+
+ return (report.int_status & 0x01);
+}
+
+static ssize_t
+mpu6000_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ if (mpu6000_read_fifo((int16_t *)buffer))
+ return 6;
+
+ /* no data */
+ return 0;
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return ERROR;
+}
+
+static int
+mpu6000_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case MPU6000_SETRATE:
+ if ((arg & 0x00/* XXX REG MASK MISSING */) == arg) {
+ SPI_LOCK(mpu6000_dev.spi, true);
+ mpu6000_set_rate(arg);
+ SPI_LOCK(mpu6000_dev.spi, false);
+ result = 0;
+ mpu6000_dev.rate = arg;
+ }
+ break;
+
+ case MPU6000_SETRANGE:
+ if ((arg & 0x00/* XXX REG MASK MISSING */) == arg) {
+ SPI_LOCK(mpu6000_dev.spi, true);
+ mpu6000_set_range(arg);
+ SPI_LOCK(mpu6000_dev.spi, false);
+ result = 0;
+ }
+ break;
+
+ case MPU6000_SETBUFFER:
+ mpu6000_dev.buffer = (struct mpu6000_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+mpu6000_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ mpu6000_dev.spi = spi;
+ mpu6000_dev.spi_id = spi_id;
+
+ SPI_LOCK(mpu6000_dev.spi, true);
+
+ // Set sensor-specific SPI mode
+ SPI_SETFREQUENCY(mpu6000_dev.spi, 10000000); // 500 KHz
+ SPI_SETBITS(mpu6000_dev.spi, 8);
+ // Either mode 1 or mode 3
+ SPI_SETMODE(mpu6000_dev.spi, SPIDEV_MODE3);
+
+ // Chip reset
+ mpu6000_write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
+ up_udelay(10000);
+ // Wake up device and select GyroZ clock (better performance)
+ mpu6000_write_reg(MPUREG_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
+ up_udelay(1000);
+ // Disable I2C bus (recommended on datasheet)
+ mpu6000_write_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
+ up_udelay(1000);
+ // SAMPLE RATE
+ mpu6000_write_reg(MPUREG_SMPLRT_DIV,0x04); // Sample rate = 200Hz Fsample= 1Khz/(4+1) = 200Hz
+ usleep(1000);
+ // FS & DLPF FS=2000¼/s, DLPF = 98Hz (low pass filter)
+ mpu6000_write_reg(MPUREG_CONFIG, BITS_DLPF_CFG_98HZ);
+ usleep(1000);
+ mpu6000_write_reg(MPUREG_GYRO_CONFIG,BITS_FS_2000DPS); // Gyro scale 2000¼/s
+ usleep(1000);
+
+ uint8_t _product_id = mpu6000_read_reg(MPUREG_PRODUCT_ID);
+ printf("MPU-6000 product id: %d\n", (int)_product_id);
+
+ if ((_product_id == MPU6000ES_REV_C4) || (_product_id == MPU6000ES_REV_C5) ||
+ (_product_id == MPU6000_REV_C4) || (_product_id == MPU6000_REV_C5)){
+ // Accel scale 8g (4096 LSB/g)
+ // Rev C has different scaling than rev D
+ mpu6000_write_reg(MPUREG_ACCEL_CONFIG,1<<3);
+ } else {
+ // Accel scale 8g (4096 LSB/g)
+ mpu6000_write_reg(MPUREG_ACCEL_CONFIG,2<<3);
+ }
+ usleep(1000);
+
+ // INT CFG => Interrupt on Data Ready
+ mpu6000_write_reg(MPUREG_INT_ENABLE,BIT_RAW_RDY_EN); // INT: Raw data ready
+ usleep(1000);
+ mpu6000_write_reg(MPUREG_INT_PIN_CFG,BIT_INT_ANYRD_2CLEAR); // INT: Clear on any read
+ usleep(1000);
+ // Oscillator set
+ // write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ);
+ usleep(1000);
+
+ /* revert back to normal bus mode */
+ SPI_SETFREQUENCY(mpu6000_dev.spi, 10000000);
+ SPI_SETBITS(mpu6000_dev.spi, 8);
+ SPI_SETMODE(mpu6000_dev.spi, SPIDEV_MODE3);
+
+ /* verify that the device is attached and functioning */
+ if ((_product_id == MPU6000ES_REV_C4) || (_product_id == MPU6000ES_REV_C5) ||
+ (_product_id == MPU6000_REV_C4) || (_product_id == MPU6000_REV_C5) ||
+ (_product_id == MPU6000_REV_D7) || (_product_id == MPU6000_REV_D8) ||
+ (_product_id == MPU6000_REV_D9) || (_product_id == MPU6000_REV_D10)){
+
+ /* make ourselves available */
+ register_driver("/dev/mpu6000", &mpu6000_fops, 0666, NULL);
+
+ result = OK;
+ } else {
+
+ errno = EIO;
+ }
+
+ SPI_LOCK(mpu6000_dev.spi, false);
+
+ SPI_LOCK(mpu6000_dev.spi, false);
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_ms5611.c b/nuttx/configs/px4fmu/src/drv_ms5611.c
new file mode 100644
index 000000000..7fea65159
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_ms5611.c
@@ -0,0 +1,493 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Measurement Specialties MS5611 barometric pressure sensor
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/i2c.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+#include <math.h>
+
+#include "chip.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/up_hrt.h>
+#include <arch/board/drv_ms5611.h>
+
+/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
+#define MS5611_MIN_INTER_MEASUREMENT_INTERVAL 9200
+
+#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 */
+
+static FAR struct ms5611_dev_s ms5611_dev;
+
+static ssize_t ms5611_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int ms5611_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations ms5611_fops = {
+ .read = ms5611_read,
+ .ioctl = ms5611_ioctl,
+};
+
+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;
+} __attribute__((packed));
+
+union ms5611_prom_u
+{
+ uint16_t c[8];
+ struct ms5611_prom_s s;
+} __attribute__((packed));
+
+struct ms5611_dev_s
+{
+ union ms5611_prom_u prom;
+ struct i2c_dev_s *i2c;
+ struct ms5611_buffer *buffer;
+} __attribute__((packed));
+
+static FAR uint8_t MS5611_ADDRESS;
+
+static FAR struct {
+ /* status register and data as read back from the device */
+ float pressure;
+ float altitude;
+ float temperature;
+ uint32_t d1_raw;
+ uint32_t d2_raw;
+ uint32_t measurements_count;
+ uint8_t last_state;
+ uint64_t last_read;
+ } ms5611_report = {
+ .pressure = 0.0f,
+ .altitude = 0.0f,
+ .temperature = 0.0f,
+ .last_state = 0,
+ /* make sure the first readout can be performed */
+ .last_read = 0,
+};
+
+static int ms5611_read_prom(void);
+
+static bool
+read_values(float *data)
+{
+ int ret;
+ uint8_t cmd_data[3];
+
+ /* check validity of pointer */
+ if (data == NULL)
+ {
+ *get_errno_ptr() = EINVAL;
+ return -EINVAL;
+ }
+
+ /* only start reading when data is available */
+ if (ms5611_report.measurements_count > 0)
+ {
+ /* do not read more often than at minimum 9.17 ms intervals */
+ if ((hrt_absolute_time() - ms5611_report.last_read) < MS5611_MIN_INTER_MEASUREMENT_INTERVAL)
+ {
+ /* set errno to 'come back later' */
+ ret = -EAGAIN;
+ goto handle_return;
+ }
+ else
+ {
+ /* set new value */
+ ms5611_report.last_read = hrt_absolute_time();
+ }
+
+ /* Read out last measurement */
+ cmd_data[0] = 0x00;
+
+ struct i2c_msg_s msgv[2] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = cmd_data,
+ .length = 1
+ },
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = I2C_M_READ,
+ .buffer = cmd_data,
+ .length = 3
+ }
+ };
+ ret = I2C_TRANSFER(ms5611_dev.i2c, msgv, 2);
+ if (ret != OK) goto handle_return;
+
+
+ /* at value 1 the last reading was temperature */
+ if (ms5611_report.last_state == 1)
+ {
+ /* put temperature into the raw set */
+ ms5611_report.d2_raw = (((uint32_t)cmd_data[0]) << 16) | (((uint32_t)cmd_data[1]) << 8) | ((uint32_t)cmd_data[2]);
+ }
+ else
+ {
+ /* put altitude into the raw set */
+ ms5611_report.d1_raw = (((uint32_t)cmd_data[0]) << 16) | (((uint32_t)cmd_data[1]) << 8) | ((uint32_t)cmd_data[2]);
+ }
+ }
+ ms5611_report.measurements_count++;
+
+ /*
+ * this block reads four pressure values and one temp value,
+ * resulting in 80 Hz pressure update and 20 Hz temperature updates
+ * at 100 Hz continuous operation.
+ */
+ if (ms5611_report.last_state == 0)
+ {
+ /* request first a temperature reading */
+ cmd_data[0] = ADDR_CMD_CONVERT_D2;
+ }
+ else
+ {
+ /* request pressure reading */
+ cmd_data[0] = ADDR_CMD_CONVERT_D1;
+ }
+
+ if (ms5611_report.last_state == 3)
+ {
+ ms5611_report.last_state = 0;
+ }
+ else
+ {
+ ms5611_report.last_state++;
+ }
+
+
+ /* write measurement command */
+ struct i2c_msg_s conv_cmd[1] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = cmd_data,
+ .length = 1
+ },
+ };
+
+ ret = I2C_TRANSFER(ms5611_dev.i2c, conv_cmd, 1);
+ if (ret != OK) goto handle_return;
+
+ /* only write back values after first complete set */
+ if (ms5611_report.measurements_count > 2)
+ {
+ /* Calculate results */
+
+ /* temperature calculation */
+ int32_t dT = ms5611_report.d2_raw - (((int32_t)ms5611_dev.prom.s.c5_reference_temp)*256);
+ int64_t temp_int64 = 2000 + (((int64_t)dT)*ms5611_dev.prom.s.c6_temp_coeff_temp)/8388608;
+
+ /* pressure calculation */
+ int64_t offset = (int64_t)ms5611_dev.prom.s.c2_pressure_offset * 65536 + ((int64_t)dT*ms5611_dev.prom.s.c4_temp_coeff_pres_offset)/128;
+ int64_t sens = (int64_t)ms5611_dev.prom.s.c1_pressure_sens * 32768 + ((int64_t)dT*ms5611_dev.prom.s.c3_temp_coeff_pres_sens)/256;
+
+ /* it's pretty cold, second order temperature compensation needed */
+ if (temp_int64 < 2000)
+ {
+ /* second order temperature compensation */
+ int64_t temp2 = (((int64_t)dT)*dT) >> 31;
+ int64_t tmp_64 = (temp_int64-2000)*(temp_int64-2000);
+ int64_t offset2 = (5*tmp_64)>>1;
+ int64_t sens2 = (5*tmp_64)>>2;
+ temp_int64 = temp_int64 - temp2;
+ offset = offset - offset2;
+ sens = sens - sens2;
+ }
+
+ int64_t press_int64 = (((ms5611_report.d1_raw*sens)/2097152-offset)/32768);
+
+ ms5611_report.temperature = temp_int64 / 100.0f;
+ ms5611_report.pressure = press_int64 / 100.0f;
+ /* convert as double for max. precision, store as float (more than enough precision) */
+ ms5611_report.altitude = (44330.0 * (1.0 - pow((press_int64 / 101325.0), 0.190295)));
+
+ /* Write back float values */
+ data[0] = ms5611_report.pressure;
+ data[1] = ms5611_report.altitude;
+ data[2] = ms5611_report.temperature;
+ }
+ else
+ {
+ /* not ready, try again */
+ ret = -EINPROGRESS;
+ }
+
+ /* return 1 if new data is available, 0 else */
+ handle_return:
+ if (ret == OK)
+ {
+ return (sizeof(ms5611_report.d1_raw) + sizeof(ms5611_report.altitude) + sizeof(ms5611_report.d2_raw));
+ }
+ else
+ {
+ errno = -ret;
+ return ret;
+ }
+}
+
+static ssize_t
+ms5611_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 12) {
+ return read_values((float *)buffer);
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return -ENOSPC;
+}
+
+static int
+ms5611_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ return -ENOSYS;
+
+// switch (cmd) {
+// case MS5611_SETRATE:
+// if ((arg & REG1_RATE_LP_MASK) == arg) {
+// set_rate(arg);
+// result = 0;
+// dev.rate = arg;
+// }
+// break;
+//
+// case MS5611_SETBUFFER:
+// dev.buffer = (struct ms5611_buffer *)arg;
+// result = 0;
+// break;
+// }
+//
+// if (result)
+// errno = EINVAL;
+// return result;
+}
+
+
+
+int ms5611_crc4(uint16_t n_prom[])
+{
+ /* routine ported from MS5611 application note */
+ 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 0 == OK if CRCs match, 1 else */
+ return !((0x000F & crc_read) == (n_rem ^ 0x00));
+}
+
+
+int ms5611_read_prom()
+{
+ /* read PROM data */
+ uint8_t prom_buf[2] = {255,255};
+
+ int retval = 0;
+
+ for (int i = 0; i < 8; i++)
+ {
+ uint8_t cmd = {ADDR_PROM_SETUP + (i*2)};
+
+ I2C_SETADDRESS(ms5611_dev.i2c, MS5611_ADDRESS, 7);
+ retval = I2C_WRITEREAD(ms5611_dev.i2c, &cmd, 1, prom_buf, 2);
+
+ /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
+ ms5611_dev.prom.c[i] = (((uint16_t)prom_buf[0])<<8) | ((uint16_t)prom_buf[1]);
+
+ if (retval != OK)
+ {
+ break;
+ }
+ }
+
+ /* calculate CRC and return error if mismatch */
+ return ms5611_crc4(ms5611_dev.prom.c);
+}
+
+int
+ms5611_attach(struct i2c_dev_s *i2c)
+{
+ int result = ERROR;
+
+ ms5611_dev.i2c = i2c;
+
+ MS5611_ADDRESS = MS5611_ADDRESS_1;
+
+ /* write reset command */
+ uint8_t cmd_data = ADDR_RESET_CMD;
+
+ struct i2c_msg_s reset_cmd[1] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = &cmd_data,
+ .length = 1
+ },
+ };
+
+ int ret = I2C_TRANSFER(ms5611_dev.i2c, reset_cmd, 1);
+
+ if (ret == OK)
+ {
+ /* wait for PROM contents to be in the device (2.8 ms) */
+ up_udelay(3000);
+
+ /* read PROM */
+ ret = ms5611_read_prom();
+ }
+
+ /* check if the address was wrong */
+ if (ret != OK)
+ {
+ /* try second address */
+ MS5611_ADDRESS = MS5611_ADDRESS_2;
+
+ /* write reset command */
+ cmd_data = ADDR_RESET_CMD;
+
+ struct i2c_msg_s reset_cmd_2[1] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = &cmd_data,
+ .length = 1
+ },
+ };
+
+ ret = I2C_TRANSFER(ms5611_dev.i2c, reset_cmd_2, 1);
+
+ /* wait for PROM contents to be in the device (2.8 ms) */
+ up_udelay(3000);
+
+ /* read PROM */
+ ret = ms5611_read_prom();
+ }
+
+ if (ret < 0) return -EIO;
+
+
+ /* verify that the device is attached and functioning */
+ if (ret == OK) {
+
+ if (MS5611_ADDRESS == MS5611_ADDRESS_1)
+ {
+ printf("[ms5611 driver] Attached MS5611 at addr #1 (0x76)\n");
+ }
+ else
+ {
+ printf("[ms5611 driver] Attached MS5611 at addr #2 (0x77)\n");
+ }
+
+ /* trigger temperature read */
+ (void)read_values(NULL);
+ /* wait for conversion to complete */
+ up_udelay(9200);
+
+ /* trigger pressure read */
+ (void)read_values(NULL);
+ /* wait for conversion to complete */
+ up_udelay(9200);
+ /* now a read_values call would obtain valid results */
+
+ /* make ourselves available */
+ register_driver("/dev/ms5611", &ms5611_fops, 0666, NULL);
+
+ result = OK;
+
+ } else {
+ errno = EIO;
+ }
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_tone_alarm.c b/nuttx/configs/px4fmu/src/drv_tone_alarm.c
new file mode 100644
index 000000000..958a18904
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_tone_alarm.c
@@ -0,0 +1,511 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/*
+ * Speaker driver supporting alarm sequences.
+ *
+ * Works with any of the 'generic' STM32 timers that has an output
+ * pin, does not require an interrupt.
+ *
+ * Depends on the HRT timer.
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <queue.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+
+#include <arch/board/board.h>
+#include <arch/board/drv_tone_alarm.h>
+#include <arch/board/up_hrt.h>
+
+#include "chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "stm32_internal.h"
+#include "stm32_gpio.h"
+#include "stm32_tim.h"
+
+#ifdef CONFIG_TONE_ALARM
+# ifndef CONFIG_HRT_TIMER
+# error CONFIG_TONE_ALARM requires CONFIG_HRT_TIMER
+# endif
+
+/* Tone alarm configuration */
+#if TONE_ALARM_TIMER == 2
+# define TONE_ALARM_BASE STM32_TIM2_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM2_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM2EN
+# ifdef CONFIG_STM32_TIM2
+# error Must not set CONFIG_STM32_TIM2 when TONE_ALARM_TIMER is 2
+# endif
+#elif TONE_ALARM_TIMER == 3
+# define TONE_ALARM_BASE STM32_TIM3_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM3_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM3EN
+# ifdef CONFIG_STM32_TIM3
+# error Must not set CONFIG_STM32_TIM3 when TONE_ALARM_TIMER is 3
+# endif
+#elif TONE_ALARM_TIMER == 4
+# define TONE_ALARM_BASE STM32_TIM4_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM4_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM4EN
+# ifdef CONFIG_STM32_TIM4
+# error Must not set CONFIG_STM32_TIM4 when TONE_ALARM_TIMER is 4
+# endif
+#elif TONE_ALARM_TIMER == 5
+# define TONE_ALARM_BASE STM32_TIM5_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM5_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM5EN
+# ifdef CONFIG_STM32_TIM5
+# error Must not set CONFIG_STM32_TIM5 when TONE_ALARM_TIMER is 5
+# endif
+#elif TONE_ALARM_TIMER == 9
+# define TONE_ALARM_BASE STM32_TIM9_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM9_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM9EN
+# ifdef CONFIG_STM32_TIM9
+# error Must not set CONFIG_STM32_TIM9 when TONE_ALARM_TIMER is 9
+# endif
+#elif TONE_ALARM_TIMER == 10
+# define TONE_ALARM_BASE STM32_TIM10_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM10_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM10EN
+# ifdef CONFIG_STM32_TIM10
+# error Must not set CONFIG_STM32_TIM10 when TONE_ALARM_TIMER is 10
+# endif
+#elif TONE_ALARM_TIMER == 11
+# define TONE_ALARM_BASE STM32_TIM11_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM11_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM11EN
+# ifdef CONFIG_STM32_TIM11
+# error Must not set CONFIG_STM32_TIM11 when TONE_ALARM_TIMER is 11
+# endif
+#else
+# error Must set TONE_ALARM_TIMER to a generic timer if CONFIG_TONE_ALARM is set
+#endif
+
+#if TONE_ALARM_CHANNEL == 1
+# define TONE_CCMR1 (3 << 4)
+# define TONE_CCMR2 0
+# define TONE_CCER (1 << 0)
+# define TONE_rCCR rCCR1
+#elif TONE_ALARM_CHANNEL == 2
+# define TONE_CCMR1 (3 << 12)
+# define TONE_CCMR2 0
+# define TONE_CCER (1 << 4)
+# define TONE_rCCR rCCR2
+#elif TONE_ALARM_CHANNEL == 3
+# define TONE_CCMR1 0
+# define TONE_CCMR2 (3 << 4)
+# define TONE_CCER (1 << 8)
+# define TONE_rCCR rCCR3
+#elif TONE_ALARM_CHANNEL == 4
+# define TONE_CCMR1 0
+# define TONE_CCMR2 (3 << 12)
+# define TONE_CCER (1 << 12)
+# define TONE_rCCR rCCR4
+#else
+# error Must set TONE_ALARM_CHANNEL to a value between 1 and 4
+#endif
+
+/*
+ * Timer register accessors
+ */
+#define REG(_reg) (*(volatile uint32_t *)(TONE_ALARM_BASE + _reg))
+
+#define rCR1 REG(STM32_GTIM_CR1_OFFSET)
+#define rCR2 REG(STM32_GTIM_CR2_OFFSET)
+#define rSMCR REG(STM32_GTIM_SMCR_OFFSET)
+#define rDIER REG(STM32_GTIM_DIER_OFFSET)
+#define rSR REG(STM32_GTIM_SR_OFFSET)
+#define rEGR REG(STM32_GTIM_EGR_OFFSET)
+#define rCCMR1 REG(STM32_GTIM_CCMR1_OFFSET)
+#define rCCMR2 REG(STM32_GTIM_CCMR2_OFFSET)
+#define rCCER REG(STM32_GTIM_CCER_OFFSET)
+#define rCNT REG(STM32_GTIM_CNT_OFFSET)
+#define rPSC REG(STM32_GTIM_PSC_OFFSET)
+#define rARR REG(STM32_GTIM_ARR_OFFSET)
+#define rCCR1 REG(STM32_GTIM_CCR1_OFFSET)
+#define rCCR2 REG(STM32_GTIM_CCR2_OFFSET)
+#define rCCR3 REG(STM32_GTIM_CCR3_OFFSET)
+#define rCCR4 REG(STM32_GTIM_CCR4_OFFSET)
+#define rDCR REG(STM32_GTIM_DCR_OFFSET)
+#define rDMAR REG(STM32_GTIM_DMAR_OFFSET)
+
+#define TONE_MAX_PATTERN 6
+#define TONE_MAX_PATTERN_LEN 40
+
+/* predefined patterns for alarms 1-TONE_MAX_PATTERN */
+const struct tone_note patterns[TONE_MAX_PATTERN][TONE_MAX_PATTERN_LEN] = {
+ {
+ {TONE_NOTE_A7, 12},
+ {TONE_NOTE_D8, 12},
+ {TONE_NOTE_C8, 12},
+ {TONE_NOTE_A7, 12},
+ {TONE_NOTE_D8, 12},
+ {TONE_NOTE_C8, 12},
+ {TONE_NOTE_D8, 4},
+ {TONE_NOTE_C8, 4},
+ {TONE_NOTE_D8, 4},
+ {TONE_NOTE_C8, 4},
+ {TONE_NOTE_D8, 4},
+ {TONE_NOTE_C8, 4},
+ },
+ {{TONE_NOTE_B6, 100}},
+ {{TONE_NOTE_C7, 100}},
+ {{TONE_NOTE_D7, 100}},
+ {{TONE_NOTE_E7, 100}},
+ { //This is tetris ;)
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_G5, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_G5, 20},
+ {TONE_NOTE_F5, 40},
+ {TONE_NOTE_F5, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_A5S, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_G5, 60},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_G5S, 40},
+ {TONE_NOTE_F5, 40},
+ {TONE_NOTE_F5, 60},
+
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_C6S, 20},
+ {TONE_NOTE_F6, 40},
+ {TONE_NOTE_D6S, 20},
+ {TONE_NOTE_C6S, 20},
+ {TONE_NOTE_C6, 60},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_A5S, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_G5, 40},
+ {TONE_NOTE_G5, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_G5S, 40},
+ {TONE_NOTE_F5, 40},
+ {TONE_NOTE_F5, 60},
+ }
+};
+
+static uint16_t notes[TONE_NOTE_MAX] = {
+ 63707, /* E4 */
+ 60132, /* F4 */
+ 56758, /* F#4/Gb4 */
+ 53571, /* G4 */
+ 50565, /* G#4/Ab4 */
+ 47727, /* A4 */
+ 45048, /* A#4/Bb4 */
+ 42520, /* B4 */
+ 40133, /* C5 */
+ 37880, /* C#5/Db5 */
+ 35755, /* D5 */
+ 33748, /* D#5/Eb5 */
+ 31853, /* E5 */
+ 30066, /* F5 */
+ 28378, /* F#5/Gb5 */
+ 26786, /* G5 */
+ 25282, /* G#5/Ab5 */
+ 23863, /* A5 */
+ 22524, /* A#5/Bb5 */
+ 21260, /* B5 */
+ 20066, /* C6 */
+ 18940, /* C#6/Db6 */
+ 17877, /* D6 */
+ 16874, /* D#6/Eb6 */
+ 15927, /* E6 */
+ 15033, /* F6 */
+ 14189, /* F#6/Gb6 */
+ 13393, /* G6 */
+ 12641, /* G#6/Ab6 */
+ 11931, /* A6 */
+ 11262, /* A#6/Bb6 */
+ 10630, /* B6 */
+ 10033, /* C7 */
+ 9470, /* C#7/Db7 */
+ 8938, /* D7 */
+ 8437, /* D#7/Eb7 */
+ 7963, /* E7 */
+ 7516, /* F7 */
+ 7094, /* F#7/Gb7 */
+ 6696, /* G7 */
+ 6320, /* G#7/Ab7 */
+ 5965, /* A7 */
+ 5631, /* A#7/Bb7 */
+ 5315, /* B7 */
+ 5016, /* C8 */
+ 4735, /* C#8/Db8 */
+ 4469, /* D8 */
+ 4218 /* D#8/Eb8 */
+};
+
+/* current state of the tone driver */
+struct state {
+ int pattern; /* current pattern */
+#define PATTERN_NONE -1
+#define PATTERN_USER 0
+ int note; /* next note to play */
+ struct hrt_call note_end;
+ struct tone_note user_pattern[TONE_MAX_PATTERN_LEN]; /* user-supplied pattern (plays at pattern 0) */
+};
+
+static struct state tone_state;
+
+static int tone_write(struct file *filp, const char *buffer, size_t len);
+static int tone_ioctl(struct file *filep, int cmd, unsigned long arg);
+
+static const struct file_operations tone_fops = {
+ .write = tone_write,
+ .ioctl = tone_ioctl
+};
+
+static void tone_next(void);
+static bool tone_ok(struct tone_note *pattern);
+int
+tone_alarm_init(void)
+{
+ /* configure the GPIO */
+ stm32_configgpio(GPIO_TONE_ALARM);
+
+ /* clock/power on our timer */
+ modifyreg32(STM32_RCC_APB1ENR, 0, TONE_ALARM_CLOCK_ENABLE);
+
+ /* default the state */
+ tone_state.pattern = -1;
+
+ /* initialise the timer */
+ rCR1 = 0;
+ rCR2 = 0;
+ rSMCR = 0;
+ rDIER = 0;
+ rCCER = 0; /* unlock CCMR* registers */
+ rCCMR1 = TONE_CCMR1;
+ rCCMR2 = TONE_CCMR2;
+ rCCER = TONE_CCER;
+ rDCR = 0;
+
+ /* toggle the CC output each time the count passes 1 */
+ TONE_rCCR = 1;
+
+ /*
+ * Configure the timebase to free-run at half max frequency.
+ * XXX this should be more flexible in order to get a better
+ * frequency range, but for the F4 with the APB1 timers based
+ * at 42MHz, this gets us down to ~320Hz or so.
+ */
+ rPSC = 1;
+
+ tone_state.pattern = PATTERN_NONE;
+ tone_state.note = 0;
+
+ /* play the startup tune */
+ tone_ioctl(NULL, TONE_SET_ALARM, 1);
+
+ /* register the device */
+ return register_driver("/dev/tone_alarm", &tone_fops, 0666, NULL);
+}
+
+static int
+tone_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ int result = 0;
+ int new = (int)arg;
+
+ irqstate_t flags = irqsave();
+
+ /* decide whether to increase the alarm level to cmd or leave it alone */
+ switch (cmd) {
+ case TONE_SET_ALARM:
+ if (new == 0) {
+ /* cancel any current alarm */
+ tone_state.pattern = PATTERN_NONE;
+ tone_next();
+
+ } else if (new > TONE_MAX_PATTERN) {
+
+ /* not a legal alarm value */
+ result = -ERANGE;
+
+ } else if (new > tone_state.pattern) {
+
+ /* higher priority than the current alarm */
+ tone_state.pattern = new;
+ tone_state.note = 0;
+
+ /* and start playing it */
+ tone_next();
+ }
+ break;
+ default:
+ result = -EINVAL;
+ break;
+ }
+
+ irqrestore(flags);
+ return result;
+}
+
+static int
+tone_write(struct file *filp, const char *buffer, size_t len)
+{
+ irqstate_t flags;
+
+ /* sanity-check the size of the write */
+ if (len > (TONE_MAX_PATTERN_LEN * sizeof(struct tone_note)))
+ return -EFBIG;
+ if ((len % sizeof(struct tone_note)) || (len == 0))
+ return -EIO;
+ if (!tone_ok((struct tone_note *)buffer))
+ return -EIO;
+
+ flags = irqsave();
+
+ /* if we aren't playing an alarm tone */
+ if (tone_state.pattern <= PATTERN_USER) {
+
+ /* reset the tone state to play the new user pattern */
+ tone_state.pattern = PATTERN_USER;
+ tone_state.note = 0;
+
+ /* copy in the new pattern */
+ memset(tone_state.user_pattern, 0, sizeof(tone_state.user_pattern));
+ memcpy(tone_state.user_pattern, buffer, len);
+
+ /* and start it */
+ tone_next();
+ }
+ irqrestore(flags);
+
+ return len;
+}
+
+static void
+tone_next(void)
+{
+ const struct tone_note *np;
+
+ /* stop the current note */
+ rCR1 = 0;
+
+ /* if we are no longer playing a pattern, we have nothing else to do here */
+ if (tone_state.pattern == PATTERN_NONE) {
+ return;
+ }
+
+ /* if the current pattern has ended, clear the pattern and stop */
+ if (tone_state.note == TONE_NOTE_MAX) {
+ tone_state.pattern = PATTERN_NONE;
+ return;
+ }
+
+ /* find the note to play */
+ if (tone_state.pattern == PATTERN_USER) {
+ np = &tone_state.user_pattern[tone_state.note];
+ } else {
+ np = &patterns[tone_state.pattern - 1][tone_state.note];
+ }
+
+ /* work out which note is next */
+ tone_state.note++;
+ if (tone_state.note >= TONE_NOTE_MAX) {
+ /* hit the end of the pattern, stop */
+ tone_state.pattern = PATTERN_NONE;
+ } else if (np[1].duration == DURATION_END) {
+ /* hit the end of the pattern, stop */
+ tone_state.pattern = PATTERN_NONE;
+ } else if (np[1].duration == DURATION_REPEAT) {
+ /* next note is a repeat, rewind in preparation */
+ tone_state.note = 0;
+ }
+
+ /* set the timer to play the note, if required */
+ if (np->pitch <= TONE_NOTE_SILENCE) {
+
+ /* set reload based on the pitch */
+ rARR = notes[np->pitch];
+
+ /* force an update, reloads the counter and all registers */
+ rEGR = GTIM_EGR_UG;
+
+ /* start the timer */
+ rCR1 = GTIM_CR1_CEN;
+ }
+
+ /* arrange a callback when the note/rest is done */
+ hrt_call_after(&tone_state.note_end, (hrt_abstime)10000 * np->duration, (hrt_callout)tone_next, NULL);
+
+}
+
+static bool
+tone_ok(struct tone_note *pattern)
+{
+ int i;
+
+ for (i = 0; i < TONE_NOTE_MAX; i++) {
+
+ /* first note must not be repeat or end */
+ if ((i == 0) &&
+ ((pattern[i].duration == DURATION_END) || (pattern[i].duration == DURATION_REPEAT)))
+ return false;
+ if (pattern[i].duration == DURATION_END)
+ break;
+
+ /* pitch must be legal */
+ if (pattern[i].pitch >= TONE_NOTE_MAX)
+ return false;
+ }
+ return true;
+}
+
+#endif /* CONFIG_TONE_ALARM */ \ No newline at end of file
diff --git a/nuttx/configs/px4fmu/src/px4fmu-internal.h b/nuttx/configs/px4fmu/src/px4fmu-internal.h
new file mode 100644
index 000000000..f48b1bf5e
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/px4fmu-internal.h
@@ -0,0 +1,166 @@
+/****************************************************************************************************
+ * configs/px4fmu/src/px4fmu_internal.h
+ * arch/arm/src/board/px4fmu_internal.n
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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 __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H
+#define __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+/* Configuration ************************************************************************************/
+
+#ifdef CONFIG_STM32_SPI2
+# error "SPI2 is not supported on this board"
+#endif
+
+#if defined(CONFIG_STM32_CAN1)
+# warning "CAN1 is not supported on this board"
+#endif
+
+/* PX4FMU GPIOs ***********************************************************************************/
+/* LEDs */
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
+
+/* External interrupts */
+#define GPIO_EXTI_COMPASS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
+// XXX MPU6000 DRDY?
+
+/* SPI chip selects */
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
+#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+
+/* User GPIOs
+ *
+ * GPIO0-1 are the buffered high-power GPIOs.
+ * GPIO2-5 are the USART2 pins.
+ * GPIO6-7 are the CAN2 pins.
+ */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN2)
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
+#define GPIO_GPIO_DIR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
+
+/* USB OTG FS
+ *
+ * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
+ */
+#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
+
+/* PWM
+ *
+ * The PX4FMU has five PWM outputs, of which only the output on
+ * pin PC8 is fixed assigned to this function. The other four possible
+ * pwm sources are the TX, RX, RTS and CTS pins of USART2
+ *
+ * Alternate function mapping:
+ * PC8 - BUZZER - TIM8_CH3/SDIO_D0 /TIM3_CH3/ USART6_CK / DCMI_D2
+ */
+
+#ifdef CONFIG_PWM
+# if defined(CONFIG_STM32_TIM3_PWM)
+# define BUZZER_PWMCHANNEL 3
+# define BUZZER_PWMTIMER 3
+# elif defined(CONFIG_STM32_TIM8_PWM)
+# define BUZZER_PWMCHANNEL 3
+# define BUZZER_PWMTIMER 8
+# endif
+#endif
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+/****************************************************************************************************
+ * Name: px4fmu_gpio_init
+ *
+ * Description:
+ * Called to configure the PX4FMU user GPIOs
+ *
+ ****************************************************************************************************/
+
+extern void px4fmu_gpio_init(void);
+
+
+// XXX additional SPI chipselect functions required?
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H */
+
diff --git a/nuttx/configs/px4fmu/src/up_adc.c b/nuttx/configs/px4fmu/src/up_adc.c
new file mode 100644
index 000000000..2d74e6f00
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_adc.c
@@ -0,0 +1,173 @@
+/************************************************************************************
+ * configs/stm3240g-eval/src/up_adc.c
+ * arch/arm/src/board/up_adc.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+#include <stdio.h>
+
+#include <nuttx/analog/adc.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+//#include "stm32_pwm.h"
+#include "stm32_adc.h"
+#include "px4fmu-internal.h"
+
+#ifdef CONFIG_ADC
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Configuration ************************************************************/
+/* Up to 3 ADC interfaces are supported */
+
+#if STM32_NADC < 3
+# undef CONFIG_STM32_ADC3
+#endif
+
+#if STM32_NADC < 2
+# undef CONFIG_STM32_ADC2
+#endif
+
+#if STM32_NADC < 1
+# undef CONFIG_STM32_ADC3
+#endif
+
+#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
+#ifndef CONFIG_STM32_ADC3
+# warning "Channel information only available for ADC3"
+#endif
+
+#define ADC3_NCHANNELS 4
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+/* The PX4FMU board has four ADC channels: ADC323 IN10-13
+ */
+
+/* Identifying number of each ADC channel: Variable Resistor. */
+
+#ifdef CONFIG_STM32_ADC3
+static const uint8_t g_chanlist[ADC3_NCHANNELS] = {10, 11};// , 12, 13}; ADC12 and 13 are used by MPU on v1.5 boards
+
+/* Configurations of pins used byte each ADC channels */
+static const uint32_t g_pinlist[ADC3_NCHANNELS] = {GPIO_ADC3_IN10, GPIO_ADC3_IN11}; // ADC12 and 13 are used by MPU on v1.5 boards, GPIO_ADC3_IN12, GPIO_ADC3_IN13};
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: adc_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/adc.
+ *
+ ************************************************************************************/
+
+int adc_devinit(void)
+{
+#ifdef CONFIG_STM32_ADC3
+ static bool initialized = false;
+ struct adc_dev_s *adc[ADC3_NCHANNELS];
+ int ret;
+ int i;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ char name[11];
+
+ for (i = 0; i < ADC3_NCHANNELS; i++)
+ {
+ stm32_configgpio(g_pinlist[i]);
+ }
+
+ for (i = 0; i < 1; i++)
+ {
+ /* Configure the pins as analog inputs for the selected channels */
+ //stm32_configgpio(g_pinlist[i]);
+
+ /* Call stm32_adcinitialize() to get an instance of the ADC interface */
+ //multiple channels only supported with dma!
+ adc[i] = stm32_adcinitialize(3, (g_chanlist), 4);
+ if (adc == NULL)
+ {
+ adbg("ERROR: Failed to get ADC interface\n");
+ return -ENODEV;
+ }
+
+
+ /* Register the ADC driver at "/dev/adc0" */
+ sprintf(name, "/dev/adc%d", i);
+ ret = adc_register(name, adc[i]);
+ if (ret < 0)
+ {
+ adbg("adc_register failed for adc %s: %d\n", name, ret);
+ return ret;
+ }
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+#else
+ return -ENOSYS;
+#endif
+}
+
+#endif /* CONFIG_STM32_ADC || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
+#endif /* CONFIG_ADC */
diff --git a/nuttx/configs/px4fmu/src/up_boot.c b/nuttx/configs/px4fmu/src/up_boot.c
new file mode 100644
index 000000000..da396cdd6
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_boot.c
@@ -0,0 +1,76 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "px4fmu-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
diff --git a/nuttx/configs/px4fmu/src/up_can.c b/nuttx/configs/px4fmu/src/up_can.c
new file mode 100644
index 000000000..daf6484f2
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_can.c
@@ -0,0 +1,142 @@
+/************************************************************************************
+ * configs/px4fmu/src/up_can.c
+ * arch/arm/src/board/up_can.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/can.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "px4fmu-internal.h"
+
+#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+ if (can == NULL)
+ {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+ if (ret < 0)
+ {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_STM32_CAN || CONFIG_STM32_CAN2 || CONFIG_STM32_CAN3 */
diff --git a/nuttx/configs/px4fmu/src/up_cpuload.c b/nuttx/configs/px4fmu/src/up_cpuload.c
new file mode 100644
index 000000000..750ec4852
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_cpuload.c
@@ -0,0 +1,182 @@
+/****************************************************************************
+ * configs/px4fmu/src/up_leds.c
+ * arch/arm/src/board/up_leds.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <sys/time.h>
+
+#include <arch/board/board.h>
+#include <arch/board/up_hrt.h>
+#include <arch/board/up_cpuload.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name:
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+
+struct system_load_s system_load;
+
+extern FAR _TCB *sched_gettcb(pid_t pid);
+
+void cpuload_initialize_once(void);
+
+void cpuload_initialize_once()
+{
+// if (!system_load.initialized)
+// {
+ system_load.start_time = hrt_absolute_time();
+ int i;
+ for (i = 0; i < CONFIG_MAX_TASKS; i++)
+ {
+ system_load.tasks[i].valid = false;
+ }
+ system_load.total_count = 0;
+
+ uint64_t now = hrt_absolute_time();
+
+ /* initialize idle thread statically */
+ system_load.tasks[0].start_time = now;
+ system_load.tasks[0].total_runtime = 0;
+ system_load.tasks[0].curr_start_time = 0;
+ system_load.tasks[0].tcb = sched_gettcb(0);
+ system_load.tasks[0].valid = true;
+ system_load.total_count++;
+
+ /* initialize init thread statically */
+ system_load.tasks[1].start_time = now;
+ system_load.tasks[1].total_runtime = 0;
+ system_load.tasks[1].curr_start_time = 0;
+ system_load.tasks[1].tcb = sched_gettcb(1);
+ system_load.tasks[1].valid = true;
+ /* count init thread */
+ system_load.total_count++;
+ // }
+}
+
+void sched_note_start(FAR _TCB *tcb )
+{
+ /* search first free slot */
+ int i;
+ for (i = 1; i < CONFIG_MAX_TASKS; i++)
+ {
+ if (!system_load.tasks[i].valid)
+ {
+ /* slot is available */
+ system_load.tasks[i].start_time = hrt_absolute_time();
+ system_load.tasks[i].total_runtime = 0;
+ system_load.tasks[i].curr_start_time = 0;
+ system_load.tasks[i].tcb = tcb;
+ system_load.tasks[i].valid = true;
+ system_load.total_count++;
+ break;
+ }
+ }
+}
+
+void sched_note_stop(FAR _TCB *tcb )
+{
+ int i;
+ for (i = 1; i < CONFIG_MAX_TASKS; i++)
+ {
+ if (system_load.tasks[i].tcb->pid == tcb->pid)
+ {
+ /* mark slot as fee */
+ system_load.tasks[i].valid = false;
+ system_load.tasks[i].total_runtime = 0;
+ system_load.tasks[i].curr_start_time = 0;
+ system_load.tasks[i].tcb = NULL;
+ system_load.total_count--;
+ break;
+ }
+ }
+}
+
+void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb)
+{
+ uint64_t new_time = hrt_absolute_time();
+
+ /* Kind of inefficient: find both tasks and update times */
+ uint8_t both_found = 0;
+ for (int i = 0; i < CONFIG_MAX_TASKS; i++)
+ {
+ /* Task ending its current scheduling run */
+ if (system_load.tasks[i].tcb->pid == pFromTcb->pid)
+ {
+ //if (system_load.tasks[i].curr_start_time != 0)
+ {
+ system_load.tasks[i].total_runtime += new_time - system_load.tasks[i].curr_start_time;
+ }
+ both_found++;
+ }
+ else if (system_load.tasks[i].tcb->pid == pToTcb->pid)
+ {
+ system_load.tasks[i].curr_start_time = new_time;
+ both_found++;
+ }
+
+ /* Do only iterate as long as needed */
+ if (both_found == 2)
+ {
+ break;
+ }
+ }
+}
+
+#endif /* CONFIG_SCHED_INSTRUMENTATION */
diff --git a/nuttx/configs/px4fmu/src/up_hrt.c b/nuttx/configs/px4fmu/src/up_hrt.c
new file mode 100644
index 000000000..35aecfe08
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_hrt.c
@@ -0,0 +1,801 @@
+/****************************************************************************
+ *
+ * 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 High-resolution timer callouts and timekeeping.
+ *
+ * This can use any general or advanced STM32 timer.
+ *
+ * Note that really, this could use systick too, but that's
+ * monopolised by NuttX and stealing it would just be awkward.
+ *
+ * We don't use the NuttX STM32 driver per se; rather, we
+ * claim the timer and then drive it directly.
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <queue.h>
+#include <errno.h>
+#include <string.h>
+
+#include <arch/board/board.h>
+#include <arch/board/up_hrt.h>
+
+#include "chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "stm32_internal.h"
+#include "stm32_gpio.h"
+#include "stm32_tim.h"
+
+#ifdef CONFIG_HRT_TIMER
+
+/* HRT configuration */
+#if HRT_TIMER == 1
+# define HRT_TIMER_BASE STM32_TIM1_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB2ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM1EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1CC
+# define HRT_TIMER_CLOCK STM32_APB2_TIM1_CLKIN
+# if CONFIG_STM32_TIM1
+# error must not set CONFIG_STM32_TIM1=y and HRT_TIMER=1
+# endif
+#elif HRT_TIMER == 2
+# define HRT_TIMER_BASE STM32_TIM2_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM2EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM2
+# define HRT_TIMER_CLOCK STM32_APB1_TIM2_CLKIN
+# if CONFIG_STM32_TIM2
+# error must not set CONFIG_STM32_TIM2=y and HRT_TIMER=2
+# endif
+#elif HRT_TIMER == 3
+# define HRT_TIMER_BASE STM32_TIM3_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM3EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM3
+# define HRT_TIMER_CLOCK STM32_APB1_TIM3_CLKIN
+# if CONFIG_STM32_TIM3
+# error must not set CONFIG_STM32_TIM3=y and HRT_TIMER=3
+# endif
+#elif HRT_TIMER == 4
+# define HRT_TIMER_BASE STM32_TIM4_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM4EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM4
+# define HRT_TIMER_CLOCK STM32_APB1_TIM4_CLKIN
+# if CONFIG_STM32_TIM4
+# error must not set CONFIG_STM32_TIM4=y and HRT_TIMER=4
+# endif
+#elif HRT_TIMER == 5
+# define HRT_TIMER_BASE STM32_TIM5_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM5EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM5
+# define HRT_TIMER_CLOCK STM32_APB1_TIM5_CLKIN
+# if CONFIG_STM32_TIM5
+# error must not set CONFIG_STM32_TIM5=y and HRT_TIMER=5
+# endif
+#elif HRT_TIMER == 8
+# define HRT_TIMER_BASE STM32_TIM8_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB2ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM8EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
+# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
+# if CONFIG_STM32_TIM8
+# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=6
+# endif
+#elif HRT_TIMER == 9
+# define HRT_TIMER_BASE STM32_TIM9_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM9EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1BRK
+# define HRT_TIMER_CLOCK STM32_APB1_TIM9_CLKIN
+# if CONFIG_STM32_TIM9
+# error must not set CONFIG_STM32_TIM9=y and HRT_TIMER=9
+# endif
+#elif HRT_TIMER == 10
+# define HRT_TIMER_BASE STM32_TIM10_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
+# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
+# if CONFIG_STM32_TIM10
+# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
+# endif
+#elif HRT_TIMER == 11
+# define HRT_TIMER_BASE STM32_TIM11_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
+# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
+# if CONFIG_STM32_TIM11
+# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
+# endif
+#else
+# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y
+#endif
+
+/*
+ * HRT clock must be a multiple of 1MHz greater than 1MHz
+ */
+#if (HRT_TIMER_CLOCK % 1000000) != 0
+# error HRT_TIMER_CLOCK must be a multiple of 1MHz
+#endif
+#if HRT_TIMER_CLOCK <= 1000000
+# error HRT_TIMER_CLOCK must be greater than 1MHz
+#endif
+
+/*
+ * Minimum/maximum deadlines.
+ *
+ * These are suitable for use with a 16-bit timer/counter clocked
+ * at 1MHz. The high-resolution timer need only guarantee that it
+ * not wrap more than once in the 50ms period for absolute time to
+ * be consistently maintained.
+ *
+ * The minimum deadline must be such that the time taken between
+ * reading a time and writing a deadline to the timer cannot
+ * result in missing the deadline.
+ */
+#define HRT_INTERVAL_MIN 50
+#define HRT_INTERVAL_MAX 50000
+
+/*
+ * Period of the free-running counter, in microseconds.
+ */
+#define HRT_COUNTER_PERIOD 65536
+
+/*
+ * Scaling factor(s) for the free-running counter; convert an input
+ * in counts to a time in microseconds.
+ */
+#define HRT_COUNTER_SCALE(_c) (_c)
+
+/*
+ * Timer register accessors
+ */
+#define REG(_reg) (*(volatile uint32_t *)(HRT_TIMER_BASE + _reg))
+
+#define rCR1 REG(STM32_GTIM_CR1_OFFSET)
+#define rCR2 REG(STM32_GTIM_CR2_OFFSET)
+#define rSMCR REG(STM32_GTIM_SMCR_OFFSET)
+#define rDIER REG(STM32_GTIM_DIER_OFFSET)
+#define rSR REG(STM32_GTIM_SR_OFFSET)
+#define rEGR REG(STM32_GTIM_EGR_OFFSET)
+#define rCCMR1 REG(STM32_GTIM_CCMR1_OFFSET)
+#define rCCMR2 REG(STM32_GTIM_CCMR2_OFFSET)
+#define rCCER REG(STM32_GTIM_CCER_OFFSET)
+#define rCNT REG(STM32_GTIM_CNT_OFFSET)
+#define rPSC REG(STM32_GTIM_PSC_OFFSET)
+#define rARR REG(STM32_GTIM_ARR_OFFSET)
+#define rCCR1 REG(STM32_GTIM_CCR1_OFFSET)
+#define rCCR2 REG(STM32_GTIM_CCR2_OFFSET)
+#define rCCR3 REG(STM32_GTIM_CCR3_OFFSET)
+#define rCCR4 REG(STM32_GTIM_CCR4_OFFSET)
+#define rDCR REG(STM32_GTIM_DCR_OFFSET)
+#define rDMAR REG(STM32_GTIM_DMAR_OFFSET)
+
+/*
+ * Specific registers and bits used by HRT sub-functions
+ */
+#if HRT_TIMER_CHANNEL == 1
+# define rCCR_HRT rCCR1 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC1IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC1IF /* interrupt status for HRT */
+#elif HRT_TIMER_CHANNEL == 2
+# define rCCR_HRT rCCR2 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC2IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC2IF /* interrupt status for HRT */
+#elif HRT_TIMER_CHANNEL == 3
+# define rCCR_HRT rCCR3 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC3IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC3IF /* interrupt status for HRT */
+#elif HRT_TIMER_CHANNEL == 4
+# define rCCR_HRT rCCR4 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC4IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC4IF /* interrupt status for HRT */
+#else
+# error HRT_TIMER_CHANNEL must be a value between 1 and 4
+#endif
+
+/*
+ * Queue of callout entries.
+ */
+static struct sq_queue_s callout_queue;
+
+/* timer-specific functions */
+static void hrt_tim_init(void);
+static int hrt_tim_isr(int irq, void *context);
+
+/* callout list manipulation */
+static void hrt_call_internal(struct hrt_call *entry,
+ hrt_abstime deadline,
+ hrt_abstime interval,
+ hrt_callout callout,
+ void *arg);
+static void hrt_call_enter(struct hrt_call *entry);
+static void hrt_call_reschedule(void);
+static void hrt_call_invoke(void);
+
+/*
+ * Specific registers and bits used by PPM sub-functions
+ */
+#ifdef CONFIG_HRT_PPM
+# if HRT_PPM_CHANNEL == 1
+# define rCCR_PPM rCCR1 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC1IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC1IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC1OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 1 /* not on TI1/TI2 */
+# define CCMR2_PPM 0 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC1E | GTIM_CCER_CC1P | GTIM_CCER_CC1NP) /* CC1, both edges */
+# elif HRT_PPM_CHANNEL == 2
+# define rCCR_PPM rCCR2 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC2IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC2IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC2OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 2 /* not on TI1/TI2 */
+# define CCMR2_PPM 0 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC2E | GTIM_CCER_CC2P | GTIM_CCER_CC2NP) /* CC2, both edges */
+# elif HRT_PPM_CHANNEL == 3
+# define rCCR_PPM rCCR3 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC3IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC3IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC3OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 0 /* not on TI1/TI2 */
+# define CCMR2_PPM 1 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC3E | GTIM_CCER_CC3P | GTIM_CCER_CC3NP) /* CC3, both edges */
+# elif HRT_PPM_CHANNEL == 4
+# define rCCR_PPM rCCR4 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC4IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC4IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC4OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 0 /* not on TI1/TI2 */
+# define CCMR2_PPM 2 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
+# else
+# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set
+# endif
+
+/*
+ * PPM decoder tuning parameters
+ */
+# define PPM_MAX_PULSE_WIDTH 500 /* maximum width of a pulse */
+# define PPM_MIN_CHANNEL_VALUE 750 /* shortest valid channel signal */
+# define PPM_MAX_CHANNEL_VALUE 2400 /* longest valid channel signal */
+# define PPM_MIN_START 5000 /* shortest valid start gap */
+
+/* decoded PPM buffer */
+#define PPM_MAX_CHANNELS 12
+uint16_t ppm_buffer[PPM_MAX_CHANNELS];
+unsigned ppm_decoded_channels;
+
+/* PPM edge history */
+uint16_t ppm_edge_history[32];
+unsigned ppm_edge_next;
+
+/* PPM pulse history */
+uint16_t ppm_pulse_history[32];
+unsigned ppm_pulse_next;
+
+static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
+
+/* PPM decoder state machine */
+struct {
+ uint16_t last_edge; /* last capture time */
+ uint16_t last_mark; /* last significant edge */
+ unsigned next_channel;
+ enum {
+ UNSYNCH = 0,
+ ARM,
+ ACTIVE,
+ INACTIVE
+ } phase;
+} ppm;
+
+static void hrt_ppm_decode(uint32_t status);
+
+#else
+/* disable the PPM configuration */
+# define rCCR_PPM 0
+# define DIER_PPM 0
+# define SR_INT_PPM 0
+# define SR_OVF_PPM 0
+# define CCMR1_PPM 0
+# define CCMR2_PPM 0
+# define CCER_PPM 0
+#endif /* CONFIG_HRT_PPM */
+
+/*
+ * Initialise the timer we are going to use.
+ *
+ * We expect that we'll own one of the reduced-function STM32 general
+ * timers, and that we can use channel 1 in compare mode.
+ */
+static void
+hrt_tim_init(void)
+{
+ /* clock/power on our timer */
+ modifyreg32(HRT_TIMER_POWER_REG, 0, HRT_TIMER_POWER_BIT);
+
+ /* claim our interrupt vector */
+ irq_attach(HRT_TIMER_VECTOR, hrt_tim_isr);
+
+ /* disable and configure the timer */
+ rCR1 = 0;
+ rCR2 = 0;
+ rSMCR = 0;
+ rDIER = DIER_HRT | DIER_PPM;
+ rCCER = 0; /* unlock CCMR* registers */
+ rCCMR1 = CCMR1_PPM;
+ rCCMR2 = CCMR2_PPM;
+ rCCER = CCER_PPM;
+ rDCR = 0;
+
+ /* configure the timer to free-run at 1MHz */
+ rPSC = (HRT_TIMER_CLOCK / 1000000) - 1; /* this really only works for whole-MHz clocks */
+
+ /* run the full span of the counter */
+ rARR = 0xffff;
+
+ /* set an initial capture a little ways off */
+ rCCR_HRT = 1000;
+
+ /* generate an update event; reloads the counter, all registers */
+ rEGR = GTIM_EGR_UG;
+
+ /* enable the timer */
+ rCR1 = GTIM_CR1_CEN;
+
+ /* enable interrupts */
+ up_enable_irq(HRT_TIMER_VECTOR);
+}
+
+#ifdef CONFIG_HRT_PPM
+/*
+ * Handle the PPM decoder state machine.
+ */
+static void
+hrt_ppm_decode(uint32_t status)
+{
+ uint16_t count = rCCR_PPM;
+ uint16_t width;
+ uint16_t interval;
+ unsigned i;
+
+ /* if we missed an edge, we have to give up */
+ if (status & SR_OVF_PPM)
+ goto error;
+
+ /* how long since the last edge? */
+ width = count - ppm.last_edge;
+ ppm.last_edge = count;
+
+ ppm_edge_history[ppm_edge_next++] = width;
+ if (ppm_edge_next >= 32)
+ ppm_edge_next = 0;
+
+ /*
+ * if this looks like a start pulse, then push the last set of values
+ * and reset the state machine
+ */
+ if (width >= PPM_MIN_START) {
+
+ /* export the last set of samples if we got something sensible */
+ if (ppm.next_channel > 4) {
+ for (i = 0; i < ppm.next_channel && i < PPM_MAX_CHANNELS; i++)
+ ppm_buffer[i] = ppm_temp_buffer[i];
+ ppm_decoded_channels = i;
+ }
+
+ /* reset for the next frame */
+ ppm.next_channel = 0;
+
+ /* next edge is the reference for the first channel */
+ ppm.phase = ARM;
+
+ return;
+ }
+
+ switch (ppm.phase) {
+ case UNSYNCH:
+ /* we are waiting for a start pulse - nothing useful to do here */
+ return;
+
+ case ARM:
+ /* we expect a pulse giving us the first mark */
+ if (width > PPM_MAX_PULSE_WIDTH)
+ goto error; /* pulse was too long */
+
+ /* record the mark timing, expect an inactive edge */
+ ppm.last_mark = count;
+ ppm.phase = INACTIVE;
+ return;
+
+ case INACTIVE:
+ /* this edge is not interesting, but now we are ready for the next mark */
+ ppm.phase = ACTIVE;
+ return;
+
+ case ACTIVE:
+ /* determine the interval from the last mark */
+ interval = count - ppm.last_mark;
+ ppm.last_mark = count;
+
+ ppm_pulse_history[ppm_pulse_next++] = interval;
+ if (ppm_pulse_next >= 32)
+ ppm_pulse_next = 0;
+
+ /* if the mark-mark timing is out of bounds, abandon the frame */
+ if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
+ goto error;
+
+ /* if we have room to store the value, do so */
+ if (ppm.next_channel < PPM_MAX_CHANNELS)
+ ppm_temp_buffer[ppm.next_channel++] = interval;
+
+ ppm.phase = INACTIVE;
+ return;
+
+ }
+
+ /* the state machine is corrupted; reset it */
+
+error:
+ /* we don't like the state of the decoder, reset it and try again */
+ ppm.phase = UNSYNCH;
+}
+#endif /* CONFIG_HRT_PPM */
+
+/*
+ * Handle the compare interupt by calling the callout dispatcher
+ * and then re-scheduling the next deadline.
+ */
+static int
+hrt_tim_isr(int irq, void *context)
+{
+ uint32_t status;
+
+ /* copy interrupt status */
+ status = rSR;
+
+ /* ack the interrupts we just read */
+ rSR = ~status;
+
+#ifdef CONFIG_HRT_PPM
+ /* was this a PPM edge? */
+ if (status & (SR_INT_PPM | SR_OVF_PPM))
+ hrt_ppm_decode(status);
+#endif
+
+ /* was this a timer tick? */
+ if (status & SR_INT_HRT) {
+ /* run any callouts that have met their deadline */
+ hrt_call_invoke();
+
+ /* and schedule the next interrupt */
+ hrt_call_reschedule();
+ }
+
+ return OK;
+}
+
+/*
+ * Fetch a never-wrapping absolute time value in microseconds from
+ * some arbitrary epoch shortly after system start.
+ */
+hrt_abstime
+hrt_absolute_time(void)
+{
+ hrt_abstime abstime;
+ uint32_t count;
+ uint32_t flags;
+
+ /*
+ * Counter state. Marked volatile as they may change
+ * inside this routine but outside the irqsave/restore
+ * pair. Discourage the compiler from moving loads/stores
+ * to these outside of the protected range.
+ */
+ static volatile hrt_abstime base_time;
+ static volatile uint32_t last_count;
+
+ /* prevent re-entry */
+ flags = irqsave();
+
+ /* get the current counter value */
+ count = rCNT;
+
+ /*
+ * Determine whether the counter has wrapped since the
+ * last time we're called.
+ *
+ * This simple test is sufficient due to the guarantee that
+ * we are always called at least once per counter period.
+ */
+ if (count < last_count)
+ base_time += HRT_COUNTER_PERIOD;
+
+ /* save the count for next time */
+ last_count = count;
+
+ /* compute the current time */
+ abstime = HRT_COUNTER_SCALE(base_time + count);
+
+ irqrestore(flags);
+
+ return abstime;
+}
+
+/*
+ * Convert a timespec to absolute time
+ */
+hrt_abstime
+ts_to_abstime(struct timespec *ts)
+{
+ hrt_abstime result;
+
+ result = (hrt_abstime)(ts->tv_sec) * 1000000;
+ result += ts->tv_nsec / 1000;
+
+ return result;
+}
+
+/*
+ * Convert absolute time to a timespec.
+ */
+void
+abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
+{
+ ts->tv_sec = abstime / 1000000;
+ abstime -= ts->tv_sec * 1000000;
+ ts->tv_nsec = abstime * 1000;
+}
+
+/*
+ * Initalise the high-resolution timing module.
+ */
+void
+hrt_init(void)
+{
+ sq_init(&callout_queue);
+ hrt_tim_init();
+
+#ifdef CONFIG_HRT_PPM
+ /* configure the PPM input pin */
+ stm32_configgpio(GPIO_PPM_IN);
+#endif
+}
+
+/*
+ * Call callout(arg) after interval has elapsed.
+ */
+void
+hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg)
+{
+ hrt_call_internal(entry,
+ hrt_absolute_time() + delay,
+ 0,
+ callout,
+ arg);
+}
+
+/*
+ * Call callout(arg) at calltime.
+ */
+void
+hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg)
+{
+ hrt_call_internal(entry, calltime, 0, callout, arg);
+}
+
+/*
+ * Call callout(arg) every period.
+ */
+void
+hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg)
+{
+ hrt_call_internal(entry,
+ hrt_absolute_time() + delay,
+ interval,
+ callout,
+ arg);
+}
+
+static void
+hrt_call_internal(struct hrt_call *entry, hrt_abstime deadline, hrt_abstime interval, hrt_callout callout, void *arg)
+{
+ irqstate_t flags = irqsave();
+
+ /* if the entry is currently queued, remove it */
+ if (entry->deadline != 0)
+ sq_rem(&entry->link, &callout_queue);
+
+ entry->deadline = deadline;
+ entry->period = interval;
+ entry->callout = callout;
+ entry->arg = arg;
+
+ hrt_call_enter(entry);
+
+ irqrestore(flags);
+}
+
+/*
+ * If this returns true, the call has been invoked and removed from the callout list.
+ *
+ * Always returns false for repeating callouts.
+ */
+bool
+hrt_called(struct hrt_call *entry)
+{
+ return (entry->deadline == 0);
+}
+
+/*
+ * Remove the entry from the callout list.
+ */
+void
+hrt_cancel(struct hrt_call *entry)
+{
+ irqstate_t flags = irqsave();
+
+ sq_rem(&entry->link, &callout_queue);
+ entry->deadline = 0;
+
+ /* if this is a periodic call being removed by the callout, prevent it from
+ * being re-entered when the callout returns.
+ */
+ entry->period = 0;
+
+ irqrestore(flags);
+}
+
+static void
+hrt_call_enter(struct hrt_call *entry)
+{
+ struct hrt_call *call, *next;
+
+ call = (struct hrt_call *)sq_peek(&callout_queue);
+
+ if ((call == NULL) || (entry->deadline < call->deadline)) {
+ sq_addfirst(&entry->link, &callout_queue);
+ //lldbg("call enter at head, reschedule\n");
+ /* we changed the next deadline, reschedule the timer event */
+ hrt_call_reschedule();
+ } else {
+ do {
+ next = (struct hrt_call *)sq_next(&call->link);
+ if ((next == NULL) || (entry->deadline < next->deadline)) {
+ //lldbg("call enter after head\n");
+ sq_addafter(&call->link, &entry->link, &callout_queue);
+ break;
+ }
+ } while ((call = next) != NULL);
+ }
+
+ //lldbg("scheduled\n");
+}
+
+static void
+hrt_call_invoke(void)
+{
+ struct hrt_call *call;
+ hrt_abstime deadline;
+
+ while (true) {
+ /* get the current time */
+ hrt_abstime now = hrt_absolute_time();
+
+ call = (struct hrt_call *)sq_peek(&callout_queue);
+ if (call == NULL)
+ break;
+ if (call->deadline > now)
+ break;
+
+ sq_rem(&call->link, &callout_queue);
+ //lldbg("call pop\n");
+
+ /* save the intended deadline for periodic calls */
+ deadline = call->deadline;
+
+ /* zero the deadline, as the call has occurred */
+ call->deadline = 0;
+
+ /* invoke the callout (if there is one) */
+ if (call->callout) {
+ //lldbg("call %p: %p(%p)\n", call, call->callout, call->arg);
+ call->callout(call->arg);
+ }
+
+ /* if the callout has a non-zero period, it has to be re-entered */
+ if (call->period != 0) {
+ call->deadline = deadline + call->period;
+ hrt_call_enter(call);
+ }
+ }
+}
+
+/*
+ * Reschedule the next timer interrupt.
+ *
+ * This routine must be called with interrupts disabled.
+ */
+static void
+hrt_call_reschedule()
+{
+ hrt_abstime now = hrt_absolute_time();
+ struct hrt_call *next = (struct hrt_call *)sq_peek(&callout_queue);
+ hrt_abstime deadline = now + HRT_INTERVAL_MAX;
+
+ /*
+ * Determine what the next deadline will be.
+ *
+ * Note that we ensure that this will be within the counter
+ * period, so that when we truncate all but the low 16 bits
+ * the next time the compare matches it will be the deadline
+ * we want.
+ *
+ * It is important for accurate timekeeping that the compare
+ * interrupt fires sufficiently often that the base_time update in
+ * hrt_absolute_time runs at least once per timer period.
+ */
+ if (next != NULL) {
+ //lldbg("entry in queue\n");
+ if (next->deadline <= (now + HRT_INTERVAL_MIN)) {
+ //lldbg("pre-expired\n");
+ /* set a minimal deadline so that we call ASAP */
+ deadline = now + HRT_INTERVAL_MIN;
+ } else if (next->deadline < deadline) {
+ //lldbg("due soon\n");
+ deadline = next->deadline;
+ }
+ }
+ //lldbg("schedule for %u at %u\n", (unsigned)(deadline & 0xffffffff), (unsigned)(now & 0xffffffff));
+
+ /* set the new compare value */
+ rCCR_HRT = deadline & 0xffff;
+}
+
+#endif /* CONFIG_HRT_TIMER */
diff --git a/nuttx/configs/px4fmu/src/up_leds.c b/nuttx/configs/px4fmu/src/up_leds.c
new file mode 100644
index 000000000..f7b76aa58
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_leds.c
@@ -0,0 +1,127 @@
+/****************************************************************************
+ * configs/px4fmu/src/up_leds.c
+ * arch/arm/src/board/up_leds.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+ /* Configure LED1-2 GPIOs for output */
+
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ if (led == 0)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+ if (led == 1)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED2, false);
+ }
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ if (led == 0)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+ if (led == 1)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+}
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/px4fmu/src/up_nsh.c b/nuttx/configs/px4fmu/src/up_nsh.c
new file mode 100644
index 000000000..6e092e3b4
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_nsh.c
@@ -0,0 +1,392 @@
+/****************************************************************************
+ * config/stm3210e_eval/src/up_nsh.c
+ * arch/arm/src/board/up_nsh.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/i2c.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/analog/adc.h>
+#include <nuttx/arch.h>
+
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+#include "stm32_uart.h"
+
+#include <arch/board/up_hrt.h>
+#include <arch/board/up_cpuload.h>
+#include <arch/board/drv_tone_alarm.h>
+#include <arch/board/up_adc.h>
+#include <arch/board/board.h>
+#include <arch/board/drv_bma180.h>
+#include <arch/board/drv_l3gd20.h>
+#include <arch/board/drv_hmc5883l.h>
+#include <arch/board/drv_mpu6000.h>
+#include <arch/board/drv_ms5611.h>
+#include <arch/board/drv_eeprom.h>
+#include <arch/board/drv_led.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: multiport_setup
+ *
+ * Description:
+ * Perform setup of the PX4FMU's multi function ports
+ *
+ ****************************************************************************/
+int multiport_setup(void)
+{
+ int result = OK;
+
+ return result;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi1;
+static struct spi_dev_s *spi3;
+static struct i2c_dev_s *i2c1;
+static struct i2c_dev_s *i2c2;
+static struct i2c_dev_s *i2c3;
+
+#include <math.h>
+
+#ifdef __cplusplus
+int matherr(struct __exception *e) {
+ return 1;
+}
+#else
+int matherr(struct exception *e) {
+ return 1;
+}
+#endif
+
+int nsh_archinitialize(void)
+{
+ int result;
+
+ /* INIT 1 Lowest level NuttX initialization has been done at this point, LEDs and UARTs are configured */
+
+ /* INIT 2 Configuring PX4 low-level peripherals, these will be always needed */
+
+ /* configure the high-resolution time/callout interface */
+#ifdef CONFIG_HRT_TIMER
+ hrt_init();
+#endif
+
+ /* configure CPU load estimation */
+ #ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+ #endif
+
+ /* set up the serial DMA polling */
+#ifdef SERIAL_HAVE_DMA
+ {
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+ }
+#endif
+
+ message("\r\n");
+
+ up_ledoff(LED_BLUE);
+ up_ledoff(LED_AMBER);
+
+ up_ledon(LED_BLUE);
+
+ /* Configure user-space led driver */
+ px4fmu_led_init();
+
+ /* Configure SPI-based devices */
+
+ spi1 = up_spiinitialize(1);
+ if (!spi1)
+ {
+ message("[boot] FAILED to initialize SPI port 1\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ // Setup 10 MHz clock (maximum rate the BMA180 can sustain)
+ SPI_SETFREQUENCY(spi1, 10000000);
+ SPI_SETBITS(spi1, 8);
+ SPI_SETMODE(spi1, SPIDEV_MODE3);
+ SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_ACCEL, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
+ up_udelay(20);
+
+ message("[boot] Successfully initialized SPI port 1\r\n");
+
+ /* initialize SPI peripherals redundantly */
+ int gyro_attempts = 0;
+ int gyro_fail = 0;
+
+ while (gyro_attempts < 5)
+ {
+ gyro_fail = l3gd20_attach(spi1, PX4_SPIDEV_GYRO);
+ gyro_attempts++;
+ if (gyro_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (gyro_fail) message("[boot] FAILED to attach L3GD20 gyro\r\n");
+
+ int acc_attempts = 0;
+ int acc_fail = 0;
+
+ while (acc_attempts < 5)
+ {
+ acc_fail = bma180_attach(spi1, PX4_SPIDEV_ACCEL);
+ acc_attempts++;
+ if (acc_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (acc_fail) message("[boot] FAILED to attach BMA180 accelerometer\r\n");
+
+ int mpu_attempts = 0;
+ int mpu_fail = 0;
+
+ while (mpu_attempts < 1)
+ {
+ mpu_fail = mpu6000_attach(spi1, PX4_SPIDEV_MPU);
+ mpu_attempts++;
+ if (mpu_fail == 0) break;
+ up_udelay(200);
+ }
+
+ if (mpu_fail) message("[boot] FAILED to attach MPU 6000 gyro/acc\r\n");
+
+ /* initialize I2C2 bus */
+
+ i2c2 = up_i2cinitialize(2);
+ if (!i2c2) {
+ message("[boot] FAILED to initialize I2C bus 2\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* set I2C2 speed */
+ I2C_SETFREQUENCY(i2c2, 400000);
+
+
+ i2c3 = up_i2cinitialize(3);
+ if (!i2c3) {
+ message("[boot] FAILED to initialize I2C bus 3\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* set I2C3 speed */
+ I2C_SETFREQUENCY(i2c3, 400000);
+
+ int mag_attempts = 0;
+ int mag_fail = 0;
+
+ while (mag_attempts < 5)
+ {
+ mag_fail = hmc5883l_attach(i2c2);
+ mag_attempts++;
+ if (mag_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (mag_fail) message("[boot] FAILED to attach HMC5883L magnetometer\r\n");
+
+ int baro_attempts = 0;
+ int baro_fail = 0;
+ while (baro_attempts < 5)
+ {
+ baro_fail = ms5611_attach(i2c2);
+ baro_attempts++;
+ if (baro_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (baro_fail) message("[boot] FAILED to attach MS5611 baro at addr #1 or #2 (0x76 or 0x77)\r\n");
+
+ /* try to attach, don't fail if device is not responding */
+ (void)eeprom_attach(i2c3, FMU_BASEBOARD_EEPROM_ADDRESS,
+ FMU_BASEBOARD_EEPROM_TOTAL_SIZE_BYTES,
+ FMU_BASEBOARD_EEPROM_PAGE_SIZE_BYTES,
+ FMU_BASEBOARD_EEPROM_PAGE_WRITE_TIME_US, "/dev/baseboard_eeprom", 1);
+
+ int eeprom_attempts = 0;
+ int eeprom_fail;
+ while (eeprom_attempts < 5)
+ {
+ /* try to attach, fail if device does not respond */
+ eeprom_fail = eeprom_attach(i2c2, FMU_ONBOARD_EEPROM_ADDRESS,
+ FMU_ONBOARD_EEPROM_TOTAL_SIZE_BYTES,
+ FMU_ONBOARD_EEPROM_PAGE_SIZE_BYTES,
+ FMU_ONBOARD_EEPROM_PAGE_WRITE_TIME_US, "/dev/eeprom", 1);
+ eeprom_attempts++;
+ if (eeprom_fail == OK) break;
+ up_udelay(1000);
+ }
+
+ if (eeprom_fail) message("[boot] FAILED to attach FMU EEPROM\r\n");
+
+ /* Report back sensor status */
+ if (acc_fail || gyro_fail || mag_fail || baro_fail || eeprom_fail)
+ {
+ up_ledon(LED_AMBER);
+ }
+
+#if defined(CONFIG_STM32_SPI3)
+ /* Get the SPI port */
+
+ message("[boot] Initializing SPI port 3\r\n");
+ spi3 = up_spiinitialize(3);
+ if (!spi3)
+ {
+ message("[boot] FAILED to initialize SPI port 3\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ message("[boot] Successfully initialized SPI port 3\r\n");
+
+ /* Now bind the SPI interface to the MMCSD driver */
+ result = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi3);
+ if (result != OK)
+ {
+ message("[boot] FAILED to bind SPI port 3 to the MMCSD driver\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ message("[boot] Successfully bound SPI port 3 to the MMCSD driver\r\n");
+#endif /* SPI3 */
+
+ /* initialize I2C1 bus */
+
+ i2c1 = up_i2cinitialize(1);
+ if (!i2c1) {
+ message("[boot] FAILED to initialize I2C bus 1\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* set I2C1 speed */
+ I2C_SETFREQUENCY(i2c1, 400000);
+
+ /* INIT 3: MULTIPORT-DEPENDENT INITIALIZATION */
+
+ /* Get board information if available */
+
+ /* Initialize the user GPIOs */
+ px4fmu_gpio_init();
+
+#ifdef CONFIG_ADC
+ int adc_state = adc_devinit();
+ if (adc_state != OK)
+ {
+ /* Try again */
+ adc_state = adc_devinit();
+ if (adc_state != OK)
+ {
+ /* Give up */
+ message("[boot] FAILED adc_devinit: %d\r\n", adc_state);
+ return -ENODEV;
+ }
+ }
+#endif
+
+ /* configure the tone generator */
+#ifdef CONFIG_TONE_ALARM
+ tone_alarm_init();
+#endif
+
+ return OK;
+}
diff --git a/nuttx/configs/px4fmu/src/up_pwm_servo.c b/nuttx/configs/px4fmu/src/up_pwm_servo.c
new file mode 100644
index 000000000..05daf1e97
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_pwm_servo.c
@@ -0,0 +1,344 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/*
+ * Servo driver supporting PWM servos connected to STM32 timer blocks.
+ *
+ * Works with any of the 'generic' or 'advanced' STM32 timers that
+ * have output pins, does not require an interrupt.
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <queue.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+
+#include <arch/board/board.h>
+#include <arch/board/up_pwm_servo.h>
+
+#include "chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "stm32_internal.h"
+#include "stm32_gpio.h"
+#include "stm32_tim.h"
+
+/* configuration limits */
+#define PWM_SERVO_MAX_TIMERS 2
+#define PWM_SERVO_MAX_CHANNELS 8
+
+/* default rate (in Hz) of PWM updates */
+static uint32_t pwm_update_rate = 50;
+
+/*
+ * Servo configuration for all of the pins that can be used as
+ * PWM outputs on FMU.
+ */
+
+/* array of timers dedicated to PWM servo use */
+static const struct pwm_servo_timer {
+ uint32_t base;
+ uint32_t clock_register;
+ uint32_t clock_bit;
+ uint32_t clock_freq;
+} pwm_timers[] = {
+ {
+ .base = STM32_TIM2_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM2EN,
+ .clock_freq = STM32_APB1_TIM2_CLKIN
+ }
+};
+
+/* array of channels in logical order */
+static const struct pwm_servo_channel {
+ uint32_t gpio;
+ uint8_t timer_index;
+ uint8_t timer_channel;
+ servo_position_t default_value;
+} pwm_channels[] = {
+ {
+ .gpio = GPIO_TIM2_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1000,
+ }
+};
+
+
+#define REG(_tmr, _reg) (*(volatile uint32_t *)(pwm_timers[_tmr].base + _reg))
+
+#define rCR1(_tmr) REG(_tmr, STM32_GTIM_CR1_OFFSET)
+#define rCR2(_tmr) REG(_tmr, STM32_GTIM_CR2_OFFSET)
+#define rSMCR(_tmr) REG(_tmr, STM32_GTIM_SMCR_OFFSET)
+#define rDIER(_tmr) REG(_tmr, STM32_GTIM_DIER_OFFSET)
+#define rSR(_tmr) REG(_tmr, STM32_GTIM_SR_OFFSET)
+#define rEGR(_tmr) REG(_tmr, STM32_GTIM_EGR_OFFSET)
+#define rCCMR1(_tmr) REG(_tmr, STM32_GTIM_CCMR1_OFFSET)
+#define rCCMR2(_tmr) REG(_tmr, STM32_GTIM_CCMR2_OFFSET)
+#define rCCER(_tmr) REG(_tmr, STM32_GTIM_CCER_OFFSET)
+#define rCNT(_tmr) REG(_tmr, STM32_GTIM_CNT_OFFSET)
+#define rPSC(_tmr) REG(_tmr, STM32_GTIM_PSC_OFFSET)
+#define rARR(_tmr) REG(_tmr, STM32_GTIM_ARR_OFFSET)
+#define rCCR1(_tmr) REG(_tmr, STM32_GTIM_CCR1_OFFSET)
+#define rCCR2(_tmr) REG(_tmr, STM32_GTIM_CCR2_OFFSET)
+#define rCCR3(_tmr) REG(_tmr, STM32_GTIM_CCR3_OFFSET)
+#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
+#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
+#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
+
+static void
+pwm_timer_init(unsigned timer)
+{
+ /* enable the timer clock before we try to talk to it */
+ modifyreg32(pwm_timers[timer].clock_register, 0, pwm_timers[timer].clock_bit);
+
+ /* disable and configure the timer */
+ rCR1(timer) = 0;
+ rCR2(timer) = 0;
+ rSMCR(timer) = 0;
+ rDIER(timer) = 0;
+ rCCER(timer) = 0;
+ rCCMR1(timer) = 0;
+ rCCMR2(timer) = 0;
+ rCCER(timer) = 0;
+ rDCR(timer) = 0;
+
+ /* configure the timer to free-run at 1MHz */
+ rPSC(timer) = pwm_timers[timer].clock_freq / 1000000;
+
+ /* and update at the desired rate */
+ rARR(timer) = 1000000 / pwm_update_rate;
+
+ /* generate an update event; reloads the counter and all registers */
+ rEGR(timer) = GTIM_EGR_UG;
+
+ /* note that the timer is left disabled - arming is performed separately */
+}
+
+static void
+pwm_timer_set_rate(unsigned timer, unsigned rate)
+{
+ /* configure the timer to update at the desired rate */
+ rARR(timer) = 1000000 / pwm_update_rate;
+
+ /* generate an update event; reloads the counter and all registers */
+ rEGR(timer) = GTIM_EGR_UG;
+}
+
+static void
+pwm_channel_init(unsigned channel)
+{
+ unsigned timer = pwm_channels[channel].timer_index;
+
+ /* configure the GPIO first */
+ stm32_configgpio(pwm_channels[channel].gpio);
+
+ /* configure the channel */
+ switch (pwm_channels[channel].timer_channel) {
+ case 1:
+ rCCMR1(timer) |= (6 << 4);
+ rCCR1(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 0);
+ break;
+ case 2:
+ rCCMR1(timer) |= (6 << 12);
+ rCCR2(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 4);
+ break;
+ case 3:
+ rCCMR2(timer) |= (6 << 4);
+ rCCR3(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 8);
+ break;
+ case 4:
+ rCCMR2(timer) |= (6 << 12);
+ rCCR4(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 12);
+ break;
+ }
+}
+
+int
+up_pwm_servo_set(unsigned channel, servo_position_t value)
+{
+ if (channel >= PWM_SERVO_MAX_CHANNELS) {
+ lldbg("pwm_channel_set: bogus channel %u\n", channel);
+ return -1;
+ }
+
+ unsigned timer = pwm_channels[channel].timer_index;
+
+ /* test timer for validity */
+ if ((pwm_timers[timer].base == 0) ||
+ (pwm_channels[channel].gpio == 0))
+ return -1;
+
+ /* configure the channel */
+ switch (pwm_channels[channel].timer_channel) {
+ case 1:
+ rCCR1(timer) = value;
+ break;
+ case 2:
+ rCCR2(timer) = value;
+ break;
+ case 3:
+ rCCR3(timer) = value;
+ break;
+ case 4:
+ rCCR4(timer) = value;
+ break;
+ default:
+ return -1;
+ }
+ return 0;
+}
+
+servo_position_t
+up_pwm_servo_get(unsigned channel)
+{
+ if (channel >= PWM_SERVO_MAX_CHANNELS) {
+ lldbg("pwm_channel_get: bogus channel %u\n", channel);
+ return 0;
+ }
+
+ unsigned timer = pwm_channels[channel].timer_index;
+ servo_position_t value = 0;
+
+ /* test timer for validity */
+ if ((pwm_timers[timer].base == 0) ||
+ (pwm_channels[channel].gpio == 0))
+ return 0;
+
+ /* configure the channel */
+ switch (pwm_channels[channel].timer_channel) {
+ case 1:
+ value = rCCR1(timer);
+ break;
+ case 2:
+ value = rCCR2(timer);
+ break;
+ case 3:
+ value = rCCR3(timer);
+ break;
+ case 4:
+ value = rCCR4(timer);
+ break;
+ }
+ return value;
+}
+
+int
+up_pwm_servo_init(uint32_t channel_mask)
+{
+ /* do basic timer initialisation first */
+ for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
+ if (pwm_timers[i].base != 0)
+ pwm_timer_init(i);
+ }
+
+ /* now init channels */
+ for (unsigned i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
+ /* don't do init for disabled channels; this leaves the pin configs alone */
+ if (((1<<i) & channel_mask) && (pwm_channels[i].gpio != 0))
+ pwm_channel_init(i);
+ }
+ return OK;
+}
+
+void
+up_pwm_servo_deinit(void)
+{
+ /* disable the timers */
+ up_pwm_servo_arm(false);
+}
+
+int
+up_pwm_servo_set_rate(unsigned rate)
+{
+ if ((rate < 50) || (rate > 400))
+ return -ERANGE;
+
+ for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
+ if (pwm_timers[i].base != 0)
+ pwm_timer_set_rate(i, rate);
+ }
+ return OK;
+}
+
+void
+up_pwm_servo_arm(bool armed)
+{
+ /*
+ * XXX this is inelgant and in particular will either jam outputs at whatever level
+ * they happen to be at at the time the timers stop or generate runts.
+ * The right thing is almost certainly to kill auto-reload on the timers so that
+ * they just stop at the end of their count for disable, and to reset/restart them
+ * for enable.
+ */
+
+ /* iterate timers and arm/disarm appropriately */
+ for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
+ if (pwm_timers[i].base != 0)
+ rCR1(i) = armed ? GTIM_CR1_CEN : 0;
+ }
+}
diff --git a/nuttx/configs/px4fmu/src/up_spi.c b/nuttx/configs/px4fmu/src/up_spi.c
new file mode 100644
index 000000000..ea34c30ce
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_spi.c
@@ -0,0 +1,192 @@
+/************************************************************************************
+ * configs/px4fmu/src/up_spi.c
+ * arch/arm/src/board/up_spi.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG too) */
+
+#undef SPI_DEBUG /* Define to enable debug */
+#undef SPI_VERBOSE /* Define to enable verbose debug */
+
+#ifdef SPI_DEBUG
+# define spidbg lldbg
+# ifdef SPI_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# undef SPI_VERBOSE
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+void weak_function stm32_spiinitialize(void)
+{
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL);
+ stm32_configgpio(GPIO_SPI_CS_MPU);
+ stm32_configgpio(GPIO_SPI_CS_SDCARD);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 1);
+}
+
+/****************************************************************************
+ * Name: stm32_spi1/2/3select and stm32_spi1/2/3status
+ *
+ * Description:
+ * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be
+ * provided by board-specific logic. They are implementations of the select
+ * and status methods of the SPI interface defined by struct spi_ops_s (see
+ * include/nuttx/spi.h). All other methods (including up_spiinitialize())
+ * are provided by common STM32 logic. To use this common SPI logic on your
+ * board:
+ *
+ * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select
+ * pins.
+ * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your
+ * board-specific logic. These functions will perform chip selection and
+ * status operations using GPIOs in the way your board is configured.
+ * 3. Add a calls to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_SPI1
+void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, selected);
+ break;
+ case PX4_SPIDEV_ACCEL:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, selected);
+ break;
+ case PX4_SPIDEV_MPU:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
+ break;
+ default:
+ spidbg("devid: %d - unexpected\n", devid);
+ break;
+
+ }
+}
+
+uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 0);
+}
+
+uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* this is actually bogus, but PX4 has no way to sense the presence of an SD card */
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */
diff --git a/nuttx/configs/px4fmu/src/up_usbdev.c b/nuttx/configs/px4fmu/src/up_usbdev.c
new file mode 100644
index 000000000..4ef105e91
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_usbdev.c
@@ -0,0 +1,105 @@
+/************************************************************************************
+ * configs/stm32f4discovery/src/up_usbdev.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "up_arch.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the STM3210E-EVAL board.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void)
+{
+ /* The OTG FS has an internal soft pull-up */
+
+ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
+
+#ifdef CONFIG_STM32_OTGFS
+ stm32_configgpio(GPIO_OTGFS_VBUS);
+ /* XXX We only support device mode
+ stm32_configgpio(GPIO_OTGFS_PWRON);
+ stm32_configgpio(GPIO_OTGFS_OVER);
+ */
+#endif
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+