summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-06-01 00:50:15 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-06-01 00:50:15 +0200
commitbdabaab5bb726e012ef841528fb89a7cb6e0101b (patch)
treef0e6f57b9fb9d404df6d8f23388a1f98a65f14b2 /nuttx/configs
parent3faa01af062a46732149d35221c656e0e7f04323 (diff)
downloadpx4-nuttx-bdabaab5bb726e012ef841528fb89a7cb6e0101b.tar.gz
px4-nuttx-bdabaab5bb726e012ef841528fb89a7cb6e0101b.tar.bz2
px4-nuttx-bdabaab5bb726e012ef841528fb89a7cb6e0101b.zip
Updated FMU and IO configs
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/Kconfig8
-rw-r--r--nuttx/configs/px4fmu-v1/src/Makefile60
-rw-r--r--nuttx/configs/px4fmu-v1/src/empty.c4
-rw-r--r--nuttx/configs/px4fmu-v1/src/px4fmu-v1-internal.h137
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_autoleds.c235
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_boot.c103
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_cxxinitialize.c155
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_idle.c119
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_nsh.c155
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_spi.c199
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_stackcheck.c40
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_usb.c124
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_userleds.c134
-rw-r--r--nuttx/configs/px4fmu-v1/src/up_watchdog.c136
-rw-r--r--nuttx/configs/px4io-v1/Kconfig8
-rwxr-xr-xnuttx/configs/px4io-v1/README.txt806
-rw-r--r--nuttx/configs/px4io-v1/common/Make.defs175
-rwxr-xr-xnuttx/configs/px4io-v1/common/ld.script129
-rwxr-xr-xnuttx/configs/px4io-v1/common/setenv.sh47
-rwxr-xr-xnuttx/configs/px4io-v1/include/README.txt1
-rwxr-xr-xnuttx/configs/px4io-v1/include/board.h172
-rw-r--r--nuttx/configs/px4io-v1/include/drv_i2c_device.h42
-rw-r--r--nuttx/configs/px4io-v1/io/Make.defs3
-rw-r--r--nuttx/configs/px4io-v1/io/appconfig32
-rwxr-xr-xnuttx/configs/px4io-v1/io/defconfig552
-rwxr-xr-xnuttx/configs/px4io-v1/io/setenv.sh47
-rw-r--r--nuttx/configs/px4io-v1/nsh/Make.defs3
-rw-r--r--nuttx/configs/px4io-v1/nsh/appconfig43
-rwxr-xr-xnuttx/configs/px4io-v1/nsh/defconfig565
-rwxr-xr-xnuttx/configs/px4io-v1/nsh/setenv.sh47
-rw-r--r--nuttx/configs/px4io-v1/src/Makefile84
-rw-r--r--nuttx/configs/px4io-v1/src/README.txt1
-rw-r--r--nuttx/configs/px4io-v1/src/drv_i2c_device.c618
-rw-r--r--nuttx/configs/px4io-v1/src/empty.c4
34 files changed, 3406 insertions, 1582 deletions
diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig
index e2dad70cb..30cf7a5b8 100644
--- a/nuttx/configs/Kconfig
+++ b/nuttx/configs/Kconfig
@@ -542,6 +542,13 @@ config ARCH_BOARD_PX4FMU_V1
---help---
PX4 flight management unit v1.x
+config ARCH_BOARD_PX4IO_V1
+ bool "PX4IO v1.x"
+ depends on CONFIG_ARCH_CHIP_STM32F100C8
+ select ARCH_HAVE_LEDS
+ ---help---
+ PX4 input / output unit v1.x
+
config ARCH_BOARD_STM32F100RC_GENERIC
bool "STMicro STM32F100RC generic board"
depends on ARCH_CHIP_STM32F100RC
@@ -789,6 +796,7 @@ config ARCH_BOARD
default "stm32f3discovery" if ARCH_BOARD_STM32F3_DISCOVERY
default "stm32f4discovery" if ARCH_BOARD_STM32F4_DISCOVERY
default "px4fmu-v1" if ARCH_BOARD_PX4FMU_V1
+ default "px4io-v1" if ARCH_BOARD_PX4IO_V1
default "stm32ldiscovery" if ARCH_BOARD_STM32L_DISCOVERY
default "mikroe-stm32f4" if ARCH_BOARD_MIKROE_STM32F4
default "sure-pic32mx" if ARCH_BOARD_SUREPIC32MX
diff --git a/nuttx/configs/px4fmu-v1/src/Makefile b/nuttx/configs/px4fmu-v1/src/Makefile
index 9b914e52a..6ef8b7d6a 100644
--- a/nuttx/configs/px4fmu-v1/src/Makefile
+++ b/nuttx/configs/px4fmu-v1/src/Makefile
@@ -1,7 +1,7 @@
############################################################################
-# configs/stm32f4discovery/src/Makefile
+# configs/px4fmu-v1/src/Makefile
#
-# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -35,55 +35,24 @@
-include $(TOPDIR)/Make.defs
-CFLAGS += -I$(TOPDIR)/sched
+CFLAGS += -I$(TOPDIR)/sched
-ASRCS =
-AOBJS = $(ASRCS:.S=$(OBJEXT))
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_boot.c up_spi.c up_stackcheck.c
+CSRCS = empty.c
+COBJS = $(CSRCS:.c=$(OBJEXT))
-ifeq ($(CONFIG_HAVE_CXX),y)
-CSRCS += up_cxxinitialize.c
-endif
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
-ifeq ($(CONFIG_ARCH_LEDS),y)
-CSRCS += up_autoleds.c
-else
-CSRCS += up_userleds.c
-endif
-
-ifeq ($(CONFIG_STM32_OTGFS),y)
-CSRCS += up_usb.c
-endif
-
-ifeq ($(CONFIG_WATCHDOG),y)
-CSRCS += up_watchdog.c
-endif
-
-ifeq ($(CONFIG_NSH_ARCHINIT),y)
-CSRCS += up_nsh.c
-endif
-
-ifeq ($(CONFIG_IDLE_CUSTOM),y)
-CSRCS += up_idle.c
-endif
-
-COBJS = $(CSRCS:.c=$(OBJEXT))
-
-SRCS = $(ASRCS) $(CSRCS)
-OBJS = $(AOBJS) $(COBJS)
-
-ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-ifeq ($(CONFIG_WINDOWS_NATIVE),y)
- CFLAGS += -I$(ARCH_SRCDIR)\chip -I$(ARCH_SRCDIR)\common -I$(ARCH_SRCDIR)\armv7-m
-else
+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}"
+ 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
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
endif
all: libboard$(LIBEXT)
@@ -112,3 +81,4 @@ distclean: clean
$(call DELFILE, .depend)
-include Make.dep
+
diff --git a/nuttx/configs/px4fmu-v1/src/empty.c b/nuttx/configs/px4fmu-v1/src/empty.c
new file mode 100644
index 000000000..ace900866
--- /dev/null
+++ b/nuttx/configs/px4fmu-v1/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
diff --git a/nuttx/configs/px4fmu-v1/src/px4fmu-v1-internal.h b/nuttx/configs/px4fmu-v1/src/px4fmu-v1-internal.h
deleted file mode 100644
index 0639bbd55..000000000
--- a/nuttx/configs/px4fmu-v1/src/px4fmu-v1-internal.h
+++ /dev/null
@@ -1,137 +0,0 @@
-/****************************************************************************************************
- * configs/stm32f4discovery/src/stm32f4discovery-internal.h
- * arch/arm/src/board/stm32f4discovery-internal.n
- *
- * Copyright (C) 2011-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.
- *
- ****************************************************************************************************/
-
-#ifndef __CONFIGS_PX4FMU_V1_SRC_PX4FMU_V1_INTERNAL_H
-#define __CONFIGS_PX4FMU_V1_SRC_PX4FMU_V1_INTERNAL_H
-
-/****************************************************************************************************
- * Included Files
- ****************************************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/compiler.h>
-#include <stdint.h>
-
-/****************************************************************************************************
- * Definitions
- ****************************************************************************************************/
-/* Configuration ************************************************************************************/
-/* How many SPI modules does this chip support? */
-
-#if STM32_NSPI < 1
-# undef CONFIG_STM32_SPI1
-# undef CONFIG_STM32_SPI2
-# undef CONFIG_STM32_SPI3
-#elif STM32_NSPI < 2
-# undef CONFIG_STM32_SPI2
-# undef CONFIG_STM32_SPI3
-#elif STM32_NSPI < 3
-# undef CONFIG_STM32_SPI3
-#endif
-
-/* px4fmu-v1 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)
-
-/* 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)
-
-/* 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)
-
-/****************************************************************************************************
- * Public Types
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Public data
- ****************************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/****************************************************************************************************
- * Public Functions
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Name: stm32_spiinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the stm32f4discovery board.
- *
- ****************************************************************************************************/
-
-void weak_function stm32_spiinitialize(void);
-
-/****************************************************************************************************
- * Name: stm32_usbinitialize
- *
- * Description:
- * Called from stm32_usbinitialize very early in inialization to setup USB-related
- * GPIO pins for the STM32F4Discovery board.
- *
- ****************************************************************************************************/
-
-#ifdef CONFIG_STM32_OTGFS
-void weak_function stm32_usbinitialize(void);
-#endif
-
-/****************************************************************************************************
- * Name: stm32_usbhost_initialize
- *
- * Description:
- * Called at application startup time to initialize the USB host functionality. This function will
- * start a thread that will monitor for device connection/disconnection events.
- *
- ****************************************************************************************************/
-
-#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST)
-int stm32_usbhost_initialize(void);
-#endif
-
-#endif /* __ASSEMBLY__ */
-#endif /* __CONFIGS_PX4FMU_V1_SRC_PX4FMU_V1_INTERNAL_H */
-
diff --git a/nuttx/configs/px4fmu-v1/src/up_autoleds.c b/nuttx/configs/px4fmu-v1/src/up_autoleds.c
deleted file mode 100644
index 440c0cfa9..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_autoleds.c
+++ /dev/null
@@ -1,235 +0,0 @@
-/****************************************************************************
- * configs/stm32f4discovery/src/up_autoleds.c
- * arch/arm/src/board/up_autoleds.c
- *
- * Copyright (C) 2011-2013 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.h"
-#include "px4fmu-v1-internal.h"
-
-#ifdef CONFIG_ARCH_LEDS
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
- * with CONFIG_DEBUG_VERBOSE too)
- */
-
-#ifdef CONFIG_DEBUG_LEDS
-# define leddbg lldbg
-# define ledvdbg llvdbg
-#else
-# define leddbg(x...)
-# define ledvdbg(x...)
-#endif
-
-/* The following definitions map the encoded LED setting to GPIO settings */
-
-#define STM32F4_LED1 (1 << 0)
-#define STM32F4_LED2 (1 << 1)
-
-#define ON_SETBITS_SHIFT (0)
-#define ON_CLRBITS_SHIFT (4)
-#define OFF_SETBITS_SHIFT (8)
-#define OFF_CLRBITS_SHIFT (12)
-
-#define ON_BITS(v) ((v) & 0xff)
-#define OFF_BITS(v) (((v) >> 8) & 0x0ff)
-#define SETBITS(b) ((b) & 0x0f)
-#define CLRBITS(b) (((b) >> 4) & 0x0f)
-
-#define ON_SETBITS(v) (SETBITS(ON_BITS(v))
-#define ON_CLRBITS(v) (CLRBITS(ON_BITS(v))
-#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v))
-#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v))
-
-#define LED_STARTED_ON_SETBITS ((STM32F4_LED1) << ON_SETBITS_SHIFT)
-#define LED_STARTED_ON_CLRBITS ((STM32F4_LED2) << ON_CLRBITS_SHIFT)
-#define LED_STARTED_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_STARTED_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_CLRBITS_SHIFT)
-
-#define LED_HEAPALLOCATE_ON_SETBITS ((STM32F4_LED2) << ON_SETBITS_SHIFT)
-#define LED_HEAPALLOCATE_ON_CLRBITS ((STM32F4_LED1) << ON_CLRBITS_SHIFT)
-#define LED_HEAPALLOCATE_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_HEAPALLOCATE_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_CLRBITS_SHIFT)
-
-#define LED_IRQSENABLED_ON_SETBITS ((STM32F4_LED1) << ON_SETBITS_SHIFT)
-#define LED_IRQSENABLED_ON_CLRBITS ((STM32F4_LED2) << ON_CLRBITS_SHIFT)
-#define LED_IRQSENABLED_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_IRQSENABLED_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_CLRBITS_SHIFT)
-
-#define LED_STACKCREATED_ON_SETBITS ((STM32F4_LED1|STM32F4_LED2) << ON_SETBITS_SHIFT)
-#define LED_STACKCREATED_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
-#define LED_STACKCREATED_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_STACKCREATED_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_CLRBITS_SHIFT)
-
-#define LED_INIRQ_ON_SETBITS ((STM32F4_LED1) << ON_SETBITS_SHIFT)
-#define LED_INIRQ_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
-#define LED_INIRQ_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_INIRQ_OFF_CLRBITS ((STM32F4_LED1) << OFF_CLRBITS_SHIFT)
-
-#define LED_SIGNAL_ON_SETBITS ((STM32F4_LED2) << ON_SETBITS_SHIFT)
-#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
-#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_SIGNAL_OFF_CLRBITS ((STM32F4_LED2) << OFF_CLRBITS_SHIFT)
-
-#define LED_ASSERTION_ON_SETBITS ((STM32F4_LED1|STM32F4_LED2) << ON_SETBITS_SHIFT)
-#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
-#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_ASSERTION_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_CLRBITS_SHIFT)
-
-#define LED_PANIC_ON_SETBITS ((STM32F4_LED1|STM32F4_LED2) << ON_SETBITS_SHIFT)
-#define LED_PANIC_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
-#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
-#define LED_PANIC_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_CLRBITS_SHIFT)
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static const uint16_t g_ledbits[8] =
-{
- (LED_STARTED_ON_SETBITS | LED_STARTED_ON_CLRBITS |
- LED_STARTED_OFF_SETBITS | LED_STARTED_OFF_CLRBITS),
-
- (LED_HEAPALLOCATE_ON_SETBITS | LED_HEAPALLOCATE_ON_CLRBITS |
- LED_HEAPALLOCATE_OFF_SETBITS | LED_HEAPALLOCATE_OFF_CLRBITS),
-
- (LED_IRQSENABLED_ON_SETBITS | LED_IRQSENABLED_ON_CLRBITS |
- LED_IRQSENABLED_OFF_SETBITS | LED_IRQSENABLED_OFF_CLRBITS),
-
- (LED_STACKCREATED_ON_SETBITS | LED_STACKCREATED_ON_CLRBITS |
- LED_STACKCREATED_OFF_SETBITS | LED_STACKCREATED_OFF_CLRBITS),
-
- (LED_INIRQ_ON_SETBITS | LED_INIRQ_ON_CLRBITS |
- LED_INIRQ_OFF_SETBITS | LED_INIRQ_OFF_CLRBITS),
-
- (LED_SIGNAL_ON_SETBITS | LED_SIGNAL_ON_CLRBITS |
- LED_SIGNAL_OFF_SETBITS | LED_SIGNAL_OFF_CLRBITS),
-
- (LED_ASSERTION_ON_SETBITS | LED_ASSERTION_ON_CLRBITS |
- LED_ASSERTION_OFF_SETBITS | LED_ASSERTION_OFF_CLRBITS),
-
- (LED_PANIC_ON_SETBITS | LED_PANIC_ON_CLRBITS |
- LED_PANIC_OFF_SETBITS | LED_PANIC_OFF_CLRBITS)
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-static inline void led_clrbits(unsigned int clrbits)
-{
- if ((clrbits & STM32F4_LED1) != 0)
- {
- stm32_gpiowrite(GPIO_LED1, false);
- }
-
- if ((clrbits & STM32F4_LED2) != 0)
- {
- stm32_gpiowrite(GPIO_LED2, false);
- }
-
-}
-
-static inline void led_setbits(unsigned int setbits)
-{
- if ((setbits & STM32F4_LED1) != 0)
- {
- stm32_gpiowrite(GPIO_LED1, true);
- }
-
- if ((setbits & STM32F4_LED2) != 0)
- {
- stm32_gpiowrite(GPIO_LED2, true);
- }
-}
-
-static void led_setonoff(unsigned int bits)
-{
- led_clrbits(CLRBITS(bits));
- led_setbits(SETBITS(bits));
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_ledinit
- ****************************************************************************/
-
-void up_ledinit(void)
-{
- /* Configure LED1-4 GPIOs for output */
-
- stm32_configgpio(GPIO_LED1);
- stm32_configgpio(GPIO_LED2);
-}
-
-/****************************************************************************
- * Name: up_ledon
- ****************************************************************************/
-
-void up_ledon(int led)
-{
- led_setonoff(ON_BITS(g_ledbits[led]));
-}
-
-/****************************************************************************
- * Name: up_ledoff
- ****************************************************************************/
-
-void up_ledoff(int led)
-{
- led_setonoff(OFF_BITS(g_ledbits[led]));
-}
-
-#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/px4fmu-v1/src/up_boot.c b/nuttx/configs/px4fmu-v1/src/up_boot.c
deleted file mode 100644
index ee6f3d59f..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_boot.c
+++ /dev/null
@@ -1,103 +0,0 @@
-/************************************************************************************
- * configs/stm32f4discovery/src/up_boot.c
- * arch/arm/src/board/up_boot.c
- *
- * Copyright (C) 2011-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 <debug.h>
-
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "px4fmu-v1-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 chip selects if 1) SPI is not disabled, and 2) the weak function
- * stm32_spiinitialize() has been brought into the link.
- */
-
-#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI3)
- if (stm32_spiinitialize)
- {
- stm32_spiinitialize();
- }
-#endif
-
- /* Initialize USB if the 1) OTG FS controller is in the configuration and 2)
- * disabled, and 3) the weak function stm32_usbinitialize() has been brought
- * into the build. Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also
- * selected.
- */
-
-#ifdef CONFIG_STM32_OTGFS
- if (stm32_usbinitialize)
- {
- stm32_usbinitialize();
- }
-#endif
-
- /* Configure on-board LEDs if LED support has been selected. */
-
-#ifdef CONFIG_ARCH_LEDS
- up_ledinit();
-#endif
-}
diff --git a/nuttx/configs/px4fmu-v1/src/up_cxxinitialize.c b/nuttx/configs/px4fmu-v1/src/up_cxxinitialize.c
deleted file mode 100644
index 402dfb111..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_cxxinitialize.c
+++ /dev/null
@@ -1,155 +0,0 @@
-/************************************************************************************
- * configs/stm32f4discovery/src/up_cxxinitialize.c
- * arch/arm/src/board/up_cxxinitialize.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 <debug.h>
-
-#include <nuttx/arch.h>
-
-#include <arch/stm32/chip.h>
-#include "chip.h"
-
-#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-/* Debug ****************************************************************************/
-/* Non-standard debug that may be enabled just for testing the static constructors */
-
-#ifndef CONFIG_DEBUG
-# undef CONFIG_DEBUG_CXX
-#endif
-
-#ifdef CONFIG_DEBUG_CXX
-# define cxxdbg dbg
-# define cxxlldbg lldbg
-# ifdef CONFIG_DEBUG_VERBOSE
-# define cxxvdbg vdbg
-# define cxxllvdbg llvdbg
-# else
-# define cxxvdbg(x...)
-# define cxxllvdbg(x...)
-# endif
-#else
-# define cxxdbg(x...)
-# define cxxlldbg(x...)
-# define cxxvdbg(x...)
-# define cxxllvdbg(x...)
-#endif
-
-/************************************************************************************
- * Private Types
- ************************************************************************************/
-/* This type defines one entry in initialization array */
-
-typedef void (*initializer_t)(void);
-
-/************************************************************************************
- * External references
- ************************************************************************************/
-/* _sinit and _einit are symbols exported by the linker script that mark the
- * beginning and the end of the C++ initialization section.
- */
-
-extern initializer_t _sinit;
-extern initializer_t _einit;
-
-/* _stext and _etext are symbols exported by the linker script that mark the
- * beginning and the end of text.
- */
-
-extern uint32_t _stext;
-extern uint32_t _etext;
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/****************************************************************************
- * Name: up_cxxinitialize
- *
- * Description:
- * If C++ and C++ static constructors are supported, then this function
- * must be provided by board-specific logic in order to perform
- * initialization of the static C++ class instances.
- *
- * This function should then be called in the application-specific
- * user_start logic in order to perform the C++ initialization. NOTE
- * that no component of the core NuttX RTOS logic is involved; This
- * function defintion only provides the 'contract' between application
- * specific C++ code and platform-specific toolchain support
- *
- ***************************************************************************/
-
-void up_cxxinitialize(void)
-{
- initializer_t *initp;
-
- cxxdbg("_sinit: %p _einit: %p _stext: %p _etext: %p\n",
- &_sinit, &_einit, &_stext, &_etext);
-
- /* Visit each entry in the initialzation table */
-
- for (initp = &_sinit; initp != &_einit; initp++)
- {
- initializer_t initializer = *initp;
- cxxdbg("initp: %p initializer: %p\n", initp, initializer);
-
- /* Make sure that the address is non-NULL and lies in the text region
- * defined by the linker script. Some toolchains may put NULL values
- * or counts in the initialization table
- */
-
- if ((void*)initializer > (void*)&_stext && (void*)initializer < (void*)&_etext)
- {
- cxxdbg("Calling %p\n", initializer);
- initializer();
- }
- }
-}
-
-#endif /* CONFIG_HAVE_CXX && CONFIG_HAVE_CXXINITIALIZE */
-
diff --git a/nuttx/configs/px4fmu-v1/src/up_idle.c b/nuttx/configs/px4fmu-v1/src/up_idle.c
deleted file mode 100644
index 53caf9702..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_idle.c
+++ /dev/null
@@ -1,119 +0,0 @@
-/****************************************************************************
- * configs/stm32f4discovery/src/up_idle.c
- * arch/arm/src/board/up_idle.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Authors: Gregory Nutt <gnutt@nuttx.org>
- * Diego Sanchez <dsanchez@nx-engineering.com>
- *
- * 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 <arch/board/board.h>
-#include <nuttx/config.h>
-
-#include <nuttx/arch.h>
-#include <nuttx/clock.h>
-
-#include <debug.h>
-#include <nuttx/rtc.h>
-#include <arch/irq.h>
-
-#include "up_internal.h"
-#include "stm32_rcc.h"
-#include "stm32_exti.h"
-
-#include "px4fmu-v1-internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-/* Configuration ************************************************************/
-/* Does the board support an IDLE LED to indicate that the board is in the
- * IDLE state?
- */
-
-#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE)
-# define BEGIN_IDLE() up_ledon(LED_IDLE)
-# define END_IDLE() up_ledoff(LED_IDLE)
-#else
-# define BEGIN_IDLE()
-# define END_IDLE()
-#endif
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-#define up_idlepm()
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_idle
- *
- * Description:
- * up_idle() is the logic that will be executed when their is no other
- * ready-to-run task. This is processor idle time and will continue until
- * some interrupt occurs to cause a context switch from the idle task.
- *
- * Processing in this state may be processor-specific. e.g., this is where
- * power management operations might be performed.
- *
- ****************************************************************************/
-
-void up_idle(void)
-{
-#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
- /* If the system is idle and there are no timer interrupts, then process
- * "fake" timer interrupts. Hopefully, something will wake up.
- */
-
- sched_process_timer();
-#else
-
- /* Perform IDLE mode power management */
-
- BEGIN_IDLE();
- up_idlepm();
- END_IDLE();
-#endif
-}
-
diff --git a/nuttx/configs/px4fmu-v1/src/up_nsh.c b/nuttx/configs/px4fmu-v1/src/up_nsh.c
deleted file mode 100644
index c26a08539..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_nsh.c
+++ /dev/null
@@ -1,155 +0,0 @@
-/****************************************************************************
- * config/stm32f4discovery/src/up_nsh.c
- * arch/arm/src/board/up_nsh.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 <stdbool.h>
-#include <stdio.h>
-#include <debug.h>
-#include <errno.h>
-
-#ifdef CONFIG_SYSTEM_USBMONITOR
-# include <apps/usbmonitor.h>
-#endif
-
-#ifdef CONFIG_STM32_SPI3
-# include <nuttx/mmcsd.h>
-#endif
-
-#include "stm32.h"
-#include "px4fmu-v1-internal.h"
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Configuration ************************************************************/
-
-#define HAVE_USBDEV 1
-#define HAVE_USBMONITOR 1
-
-/* Can't support USB host or device features if USB OTG FS is not enabled */
-
-#ifndef CONFIG_STM32_OTGFS
-# undef HAVE_USBDEV
-# undef HAVE_USBMONITOR
-#endif
-
-/* Can't support USB device is USB device is not enabled */
-
-#ifndef CONFIG_USBDEV
-# undef HAVE_USBDEV
-# undef HAVE_USBMONITOR
-#endif
-
-/* Check if we should enable the USB monitor before starting NSH */
-
-#if !defined(CONFIG_USBDEV_TRACE) || !defined(CONFIG_SYSTEM_USBMONITOR)
-# undef HAVE_USBMONITOR
-#endif
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-# ifdef CONFIG_DEBUG
-# define message(...) lowsyslog(__VA_ARGS__)
-# else
-# define message(...) printf(__VA_ARGS__)
-# endif
-#else
-# ifdef CONFIG_DEBUG
-# define message lowsyslog
-# else
-# define message printf
-# endif
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nsh_archinitialize
- *
- * Description:
- * Perform architecture specific initialization
- *
- ****************************************************************************/
-
-int nsh_archinitialize(void)
-{
-#if defined(HAVE_USBMONITOR) || defined(CONFIG_STM32_SPI3)
- int ret;
-#endif
-
-#ifdef HAVE_USBMONITOR
- /* Start the USB Monitor */
-
- ret = usbmonitor_start(0, NULL);
- if (ret != OK)
- {
- message("nsh_archinitialize: Start USB monitor: %d\n", ret);
- }
-#endif
-
-#ifdef CONFIG_STM32_SPI3
- message("[boot] Initializing SPI port 3\n");
- struct spi_dev_s *spi3 = up_spiinitialize(3);
-
- if (!spi3) {
- message("[boot] FAILED to initialize SPI port 3\n");
- return -ENODEV;
- }
-
- message("[boot] Successfully initialized SPI port 3\n");
-
- /* Now bind the SPI interface to the MMCSD driver */
- ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi3);
-
- if (ret != OK) {
- message("[boot] FAILED to bind SPI port 3 to the MMCSD driver\n");
- return -ENODEV;
- }
-
- message("[boot] Successfully bound SPI port 3 to the MMCSD driver\n");
-#endif
-
- return OK;
-}
diff --git a/nuttx/configs/px4fmu-v1/src/up_spi.c b/nuttx/configs/px4fmu-v1/src/up_spi.c
deleted file mode 100644
index 63d1b8520..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_spi.c
+++ /dev/null
@@ -1,199 +0,0 @@
-/************************************************************************************
- * configs/stm32f4discovery/src/up_spi.c
- * arch/arm/src/board/up_spi.c
- *
- * Copyright (C) 2011-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 <stdint.h>
-#include <stdbool.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/spi.h>
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "chip.h"
-#include "stm32.h"
-#include "px4fmu-v1-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-v1 board.
- *
- ************************************************************************************/
-
-void stm32_spiinitialize(void)
-{
-#ifdef CONFIG_STM32_SPI1
- stm32_configgpio(GPIO_SPI_CS_GYRO);
- stm32_configgpio(GPIO_SPI_CS_ACCEL);
- stm32_configgpio(GPIO_SPI_CS_MPU);
-
- /* 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);
-#endif
-
-#ifdef CONFIG_STM32_SPI3
- stm32_configgpio(GPIO_SPI_CS_SDCARD);
- stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 1);
-#endif
-}
-
-/****************************************************************************
- * 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)
-{
- /* 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, 1);
- stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
- break;
-
- case PX4_SPIDEV_ACCEL:
- /* Making sure the other peripherals are not selected */
- stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
- stm32_gpiowrite(GPIO_SPI_CS_ACCEL, !selected);
- stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
- break;
-
- case PX4_SPIDEV_MPU:
- /* Making sure the other peripherals are not selected */
- stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
- stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
- stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
- break;
-
- default:
- break;
- }
-}
-
-uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
-{
- return SPI_STATUS_PRESENT;
-}
-#endif
-
-#ifdef CONFIG_STM32_SPI2
-# error SPI2 is not supported on this board.
-#endif
-
-#ifdef CONFIG_STM32_SPI3
-void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
-{
- /* there can only be one device on this bus, so always select it */
- stm32_gpiowrite(GPIO_SPI_CS_SDCARD, !selected);
-}
-
-uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
-{
- /* this is actually bogus, but px4fmu-v1 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-v1/src/up_stackcheck.c b/nuttx/configs/px4fmu-v1/src/up_stackcheck.c
deleted file mode 100644
index e8f02a863..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_stackcheck.c
+++ /dev/null
@@ -1,40 +0,0 @@
-
-
-void __cyg_profile_func_enter(void *func, void *caller) __attribute__((naked, no_instrument_function));
-void __cyg_profile_func_exit(void *func, void *caller) __attribute__((naked, no_instrument_function));
-void __stack_overflow_trap(void) __attribute__((naked, no_instrument_function));
-
-void
-__stack_overflow_trap(void)
-{
- /* if we get here, the stack has overflowed */
- asm ( "b .");
-}
-
-void
-__cyg_profile_func_enter(void *func, void *caller)
-{
- asm volatile (
- " mrs r2, ipsr \n" /* Check whether we are in interrupt mode */
- " cmp r2, #0 \n" /* since we don't switch r10 on interrupt entry, we */
- " bne 2f \n" /* can't detect overflow of the interrupt stack. */
- " \n"
- " sub r2, sp, #68 \n" /* compute stack pointer as though we just stacked a full frame */
- " mrs r1, control \n" /* Test CONTROL.FPCA to see whether we also need room for the FP */
- " tst r1, #4 \n" /* context. */
- " beq 1f \n"
- " sub r2, r2, #136 \n" /* subtract FP context frame size */
- "1: \n"
- " cmp r2, r10 \n" /* compare stack with limit */
- " bgt 2f \n" /* stack is above limit and thus OK */
- " b __stack_overflow_trap\n"
- "2: \n"
- " bx lr \n"
- );
-}
-
-void
-__cyg_profile_func_exit(void *func, void *caller)
-{
- asm volatile("bx lr");
-}
diff --git a/nuttx/configs/px4fmu-v1/src/up_usb.c b/nuttx/configs/px4fmu-v1/src/up_usb.c
deleted file mode 100644
index ab7d90c68..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_usb.c
+++ /dev/null
@@ -1,124 +0,0 @@
-/************************************************************************************
- * 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 <sched.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/usb/usbdev.h>
-#include <nuttx/usb/usbhost.h>
-#include <nuttx/usb/usbdev_trace.h>
-
-#include "up_arch.h"
-#include "stm32.h"
-#include "px4fmu-v1-internal.h"
-
-#ifdef CONFIG_STM32_OTGFS
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-
-#if defined(CONFIG_USBDEV)
-# define HAVE_USB 1
-#else
-# warning "CONFIG_STM32_OTGFS is enabled but not CONFIG_USBDEV"
-# undef HAVE_USB
-#endif
-
-/************************************************************************************
- * Private Data
- ************************************************************************************/
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: stm32_usbinitialize
- *
- * Description:
- * Called from stm32_usbinitialize very early in inialization to setup USB-related
- * GPIO pins for the STM32F4Discovery board.
- *
- ************************************************************************************/
-
-void stm32_usbinitialize(void)
-{
- /* The OTG FS has an internal soft pull-up. No GPIO configuration is required */
-
- /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
-
-#ifdef CONFIG_STM32_OTGFS
- stm32_configgpio(GPIO_OTGFS_VBUS);
-#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.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_USBDEV
-void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
-{
- ulldbg("resume: %d\n", resume);
-}
-#endif
-
-#endif /* CONFIG_STM32_OTGFS */
-
-
-
diff --git a/nuttx/configs/px4fmu-v1/src/up_userleds.c b/nuttx/configs/px4fmu-v1/src/up_userleds.c
deleted file mode 100644
index 32452120d..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_userleds.c
+++ /dev/null
@@ -1,134 +0,0 @@
-/****************************************************************************
- * configs/stm32f4discovery/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 <nuttx/power/pm.h>
-
-#include "chip.h"
-#include "up_arch.h"
-#include "up_internal.h"
-#include "stm32.h"
-#include "px4fmu-v1-internal.h"
-
-#ifndef CONFIG_ARCH_LEDS
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
- * with CONFIG_DEBUG_VERBOSE too)
- */
-
-#ifdef CONFIG_DEBUG_LEDS
-# define leddbg lldbg
-# define ledvdbg llvdbg
-#else
-# define leddbg(x...)
-# define ledvdbg(x...)
-#endif
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-/* This array maps an LED number to GPIO pin configuration */
-
-static uint32_t g_ledcfg[BOARD_NLEDS] =
-{
- GPIO_LED1, GPIO_LED2
-};
-
-/****************************************************************************
- * Private Function Protototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: stm32_ledinit
- ****************************************************************************/
-
-void stm32_ledinit(void)
-{
- /* Configure LED1-4 GPIOs for output */
-
- stm32_configgpio(GPIO_LED1);
- stm32_configgpio(GPIO_LED2);
-}
-
-/****************************************************************************
- * Name: stm32_setled
- ****************************************************************************/
-
-void stm32_setled(int led, bool ledon)
-{
- if ((unsigned)led < BOARD_NLEDS)
- {
- stm32_gpiowrite(g_ledcfg[led], ledon);
- }
-}
-
-/****************************************************************************
- * Name: stm32_setleds
- ****************************************************************************/
-
-void stm32_setleds(uint8_t ledset)
-{
- stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0);
- stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0);
-}
-
-#endif /* !CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/px4fmu-v1/src/up_watchdog.c b/nuttx/configs/px4fmu-v1/src/up_watchdog.c
deleted file mode 100644
index 4bef40f78..000000000
--- a/nuttx/configs/px4fmu-v1/src/up_watchdog.c
+++ /dev/null
@@ -1,136 +0,0 @@
-/************************************************************************************
- * configs/stm32f4discovery/src/up_watchdog.c
- * arch/arm/src/board/up_watchdog.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 <errno.h>
-#include <debug.h>
-
-#include <nuttx/watchdog.h>
-#include <arch/board/board.h>
-
-#include "stm32_wdg.h"
-
-#ifdef CONFIG_WATCHDOG
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-/* Configuration *******************************************************************/
-/* Wathdog hardware should be enabled */
-
-#if !defined(CONFIG_STM32_WWDG) && !defined(CONFIG_STM32_IWDG)
-# warning "One of CONFIG_STM32_WWDG or CONFIG_STM32_IWDG must be defined"
-#endif
-
-/* Select the path to the registered watchdog timer device */
-
-#ifndef CONFIG_STM32_WDG_DEVPATH
-# ifdef CONFIG_EXAMPLES_WATCHDOG_DEVPATH
-# define CONFIG_STM32_WDG_DEVPATH CONFIG_EXAMPLES_WATCHDOG_DEVPATH
-# else
-# define CONFIG_STM32_WDG_DEVPATH "/dev/watchdog0"
-# endif
-#endif
-
-/* Use the un-calibrated LSI frequency if we have nothing better */
-
-#if defined(CONFIG_STM32_IWDG) && !defined(CONFIG_STM32_LSIFREQ)
-# define CONFIG_STM32_LSIFREQ STM32_LSI_FREQUENCY
-#endif
-
-/* Debug ***************************************************************************/
-/* Non-standard debug that may be enabled just for testing the watchdog timer */
-
-#ifndef CONFIG_DEBUG
-# undef CONFIG_DEBUG_WATCHDOG
-#endif
-
-#ifdef CONFIG_DEBUG_WATCHDOG
-# define wdgdbg dbg
-# define wdglldbg lldbg
-# ifdef CONFIG_DEBUG_VERBOSE
-# define wdgvdbg vdbg
-# define wdgllvdbg llvdbg
-# else
-# define wdgvdbg(x...)
-# define wdgllvdbg(x...)
-# endif
-#else
-# define wdgdbg(x...)
-# define wdglldbg(x...)
-# define wdgvdbg(x...)
-# define wdgllvdbg(x...)
-#endif
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/****************************************************************************
- * Name: up_wdginitialize()
- *
- * Description:
- * Perform architecuture-specific initialization of the Watchdog hardware.
- * This interface must be provided by all configurations using
- * apps/examples/watchdog
- *
- ****************************************************************************/
-
-int up_wdginitialize(void)
-{
- /* Initialize tha register the watchdog timer device */
-
-#if defined(CONFIG_STM32_WWDG)
- stm32_wwdginitialize(CONFIG_STM32_WDG_DEVPATH);
- return OK;
-#elif defined(CONFIG_STM32_IWDG)
- stm32_iwdginitialize(CONFIG_STM32_WDG_DEVPATH, CONFIG_STM32_LSIFREQ);
- return OK;
-#else
- return -ENODEV;
-#endif
-}
-
-#endif /* CONFIG_WATCHDOG */
diff --git a/nuttx/configs/px4io-v1/Kconfig b/nuttx/configs/px4io-v1/Kconfig
new file mode 100644
index 000000000..6bd2e8e21
--- /dev/null
+++ b/nuttx/configs/px4io-v1/Kconfig
@@ -0,0 +1,8 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+if ARCH_BOARD_PX4IO_V1
+
+endif
diff --git a/nuttx/configs/px4io-v1/README.txt b/nuttx/configs/px4io-v1/README.txt
new file mode 100755
index 000000000..9b1615f42
--- /dev/null
+++ b/nuttx/configs/px4io-v1/README.txt
@@ -0,0 +1,806 @@
+README
+======
+
+This README discusses issues unique to NuttX configurations for the
+STMicro STM3210E-EVAL development board.
+
+Contents
+========
+
+ - Development Environment
+ - GNU Toolchain Options
+ - IDEs
+ - NuttX buildroot Toolchain
+ - DFU and JTAG
+ - OpenOCD
+ - LEDs
+ - Temperature Sensor
+ - RTC
+ - STM3210E-EVAL-specific Configuration Options
+ - Configurations
+
+Development Environment
+=======================
+
+ Either Linux or Cygwin on Windows can be used for the development environment.
+ The source has been built only using the GNU toolchain (see below). Other
+ toolchains will likely cause problems. Testing was performed using the Cygwin
+ environment because the Raisonance R-Link emulatator and some RIDE7 development tools
+ were used and those tools works only under Windows.
+
+GNU Toolchain Options
+=====================
+
+ The NuttX make system has been modified to support the following different
+ toolchain options.
+
+ 1. The CodeSourcery GNU toolchain,
+ 2. The devkitARM GNU toolchain,
+ 3. Raisonance GNU toolchain, or
+ 4. The NuttX buildroot Toolchain (see below).
+
+ All testing has been conducted using the NuttX buildroot toolchain. However,
+ the make system is setup to default to use the devkitARM toolchain. To use
+ the CodeSourcery, devkitARM or Raisonance GNU toolchain, you simply need to
+ add one of the following configuration options to your .config (or defconfig)
+ file:
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+ CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux
+ CONFIG_STM32_DEVKITARM=y : devkitARM under Windows
+ CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows
+ CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
+
+ If you are not using CONFIG_STM32_BUILDROOT, then you may also have to modify
+ the PATH in the setenv.h file if your make cannot find the tools.
+
+ NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
+ Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot
+ toolchains are Cygwin and/or Linux native toolchains. There are several limitations
+ to using a Windows based toolchain in a Cygwin environment. The three biggest are:
+
+ 1. The Windows toolchain cannot follow Cygwin paths. Path conversions are
+ performed automatically in the Cygwin makefiles using the 'cygpath' utility
+ but you might easily find some new path problems. If so, check out 'cygpath -w'
+
+ 2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links
+ are used in Nuttx (e.g., include/arch). The make system works around these
+ problems for the Windows tools by copying directories instead of linking them.
+ But this can also cause some confusion for you: For example, you may edit
+ a file in a "linked" directory and find that your changes had no effect.
+ That is because you are building the copy of the file in the "fake" symbolic
+ directory. If you use a Windows toolchain, you should get in the habit of
+ making like this:
+
+ make clean_context all
+
+ An alias in your .bashrc file might make that less painful.
+
+ 3. Dependencies are not made when using Windows versions of the GCC. This is
+ because the dependencies are generated using Windows pathes which do not
+ work with the Cygwin make.
+
+ Support has been added for making dependencies with the windows-native toolchains.
+ That support can be enabled by modifying your Make.defs file as follows:
+
+ - MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)"
+
+ If you have problems with the dependency build (for example, if you are not
+ building on C:), then you may need to modify tools/mkdeps.sh
+
+ NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization
+ level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with
+ -Os.
+
+ NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that
+ the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
+ path or will get the wrong version of make.
+
+IDEs
+====
+
+ NuttX is built using command-line make. It can be used with an IDE, but some
+ effort will be required to create the project (There is a simple RIDE project
+ in the RIDE subdirectory).
+
+ Makefile Build
+ --------------
+ Under Eclipse, it is pretty easy to set up an "empty makefile project" and
+ simply use the NuttX makefile to build the system. That is almost for free
+ under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty
+ makefile project in order to work with Windows (Google for "Eclipse Cygwin" -
+ there is a lot of help on the internet).
+
+ Native Build
+ ------------
+ Here are a few tips before you start that effort:
+
+ 1) Select the toolchain that you will be using in your .config file
+ 2) Start the NuttX build at least one time from the Cygwin command line
+ before trying to create your project. This is necessary to create
+ certain auto-generated files and directories that will be needed.
+ 3) Set up include pathes: You will need include/, arch/arm/src/stm32,
+ arch/arm/src/common, arch/arm/src/armv7-m, and sched/.
+ 4) All assembly files need to have the definition option -D __ASSEMBLY__
+ on the command line.
+
+ Startup files will probably cause you some headaches. The NuttX startup file
+ is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX
+ one time from the Cygwin command line in order to obtain the pre-built
+ startup object needed by RIDE.
+
+NuttX buildroot Toolchain
+=========================
+
+ A GNU GCC-based toolchain is assumed. The files */setenv.sh should
+ be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
+ different from the default in your PATH variable).
+
+ If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX
+ SourceForge download site (https://sourceforge.net/project/showfiles.php?group_id=189573).
+ This GNU toolchain builds and executes in the Linux or Cygwin environment.
+
+ 1. You must have already configured Nuttx in <some-dir>/nuttx.
+
+ cd tools
+ ./configure.sh stm3210e-eval/<sub-dir>
+
+ 2. Download the latest buildroot package into <some-dir>
+
+ 3. unpack the buildroot tarball. The resulting directory may
+ have versioning information on it like buildroot-x.y.z. If so,
+ rename <some-dir>/buildroot-x.y.z to <some-dir>/buildroot.
+
+ 4. cd <some-dir>/buildroot
+
+ 5. cp configs/cortexm3-defconfig-4.3.3 .config
+
+ 6. make oldconfig
+
+ 7. make
+
+ 8. Edit setenv.h, if necessary, so that the PATH variable includes
+ the path to the newly built binaries.
+
+ See the file configs/README.txt in the buildroot source tree. That has more
+ detailed PLUS some special instructions that you will need to follow if you are
+ building a Cortex-M3 toolchain for Cygwin under Windows.
+
+DFU and JTAG
+============
+
+ Enbling Support for the DFU Bootloader
+ --------------------------------------
+ The linker files in these projects can be configured to indicate that you
+ will be loading code using STMicro built-in USB Device Firmware Upgrade (DFU)
+ loader or via some JTAG emulator. You can specify the DFU bootloader by
+ adding the following line:
+
+ CONFIG_STM32_DFU=y
+
+ to your .config file. Most of the configurations in this directory are set
+ up to use the DFU loader.
+
+ If CONFIG_STM32_DFU is defined, the code will not be positioned at the beginning
+ of FLASH (0x08000000) but will be offset to 0x08003000. This offset is needed
+ to make space for the DFU loader and 0x08003000 is where the DFU loader expects
+ to find new applications at boot time. If you need to change that origin for some
+ other bootloader, you will need to edit the file(s) ld.script.dfu for each
+ configuration.
+
+ The DFU SE PC-based software is available from the STMicro website,
+ http://www.st.com. General usage instructions:
+
+ 1. Convert the NuttX Intel Hex file (nuttx.ihx) into a special DFU
+ file (nuttx.dfu)... see below for details.
+ 2. Connect the STM3210E-EVAL board to your computer using a USB
+ cable.
+ 3. Start the DFU loader on the STM3210E-EVAL board. You do this by
+ resetting the board while holding the "Key" button. Windows should
+ recognize that the DFU loader has been installed.
+ 3. Run the DFU SE program to load nuttx.dfu into FLASH.
+
+ What if the DFU loader is not in FLASH? The loader code is available
+ inside of the Demo dirctory of the USBLib ZIP file that can be downloaded
+ from the STMicro Website. You can build it using RIDE (or other toolchains);
+ you will need a JTAG emulator to burn it into FLASH the first time.
+
+ In order to use STMicro's built-in DFU loader, you will have to get
+ the NuttX binary into a special format with a .dfu extension. The
+ DFU SE PC_based software installation includes a file "DFU File Manager"
+ conversion program that a file in Intel Hex format to the special DFU
+ format. When you successfully build NuttX, you will find a file called
+ nutt.ihx in the top-level directory. That is the file that you should
+ provide to the DFU File Manager. You will need to rename it to nuttx.hex
+ in order to find it with the DFU File Manager. You will end up with
+ a file called nuttx.dfu that you can use with the STMicro DFU SE program.
+
+ Enabling JTAG
+ -------------
+ If you are not using the DFU, then you will probably also need to enable
+ JTAG support. By default, all JTAG support is disabled but there NuttX
+ configuration options to enable JTAG in various different ways.
+
+ These configurations effect the setting of the SWJ_CFG[2:0] bits in the AFIO
+ MAPR register. These bits are used to configure the SWJ and trace alternate function I/Os. The SWJ (SerialWire JTAG) supports JTAG or SWD access to the
+ Cortex debug port. The default state in this port is for all JTAG support
+ to be disable.
+
+ CONFIG_STM32_JTAG_FULL_ENABLE - sets SWJ_CFG[2:0] to 000 which enables full
+ SWJ (JTAG-DP + SW-DP)
+
+ CONFIG_STM32_JTAG_NOJNTRST_ENABLE - sets SWJ_CFG[2:0] to 001 which enable
+ full SWJ (JTAG-DP + SW-DP) but without JNTRST.
+
+ CONFIG_STM32_JTAG_SW_ENABLE - sets SWJ_CFG[2:0] to 010 which would set JTAG-DP
+ disabled and SW-DP enabled
+
+ The default setting (none of the above defined) is SWJ_CFG[2:0] set to 100
+ which disable JTAG-DP and SW-DP.
+
+OpenOCD
+=======
+
+I have also used OpenOCD with the STM3210E-EVAL. In this case, I used
+the Olimex USB ARM OCD. See the script in configs/stm3210e-eval/tools/oocd.sh
+for more information. Using the script:
+
+1) Start the OpenOCD GDB server
+
+ cd <nuttx-build-directory>
+ configs/stm3210e-eval/tools/oocd.sh $PWD
+
+2) Load Nuttx
+
+ cd <nuttx-built-directory>
+ arm-none-eabi-gdb nuttx
+ gdb> target remote localhost:3333
+ gdb> mon reset
+ gdb> mon halt
+ gdb> load nuttx
+
+3) Running NuttX
+
+ gdb> mon reset
+ gdb> c
+
+LEDs
+====
+
+The STM3210E-EVAL board has four LEDs labeled LD1, LD2, LD3 and LD4 on the
+board.. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
+defined. In that case, the usage by the board port is defined in
+include/board.h and src/up_leds.c. The LEDs are used to encode OS-related
+events as follows:
+
+ SYMBOL Meaning LED1* LED2 LED3 LED4
+ ---------------- ----------------------- ----- ----- ----- -----
+ LED_STARTED NuttX has been started ON OFF OFF OFF
+ LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
+ LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
+ LED_STACKCREATED Idle stack created OFF OFF ON OFF
+ LED_INIRQ In an interrupt** ON N/C N/C OFF
+ LED_SIGNAL In a signal handler*** N/C ON N/C OFF
+ LED_ASSERTION An assertion failed ON ON N/C OFF
+ LED_PANIC The system has crashed N/C N/C N/C ON
+ LED_IDLE STM32 is is sleep mode (Optional, not used)
+
+ * If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot
+ and these LEDs will give you some indication of where the failure was
+ ** The normal state is LED3 ON and LED1 faintly glowing. This faint glow
+ is because of timer interupts that result in the LED being illuminated
+ on a small proportion of the time.
+*** LED2 may also flicker normally if signals are processed.
+
+Temperature Sensor
+==================
+
+Support for the on-board LM-75 temperature sensor is available. This supported
+has been verified, but has not been included in any of the available the
+configurations. To set up the temperature sensor, add the following to the
+NuttX configuration file
+
+ CONFIG_I2C=y
+ CONFIG_I2C_LM75=y
+
+Then you can implement logic like the following to use the temperature sensor:
+
+ #include <nuttx/sensors/lm75.h>
+ #include <arch/board/board.h>
+
+ ret = stm32_lm75initialize("/dev/temp"); /* Register the temperature sensor */
+ fd = open("/dev/temp", O_RDONLY); /* Open the temperature sensor device */
+ ret = ioctl(fd, SNIOC_FAHRENHEIT, 0); /* Select Fahrenheit */
+ bytesread = read(fd, buffer, 8*sizeof(b16_t)); /* Read temperature samples */
+
+More complex temperature sensor operations are also available. See the IOCTAL
+commands enumerated in include/nuttx/sensors/lm75.h. Also read the descriptions
+of the stm32_lm75initialize() and stm32_lm75attach() interfaces in the
+arch/board/board.h file (sames as configs/stm3210e-eval/include/board.h).
+
+RTC
+===
+
+ The STM32 RTC may configured using the following settings.
+
+ CONFIG_RTC - Enables general support for a hardware RTC. Specific
+ architectures may require other specific settings.
+ CONFIG_RTC_HIRES - The typical RTC keeps time to resolution of 1
+ second, usually supporting a 32-bit time_t value. In this case,
+ the RTC is used to &quot;seed&quot; the normal NuttX timer and the
+ NuttX timer provides for higher resoution time. If CONFIG_RTC_HIRES
+ is enabled in the NuttX configuration, then the RTC provides higher
+ resolution time and completely replaces the system timer for purpose of
+ date and time.
+ CONFIG_RTC_FREQUENCY - If CONFIG_RTC_HIRES is defined, then the
+ frequency of the high resolution RTC must be provided. If CONFIG_RTC_HIRES
+ is not defined, CONFIG_RTC_FREQUENCY is assumed to be one.
+ CONFIG_RTC_ALARM - Enable if the RTC hardware supports setting of an alarm.
+ A callback function will be executed when the alarm goes off
+
+ In hi-res mode, the STM32 RTC operates only at 16384Hz. Overflow interrupts
+ are handled when the 32-bit RTC counter overflows every 3 days and 43 minutes.
+ A BKP register is incremented on each overflow interrupt creating, effectively,
+ a 48-bit RTC counter.
+
+ In the lo-res mode, the RTC operates at 1Hz. Overflow interrupts are not handled
+ (because the next overflow is not expected until the year 2106.
+
+ WARNING: Overflow interrupts are lost whenever the STM32 is powered down. The
+ overflow interrupt may be lost even if the STM32 is powered down only momentarily.
+ Therefore hi-res solution is only useful in systems where the power is always on.
+
+STM3210E-EVAL-specific Configuration Options
+============================================
+
+ CONFIG_ARCH - Identifies the arch/ subdirectory. This should
+ be set to:
+
+ CONFIG_ARCH=arm
+
+ CONFIG_ARCH_family - For use in C code:
+
+ CONFIG_ARCH_ARM=y
+
+ CONFIG_ARCH_architecture - For use in C code:
+
+ CONFIG_ARCH_CORTEXM3=y
+
+ CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+
+ CONFIG_ARCH_CHIP=stm32
+
+ CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
+ chip:
+
+ CONFIG_ARCH_CHIP_STM32F103ZET6
+
+ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock
+ configuration features.
+
+ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n
+
+ CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
+ hence, the board that supports the particular chip or SoC.
+
+ CONFIG_ARCH_BOARD=stm3210e_eval (for the STM3210E-EVAL development board)
+
+ CONFIG_ARCH_BOARD_name - For use in C code
+
+ CONFIG_ARCH_BOARD_STM3210E_EVAL=y
+
+ CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
+ of delay loops
+
+ CONFIG_ENDIAN_BIG - define if big endian (default is little
+ endian)
+
+ CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case):
+
+ CONFIG_DRAM_SIZE=0x00010000 (64Kb)
+
+ CONFIG_DRAM_START - The start address of installed DRAM
+
+ CONFIG_DRAM_START=0x20000000
+
+ CONFIG_DRAM_END - Last address+1 of installed RAM
+
+ CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
+
+ CONFIG_ARCH_IRQPRIO - The STM32F103Z supports interrupt prioritization
+
+ CONFIG_ARCH_IRQPRIO=y
+
+ CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
+ have LEDs
+
+ CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+ stack. If defined, this symbol is the size of the interrupt
+ stack in bytes. If not defined, the user task stacks will be
+ used during interrupt handling.
+
+ CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+
+ CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+
+ CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+ cause a 100 second delay during boot-up. This 100 second delay
+ serves no purpose other than it allows you to calibratre
+ CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure
+ the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
+ the delay actually is 100 seconds.
+
+ Individual subsystems can be enabled:
+ AHB
+ ---
+ CONFIG_STM32_DMA1
+ CONFIG_STM32_DMA2
+ CONFIG_STM32_CRC
+ CONFIG_STM32_FSMC
+ CONFIG_STM32_SDIO
+
+ APB1
+ ----
+ CONFIG_STM32_TIM2
+ CONFIG_STM32_TIM3
+ CONFIG_STM32_TIM4
+ CONFIG_STM32_TIM5
+ CONFIG_STM32_TIM6
+ CONFIG_STM32_TIM7
+ CONFIG_STM32_WWDG
+ CONFIG_STM32_SPI2
+ CONFIG_STM32_SPI4
+ CONFIG_STM32_USART2
+ CONFIG_STM32_USART3
+ CONFIG_STM32_UART4
+ CONFIG_STM32_UART5
+ CONFIG_STM32_I2C1
+ CONFIG_STM32_I2C2
+ CONFIG_STM32_USB
+ CONFIG_STM32_CAN
+ CONFIG_STM32_BKP
+ CONFIG_STM32_PWR
+ CONFIG_STM32_DAC1
+ CONFIG_STM32_DAC2
+ CONFIG_STM32_USB
+
+ APB2
+ ----
+ CONFIG_STM32_ADC1
+ CONFIG_STM32_ADC2
+ CONFIG_STM32_TIM1
+ CONFIG_STM32_SPI1
+ CONFIG_STM32_TIM8
+ CONFIG_STM32_USART1
+ CONFIG_STM32_ADC3
+
+ Timer and I2C devices may need to the following to force power to be applied
+ unconditionally at power up. (Otherwise, the device is powered when it is
+ initialized).
+
+ CONFIG_STM32_FORCEPOWER
+
+ Timer devices may be used for different purposes. One special purpose is
+ to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn
+ is defined (as above) then the following may also be defined to indicate that
+ the timer is intended to be used for pulsed output modulation, ADC conversion,
+ or DAC conversion. Note that ADC/DAC require two definition: Not only do you have
+ to assign the timer (n) for used by the ADC or DAC, but then you also have to
+ configure which ADC or DAC (m) it is assigned to.
+
+ CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,8
+ CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,8
+ CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,8, m=1,..,3
+ CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,8
+ CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,8, m=1,..,2
+
+ For each timer that is enabled for PWM usage, we need the following additional
+ configuration settings:
+
+ CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
+
+ NOTE: The STM32 timers are each capable of generating different signals on
+ each of the four channels with different duty cycles. That capability is
+ not supported by this driver: Only one output channel per timer.
+
+ Alternate pin mappings (should not be used with the STM3210E-EVAL board):
+
+ CONFIG_STM32_TIM1_FULL_REMAP
+ CONFIG_STM32_TIM1_PARTIAL_REMAP
+ CONFIG_STM32_TIM2_FULL_REMAP
+ CONFIG_STM32_TIM2_PARTIAL_REMAP_1
+ CONFIG_STM32_TIM2_PARTIAL_REMAP_2
+ CONFIG_STM32_TIM3_FULL_REMAP
+ CONFIG_STM32_TIM3_PARTIAL_REMAP
+ CONFIG_STM32_TIM4_REMAP
+ CONFIG_STM32_USART1_REMAP
+ CONFIG_STM32_USART2_REMAP
+ CONFIG_STM32_USART3_FULL_REMAP
+ CONFIG_STM32_USART3_PARTIAL_REMAP
+ CONFIG_STM32_SPI1_REMAP
+ CONFIG_STM32_SPI3_REMAP
+ CONFIG_STM32_I2C1_REMAP
+ CONFIG_STM32_CAN1_FULL_REMAP
+ CONFIG_STM32_CAN1_PARTIAL_REMAP
+ CONFIG_STM32_CAN2_REMAP
+
+ JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
+ CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+ CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+ but without JNTRST.
+ CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+
+ STM32F103Z specific device driver settings
+
+ CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART
+ m (m=4,5) for the console and ttys0 (default is the USART1).
+ CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received.
+ This specific the size of the receive buffer
+ CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before
+ being sent. This specific the size of the transmit buffer
+ CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be
+ CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8.
+ CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+ CONFIG_U[S]ARTn_2STOP - Two stop bits
+
+ CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI
+ support. Non-interrupt-driven, poll-waiting is recommended if the
+ interrupt rate would be to high in the interrupt driven case.
+ CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance.
+ Cannot be used with CONFIG_STM32_SPI_INTERRUPT.
+
+ CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
+ and CONFIG_STM32_DMA2.
+ CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128
+ CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
+ Default: Medium
+ CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
+ 4-bit transfer mode.
+
+ STM3210E-EVAL CAN Configuration
+
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
+ Standard 11-bit IDs.
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+ CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback
+ mode for testing. The STM32 CAN driver does support loopback mode.
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+ CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
+ CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
+ CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
+ dump of all CAN registers.
+
+ STM3210E-EVAL LCD Hardware Configuration
+
+ CONFIG_LCD_LANDSCAPE - Define for 320x240 display "landscape"
+ support. Default is this 320x240 "landscape" orientation
+ (this setting is informative only... not used).
+ CONFIG_LCD_PORTRAIT - Define for 240x320 display "portrait"
+ orientation support. In this orientation, the STM3210E-EVAL's
+ LCD ribbon cable is at the bottom of the display. Default is
+ 320x240 "landscape" orientation.
+ CONFIG_LCD_RPORTRAIT - Define for 240x320 display "reverse
+ portrait" orientation support. In this orientation, the
+ STM3210E-EVAL's LCD ribbon cable is at the top of the display.
+ Default is 320x240 "landscape" orientation.
+ CONFIG_LCD_BACKLIGHT - Define to support a backlight.
+ CONFIG_LCD_PWM - If CONFIG_STM32_TIM1 is also defined, then an
+ adjustable backlight will be provided using timer 1 to generate
+ various pulse widthes. The granularity of the settings is
+ determined by CONFIG_LCD_MAXPOWER. If CONFIG_LCD_PWM (or
+ CONFIG_STM32_TIM1) is not defined, then a simple on/off backlight
+ is provided.
+ CONFIG_LCD_RDSHIFT - When reading 16-bit gram data, there appears
+ to be a shift in the returned data. This value fixes the offset.
+ Default 5.
+
+ The LCD driver dynamically selects the LCD based on the reported LCD
+ ID value. However, code size can be reduced by suppressing support for
+ individual LCDs using:
+
+ CONFIG_STM32_AM240320_DISABLE
+ CONFIG_STM32_SPFD5408B_DISABLE
+ CONFIG_STM32_R61580_DISABLE
+
+Configurations
+==============
+
+Each STM3210E-EVAL configuration is maintained in a sudirectory and
+can be selected as follow:
+
+ cd tools
+ ./configure.sh stm3210e-eval/<subdir>
+ cd -
+ . ./setenv.sh
+
+Where <subdir> is one of the following:
+
+ buttons:
+ --------
+
+ Uses apps/examples/buttons to exercise STM3210E-EVAL buttons and
+ button interrupts.
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+
+ composite
+ ---------
+
+ This configuration exercises a composite USB interface consisting
+ of a CDC/ACM device and a USB mass storage device. This configuration
+ uses apps/examples/composite.
+
+ nsh and nsh2:
+ ------------
+ Configure the NuttShell (nsh) located at examples/nsh.
+
+ Differences between the two NSH configurations:
+
+ =========== ======================= ================================
+ nsh nsh2
+ =========== ======================= ================================
+ Toolchain: NuttX buildroot for Codesourcery for Windows (1)
+ Linux or Cygwin (1,2)
+ ----------- ----------------------- --------------------------------
+ Loader: DfuSe DfuSe
+ ----------- ----------------------- --------------------------------
+ Serial Debug output: USART1 Debug output: USART1
+ Console: NSH output: USART1 NSH output: USART1 (3)
+ ----------- ----------------------- --------------------------------
+ microSD Yes Yes
+ Support
+ ----------- ----------------------- --------------------------------
+ FAT FS CONFIG_FAT_LCNAME=y CONFIG_FAT_LCNAME=y
+ Config CONFIG_FAT_LFN=n CONFIG_FAT_LFN=y (4)
+ ----------- ----------------------- --------------------------------
+ Support for No Yes
+ Built-in
+ Apps
+ ----------- ----------------------- --------------------------------
+ Built-in None apps/examples/nx
+ Apps apps/examples/nxhello
+ apps/examples/usbstorage (5)
+ =========== ======================= ================================
+
+ (1) You will probably need to modify nsh/setenv.sh or nsh2/setenv.sh
+ to set up the correct PATH variable for whichever toolchain you
+ may use.
+ (2) Since DfuSe is assumed, this configuration may only work under
+ Cygwin without modification.
+ (3) When any other device other than /dev/console is used for a user
+ interface, (1) linefeeds (\n) will not be expanded to carriage return
+ / linefeeds \r\n). You will need to configure your terminal program
+ to account for this. And (2) input is not automatically echoed so
+ you will have to turn local echo on.
+ (4) Microsoft holds several patents related to the design of
+ long file names in the FAT file system. Please refer to the
+ details in the top-level COPYING file. Please do not use FAT
+ long file name unless you are familiar with these patent issues.
+ (5) When built as an NSH add-on command (CONFIG_EXAMPLES_USBMSC_BUILTIN=y),
+ Caution should be used to assure that the SD drive is not in use when
+ the USB storage device is configured. Specifically, the SD driver
+ should be unmounted like:
+
+ nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Card is mounted in NSH
+ ...
+ nsh> umount /mnd/sdcard # Unmount before connecting USB!!!
+ nsh> msconn # Connect the USB storage device
+ ...
+ nsh> msdis # Disconnect USB storate device
+ nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Restore the mount
+
+ Failure to do this could result in corruption of the SD card format.
+
+ nx:
+ ---
+ An example using the NuttX graphics system (NX). This example
+ focuses on general window controls, movement, mouse and keyboard
+ input.
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+ CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait
+
+ nxlines:
+ ------
+ Another example using the NuttX graphics system (NX). This
+ example focuses on placing lines on the background in various
+ orientations.
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+ CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait
+
+ nxtext:
+ ------
+ Another example using the NuttX graphics system (NX). This
+ example focuses on placing text on the background while pop-up
+ windows occur. Text should continue to update normally with
+ or without the popup windows present.
+
+ CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin
+ CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait
+
+ NOTE: When I tried building this example with the CodeSourcery
+ tools, I got a hardfault inside of its libgcc. I haven't
+ retested since then, but beware if you choose to change the
+ toolchain.
+
+ ostest:
+ ------
+ This configuration directory, performs a simple OS test using
+ examples/ostest. By default, this project assumes that you are
+ using the DFU bootloader.
+
+ CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin
+
+ RIDE
+ ----
+ This configuration builds a trivial bring-up binary. It is
+ useful only because it words with the RIDE7 IDE and R-Link debugger.
+
+ CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows
+
+ usbserial:
+ ---------
+ This configuration directory exercises the USB serial class
+ driver at examples/usbserial. See examples/README.txt for
+ more information.
+
+ CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin
+
+ USB debug output can be enabled as by changing the following
+ settings in the configuration file:
+
+ -CONFIG_DEBUG=n
+ -CONFIG_DEBUG_VERBOSE=n
+ -CONFIG_DEBUG_USB=n
+ +CONFIG_DEBUG=y
+ +CONFIG_DEBUG_VERBOSE=y
+ +CONFIG_DEBUG_USB=y
+
+ -CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=n
+ -CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=n
+ -CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n
+ -CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n
+ -CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
+ +CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=y
+ +CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=y
+ +CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=y
+ +CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=y
+ +CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=y
+
+ By default, the usbserial example uses the Prolific PL2303
+ serial/USB converter emulation. The example can be modified
+ to use the CDC/ACM serial class by making the following changes
+ to the configuration file:
+
+ -CONFIG_PL2303=y
+ +CONFIG_PL2303=n
+
+ -CONFIG_CDCACM=n
+ +CONFIG_CDCACM=y
+
+ The example can also be converted to use the alternative
+ USB serial example at apps/examples/usbterm by changing the
+ following:
+
+ -CONFIGURED_APPS += examples/usbserial
+ +CONFIGURED_APPS += examples/usbterm
+
+ In either the original appconfig file (before configuring)
+ or in the final apps/.config file (after configuring).
+
+ usbstorage:
+ ----------
+ This configuration directory exercises the USB mass storage
+ class driver at examples/usbstorage. See examples/README.txt for
+ more information.
+
+ CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin
+
diff --git a/nuttx/configs/px4io-v1/common/Make.defs b/nuttx/configs/px4io-v1/common/Make.defs
new file mode 100644
index 000000000..7f782b5b2
--- /dev/null
+++ b/nuttx/configs/px4io-v1/common/Make.defs
@@ -0,0 +1,175 @@
+############################################################################
+# configs/px4fmu/common/Make.defs
+#
+# 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.
+#
+############################################################################
+
+#
+# Generic Make.defs for the PX4FMU
+# Do not specify/use this file directly - it is included by config-specific
+# Make.defs in the per-config directories.
+#
+
+include ${TOPDIR}/tools/Config.mk
+
+#
+# We only support building with the ARM bare-metal toolchain from
+# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
+#
+CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+CC = $(CROSSDEV)gcc
+CXX = $(CROSSDEV)g++
+CPP = $(CROSSDEV)gcc -E
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+MAXOPTIMIZATION = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m3 \
+ -mthumb \
+ -march=armv7-m
+
+# enable precise stack overflow tracking
+#INSTRUMENTATIONDEFINES = -finstrument-functions \
+# -ffixed-r10
+
+# use our linker script
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)}"
+else
+ ifeq ($(PX4_WINTOOL),y)
+ # Windows-native toolchains (MSYS)
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)
+ else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)
+ endif
+endif
+
+# tool versions
+ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
+ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
+
+# optimisation flags
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ARCHOPTIMIZATION += -g
+endif
+
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+ARCHWARNINGS = -Wall \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS)
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+# this seems to be the only way to add linker flags
+EXTRA_LIBS += --warn-common \
+ --gc-sections
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+# produce partially-linked $1 from files in $2
+define PRELINK
+ @echo "PRELINK: $1"
+ $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx/configs/px4io-v1/common/ld.script b/nuttx/configs/px4io-v1/common/ld.script
new file mode 100755
index 000000000..69c2f9cb2
--- /dev/null
+++ b/nuttx/configs/px4io-v1/common/ld.script
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * configs/stm3210e-eval/nsh/ld.script
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and
+ * 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH,
+ * FLASH memory is aliased to address 0x0000:0000 where the code expects to
+ * begin execution by jumping to the entry point in the 0x0800:0000 address
+ * range.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ /* The STM32F100CB has 8Kb of SRAM beginning at the following address */
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/px4io-v1/common/setenv.sh b/nuttx/configs/px4io-v1/common/setenv.sh
new file mode 100755
index 000000000..ff9a4bf8a
--- /dev/null
+++ b/nuttx/configs/px4io-v1/common/setenv.sh
@@ -0,0 +1,47 @@
+#!/bin/bash
+# configs/stm3210e-eval/dfu/setenv.sh
+#
+# Copyright (C) 2009 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.
+#
+
+if [ "$(basename $0)" = "setenv.sh" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
+
+WD=`pwd`
+export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
+export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/px4io-v1/include/README.txt b/nuttx/configs/px4io-v1/include/README.txt
new file mode 100755
index 000000000..2264a80aa
--- /dev/null
+++ b/nuttx/configs/px4io-v1/include/README.txt
@@ -0,0 +1 @@
+This directory contains header files unique to the PX4IO board.
diff --git a/nuttx/configs/px4io-v1/include/board.h b/nuttx/configs/px4io-v1/include/board.h
new file mode 100755
index 000000000..668602ea8
--- /dev/null
+++ b/nuttx/configs/px4io-v1/include/board.h
@@ -0,0 +1,172 @@
+/************************************************************************************
+ * configs/px4io/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * 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 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 __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+# include <stdbool.h>
+#endif
+#include <stm32_rcc.h>
+#include <stm32_sdio.h>
+#include <stm32.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+
+/* On-board crystal frequency is 24MHz (HSE) */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+/* Use the HSE output as the system clock */
+
+#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE
+#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE
+#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL
+
+/* AHB clock (HCLK) is SYSCLK (24MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB2 clock (PCLK2) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
+#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */
+
+/* APB2 timer 1 will receive PCLK2. */
+
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* APB1 clock (PCLK1) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY)
+
+/* All timers run off PCLK */
+
+#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY)
+
+/*
+ * Some of the USART pins are not available; override the GPIO
+ * definitions with an invalid pin configuration.
+ */
+#undef GPIO_USART2_CTS
+#define GPIO_USART2_CTS 0xffffffff
+#undef GPIO_USART2_RTS
+#define GPIO_USART2_RTS 0xffffffff
+#undef GPIO_USART2_CK
+#define GPIO_USART2_CK 0xffffffff
+#undef GPIO_USART3_TX
+#define GPIO_USART3_TX 0xffffffff
+#undef GPIO_USART3_CK
+#define GPIO_USART3_CK 0xffffffff
+#undef GPIO_USART3_CTS
+#define GPIO_USART3_CTS 0xffffffff
+#undef GPIO_USART3_RTS
+#define GPIO_USART3_RTS 0xffffffff
+
+/*
+ * High-resolution timer
+ */
+#ifdef CONFIG_HRT_TIMER
+# define HRT_TIMER 1 /* use timer1 for the HRT */
+# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#endif
+
+/*
+ * PPM
+ *
+ * PPM input is handled by the HRT timer.
+ *
+ * Pin is PA8, timer 1, channel 1
+ */
+#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM)
+# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+# define GPIO_PPM_IN GPIO_TIM1_CH1IN
+#endif
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * 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.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx/configs/px4io-v1/include/drv_i2c_device.h b/nuttx/configs/px4io-v1/include/drv_i2c_device.h
new file mode 100644
index 000000000..02582bc09
--- /dev/null
+++ b/nuttx/configs/px4io-v1/include/drv_i2c_device.h
@@ -0,0 +1,42 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+ /**
+ * @file A simple, polled I2C slave-mode driver.
+ *
+ * The master writes to and reads from a byte buffer, which the caller
+ * can update inbetween calls to the FSM.
+ */
+
+extern void i2c_fsm_init(uint8_t *buffer, size_t buffer_size);
+extern bool i2c_fsm(void);
diff --git a/nuttx/configs/px4io-v1/io/Make.defs b/nuttx/configs/px4io-v1/io/Make.defs
new file mode 100644
index 000000000..c7f6effd9
--- /dev/null
+++ b/nuttx/configs/px4io-v1/io/Make.defs
@@ -0,0 +1,3 @@
+include ${TOPDIR}/.config
+
+include $(TOPDIR)/configs/px4io-v1/common/Make.defs
diff --git a/nuttx/configs/px4io-v1/io/appconfig b/nuttx/configs/px4io-v1/io/appconfig
new file mode 100644
index 000000000..48a41bcdb
--- /dev/null
+++ b/nuttx/configs/px4io-v1/io/appconfig
@@ -0,0 +1,32 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
diff --git a/nuttx/configs/px4io-v1/io/defconfig b/nuttx/configs/px4io-v1/io/defconfig
new file mode 100755
index 000000000..43dd1b0e8
--- /dev/null
+++ b/nuttx/configs/px4io-v1/io/defconfig
@@ -0,0 +1,552 @@
+############################################################################
+# configs/px4io/nsh/defconfig
+#
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (C) 2011-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.
+#
+############################################################################
+#
+# architecture selection
+#
+# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
+# processor architecture.
+# CONFIG_ARCH_family - for use in C code. This identifies the
+# particular chip family that the architecture is implemented
+# in.
+# CONFIG_ARCH_architecture - for use in C code. This identifies the
+# specific architecture within the chip family.
+# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+# CONFIG_ARCH_CHIP_name - For use in C code
+# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
+# the board that supports the particular chip or SoC.
+# CONFIG_ARCH_BOARD_name - for use in C code
+# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
+# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
+# CONFIG_DRAM_SIZE - Describes the installed DRAM.
+# CONFIG_DRAM_START - The start address of DRAM (physical)
+# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization
+# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+# stack. If defined, this symbol is the size of the interrupt
+# stack in bytes. If not defined, the user task stacks will be
+# used during interrupt handling.
+# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
+# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
+# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+# cause a 100 second delay during boot-up. This 100 second delay
+# serves no purpose other than it allows you to calibrate
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
+# the delay actually is 100 seconds.
+# CONFIG_ARCH_DMA - Support DMA initialization
+#
+CONFIG_ARCH="arm"
+CONFIG_ARCH_ARM=y
+CONFIG_ARCH_CORTEXM3=y
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32F100C8=y
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_PX4IO_V1=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="px4io-v1"
+CONFIG_BOARD_LOOPSPERMSEC=2000
+CONFIG_DRAM_SIZE=0x00002000
+CONFIG_DRAM_START=0x20000000
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARCH_BOOTLOADER=n
+CONFIG_ARCH_LEDS=n
+CONFIG_ARCH_BUTTONS=n
+CONFIG_ARCH_CALIBRATION=n
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_MATH_H=y
+
+CONFIG_ARMV7M_CMNVECTOR=y
+
+#
+# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
+#
+# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG
+#
+# JTAG Enable options:
+#
+# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# but without JNTRST.
+# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+#
+CONFIG_STM32_DFU=n
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
+CONFIG_STM32_JTAG_SW_ENABLE=n
+
+#
+# Individual subsystems can be enabled:
+#
+# AHB:
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=n
+CONFIG_STM32_CRC=n
+# APB1:
+# Timers 2,3 and 4 are owned by the PWM driver
+CONFIG_STM32_TIM2=n
+CONFIG_STM32_TIM3=n
+CONFIG_STM32_TIM4=n
+CONFIG_STM32_TIM5=n
+CONFIG_STM32_TIM6=n
+CONFIG_STM32_TIM7=n
+CONFIG_STM32_WWDG=n
+CONFIG_STM32_SPI2=n
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=y
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=n
+CONFIG_STM32_BKP=n
+CONFIG_STM32_PWR=n
+CONFIG_STM32_DAC=n
+# APB2:
+# We use our own ADC driver, but leave this on for clocking purposes.
+CONFIG_STM32_ADC1=y
+CONFIG_STM32_ADC2=n
+# TIM1 is owned by the HRT
+CONFIG_STM32_TIM1=n
+CONFIG_STM32_SPI1=n
+CONFIG_STM32_TIM8=n
+CONFIG_STM32_USART1=y
+CONFIG_STM32_ADC3=n
+
+
+#
+# STM32F100 specific serial device driver settings
+#
+# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
+# console and ttys0 (default is the USART1).
+# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received.
+# This specific the size of the receive buffer
+# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before
+# being sent. This specific the size of the transmit buffer
+# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be
+# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8.
+# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+# CONFIG_USARTn_2STOP - Two stop bits
+#
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_STANDARD_SERIAL=y
+
+CONFIG_USART1_SERIAL_CONSOLE=y
+CONFIG_USART2_SERIAL_CONSOLE=n
+CONFIG_USART3_SERIAL_CONSOLE=n
+
+CONFIG_USART1_TXBUFSIZE=64
+CONFIG_USART2_TXBUFSIZE=64
+CONFIG_USART3_TXBUFSIZE=64
+
+CONFIG_USART1_RXBUFSIZE=64
+CONFIG_USART2_RXBUFSIZE=64
+CONFIG_USART3_RXBUFSIZE=64
+
+CONFIG_USART1_BAUD=115200
+CONFIG_USART2_BAUD=115200
+CONFIG_USART3_BAUD=115200
+
+CONFIG_USART1_BITS=8
+CONFIG_USART2_BITS=8
+CONFIG_USART3_BITS=8
+
+CONFIG_USART1_PARITY=0
+CONFIG_USART2_PARITY=0
+CONFIG_USART3_PARITY=0
+
+CONFIG_USART1_2STOP=0
+CONFIG_USART2_2STOP=0
+CONFIG_USART3_2STOP=0
+
+CONFIG_USART1_RXDMA=y
+SERIAL_HAVE_CONSOLE_DMA=y
+# Conflicts with I2C1 DMA
+CONFIG_USART2_RXDMA=n
+CONFIG_USART3_RXDMA=y
+
+#
+# PX4IO specific driver settings
+#
+# CONFIG_HRT_TIMER
+# Enables the high-resolution timer. The board definition must
+# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/
+# compare channels to be used.
+# CONFIG_HRT_PPM
+# Enables R/C PPM input using the HRT. The board definition must
+# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
+# used, and define GPIO_PPM_IN to configure the appropriate timer
+# GPIO.
+# CONFIG_PWM_SERVO
+# Enables the PWM servo driver. The driver configuration must be
+# supplied by the board support at initialisation time.
+# Note that USART2 must be disabled on the PX4 board for this to
+# be available.
+#
+#
+CONFIG_HRT_TIMER=y
+CONFIG_HRT_PPM=y
+
+#
+# General build options
+#
+# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
+# BSPs from www.ridgerun.com using the tools/mkimage.sh script
+# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_RAW_BINARY - make a raw binary format file used with many
+# different loaders using the GNU objcopy program. This option
+# should not be selected if you are not using the GNU toolchain.
+# CONFIG_HAVE_LIBM - toolchain supports libm.a
+#
+CONFIG_RRLOAD_BINARY=n
+CONFIG_INTELHEX_BINARY=n
+CONFIG_MOTOROLA_SREC=n
+CONFIG_RAW_BINARY=y
+CONFIG_HAVE_LIBM=n
+
+#
+# General OS setup
+#
+# CONFIG_APPS_DIR - Identifies the relative path to the directory
+# that builds the application to link with NuttX. Default: ../apps
+# CONFIG_DEBUG - enables built-in debug options
+# CONFIG_DEBUG_VERBOSE - enables verbose debug output
+# CONFIG_DEBUG_SYMBOLS - build without optimization and with
+# debug symbols (needed for use with a debugger).
+# CONFIG_HAVE_CXX - Enable support for C++
+# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support
+# for initialization of static C++ instances for this architecture
+# and for the selected toolchain (via up_cxxinitialize()).
+# CONFIG_MM_REGIONS - If the architecture includes multiple
+# regions of memory to allocate from, this specifies the
+# number of memory regions that the memory manager must
+# handle and enables the API mm_addregion(start, end);
+# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
+# time console output
+# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
+# or MSEC_PER_TICK=10. This setting may be defined to
+# inform NuttX that the processor hardware is providing
+# system timer interrupts at some interrupt interval other
+# than 10 msec.
+# CONFIG_RR_INTERVAL - The round robin timeslice will be set
+# this number of milliseconds; Round robin scheduling can
+# be disabled by setting this value to zero.
+# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
+# scheduler to monitor system performance
+# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
+# task name to save in the TCB. Useful if scheduler
+# instrumentation is selected. Set to zero to disable.
+# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
+# Used to initialize the internal time logic.
+# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
+# You would only need this if you are concerned about accurate
+# time conversions in the past or in the distant future.
+# CONFIG_JULIAN_TIME - Enables Julian time conversions. You
+# would only need this if you are concerned about accurate
+# time conversion in the distand past. You must also define
+# CONFIG_GREGORIAN_TIME in order to use Julian time.
+# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
+# provides /dev/console. Enables stdout, stderr, stdin.
+# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console
+# driver (minimul support)
+# CONFIG_MUTEX_TYPES: Set to enable support for recursive and
+# errorcheck mutexes. Enables pthread_mutexattr_settype().
+# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority
+# inheritance on mutexes and semaphores.
+# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority
+# inheritance is enabled. It defines the maximum number of
+# different threads (minus one) that can take counts on a
+# semaphore with priority inheritance support. This may be
+# set to zero if priority inheritance is disabled OR if you
+# are only using semaphores as mutexes (only one holder) OR
+# if no more than two threads participate using a counting
+# semaphore.
+# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
+# then this setting is the maximum number of higher priority
+# threads (minus 1) than can be waiting for another thread
+# to release a count on a semaphore. This value may be set
+# to zero if no more than one thread is expected to wait for
+# a semaphore.
+# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
+# by task_create() when a new task is started. If set, all
+# files/drivers will appear to be closed in the new task.
+# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first
+# three file descriptors (stdin, stdout, stderr) by task_create()
+# when a new task is started. If set, all files/drivers will
+# appear to be closed in the new task except for stdin, stdout,
+# and stderr.
+# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
+# desciptors by task_create() when a new task is started. If
+# set, all sockets will appear to be closed in the new task.
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work in units of microseconds. Default: 50*1000 (50 MS).
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
+# CONFIG_SCHED_WAITPID - Enable the waitpid() API
+# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
+#
+CONFIG_USER_ENTRYPOINT="user_start"
+#CONFIG_APPS_DIR=
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEBUG_FS=n
+CONFIG_DEBUG_GRAPHICS=n
+CONFIG_DEBUG_LCD=n
+CONFIG_DEBUG_USB=n
+CONFIG_DEBUG_NET=n
+CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
+
+CONFIG_MSEC_PER_TICK=1
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_MM_REGIONS=1
+CONFIG_MM_SMALL=y
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=8
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
+CONFIG_GREGORIAN_TIME=n
+CONFIG_JULIAN_TIME=n
+# this eats ~1KiB of RAM ... work out why
+CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_LOWCONSOLE=n
+CONFIG_MUTEX_TYPES=n
+CONFIG_PRIORITY_INHERITANCE=n
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=0
+CONFIG_FDCLONE_DISABLE=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=50000
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
+CONFIG_SCHED_WAITPID=n
+CONFIG_SCHED_ATEXIT=n
+
+#
+# The following can be used to disable categories of
+# APIs supported by the OS. If the compiler supports
+# weak functions, then it should not be necessary to
+# disable functions unless you want to restrict usage
+# of those APIs.
+#
+# There are certain dependency relationships in these
+# features.
+#
+# o mq_notify logic depends on signals to awaken tasks
+# waiting for queues to become full or empty.
+# o pthread_condtimedwait() depends on signals to wake
+# up waiting tasks.
+#
+CONFIG_DISABLE_CLOCK=n
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_ENVIRON=y
+CONFIG_DISABLE_POLL=y
+
+#
+# Misc libc settings
+#
+# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
+# little smaller if we do not support fieldwidthes
+#
+CONFIG_NOPRINTF_FIELDWIDTH=n
+
+#
+# Allow for architecture optimized implementations
+#
+# The architecture can provide optimized versions of the
+# following to improve system performance
+#
+CONFIG_ARCH_MEMCPY=n
+CONFIG_ARCH_MEMCMP=n
+CONFIG_ARCH_MEMMOVE=n
+CONFIG_ARCH_MEMSET=n
+CONFIG_ARCH_STRCMP=n
+CONFIG_ARCH_STRCPY=n
+CONFIG_ARCH_STRNCPY=n
+CONFIG_ARCH_STRLEN=n
+CONFIG_ARCH_STRNLEN=n
+CONFIG_ARCH_BZERO=n
+
+#
+# Sizes of configurable things (0 disables)
+#
+# CONFIG_MAX_TASKS - The maximum number of simultaneously
+# active tasks. This value must be a power of two.
+# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
+# of parameters that a task may receive (i.e., maxmum value
+# of 'argc')
+# CONFIG_NPTHREAD_KEYS - The number of items of thread-
+# specific data that can be retained
+# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
+# descriptors (one for each open)
+# CONFIG_NFILE_STREAMS - The maximum number of streams that
+# can be fopen'ed
+# CONFIG_NAME_MAX - The maximum size of a file name.
+# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
+# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled
+# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added
+# to force automatic, line-oriented flushing the output buffer
+# for putc(), fputc(), putchar(), puts(), fputs(), printf(),
+# fprintf(), and vfprintf(). When a newline is encountered in
+# the output string, the output buffer will be flushed. This
+# (slightly) increases the NuttX footprint but supports the kind
+# of behavior that people expect for printf().
+# CONFIG_NUNGET_CHARS - Number of characters that can be
+# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
+# structures. The system manages a pool of preallocated
+# message structures to minimize dynamic allocations
+# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
+# a fixed payload size given by this settin (does not include
+# other message structure overhead.
+# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
+# can be passed to a watchdog handler
+# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
+# structures. The system manages a pool of preallocated
+# watchdog structures to minimize dynamic allocations
+# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
+# timer structures. The system manages a pool of preallocated
+# timer structures to minimize dynamic allocations. Set to
+# zero for all dynamic allocations.
+#
+CONFIG_MAX_TASKS=4
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=2
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=0
+CONFIG_NAME_MAX=12
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STDIO_LINEBUFFER=n
+CONFIG_NUNGET_CHARS=2
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=0
+
+
+#
+# Settings for apps/nshlib
+#
+# CONFIG_NSH_BUILTIN_APPS - Support external registered,
+# "named" applications that can be executed from the NSH
+# command line (see apps/README.txt for more information).
+# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
+# CONFIG_NSH_STRERROR - Use strerror(errno)
+# CONFIG_NSH_LINELEN - Maximum length of one command line
+# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
+# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
+# CONFIG_NSH_DISABLEBG - Disable background commands
+# CONFIG_NSH_ROMFSETC - Use startup script in /etc
+# CONFIG_NSH_CONSOLE - Use serial console front end
+# CONFIG_NSH_TELNET - Use telnetd console front end
+# CONFIG_NSH_ARCHINIT - Platform provides architecture
+# specific initialization (nsh_archinitialize()).
+#
+
+# Disable NSH completely
+CONFIG_NSH_CONSOLE=n
+
+#
+# Stack and heap information
+#
+# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
+# operation from FLASH but must copy initialized .data sections to RAM.
+# (should also be =n for the STM3210E-EVAL which always runs from flash)
+# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
+# but copy themselves entirely into RAM for better performance.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
+# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
+# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack.
+# This is the thread that (1) performs the inital boot of the system up
+# to the point where user_start() is spawned, and (2) there after is the
+# IDLE thread that executes only when there is no other thread ready to
+# run.
+# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate
+# for the main user thread that begins at the user_start() entry point.
+# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
+# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
+# CONFIG_HEAP_BASE - The beginning of the heap
+# CONFIG_HEAP_SIZE - The size of the heap
+#
+CONFIG_BOOT_RUNFROMFLASH=n
+CONFIG_BOOT_COPYTORAM=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_STACK_POINTER=
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=1200
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx/configs/px4io-v1/io/setenv.sh b/nuttx/configs/px4io-v1/io/setenv.sh
new file mode 100755
index 000000000..ff9a4bf8a
--- /dev/null
+++ b/nuttx/configs/px4io-v1/io/setenv.sh
@@ -0,0 +1,47 @@
+#!/bin/bash
+# configs/stm3210e-eval/dfu/setenv.sh
+#
+# Copyright (C) 2009 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.
+#
+
+if [ "$(basename $0)" = "setenv.sh" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
+
+WD=`pwd`
+export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
+export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/px4io-v1/nsh/Make.defs b/nuttx/configs/px4io-v1/nsh/Make.defs
new file mode 100644
index 000000000..87508e22e
--- /dev/null
+++ b/nuttx/configs/px4io-v1/nsh/Make.defs
@@ -0,0 +1,3 @@
+include ${TOPDIR}/.config
+
+include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs
diff --git a/nuttx/configs/px4io-v1/nsh/appconfig b/nuttx/configs/px4io-v1/nsh/appconfig
new file mode 100644
index 000000000..d5809a939
--- /dev/null
+++ b/nuttx/configs/px4io-v1/nsh/appconfig
@@ -0,0 +1,43 @@
+############################################################################
+# configs/stm3210e-eval/nsh/appconfig
+#
+# Copyright (C) 2011-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.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/nsh
+
+CONFIGURED_APPS += system/readline
+CONFIGURED_APPS += nshlib
+CONFIGURED_APPS += reboot
+
diff --git a/nuttx/configs/px4io-v1/nsh/defconfig b/nuttx/configs/px4io-v1/nsh/defconfig
new file mode 100755
index 000000000..6f4e20869
--- /dev/null
+++ b/nuttx/configs/px4io-v1/nsh/defconfig
@@ -0,0 +1,565 @@
+############################################################################
+# configs/px4io/nsh/defconfig
+#
+# Copyright (C) 2009-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.
+#
+############################################################################
+#
+# architecture selection
+#
+# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
+# processor architecture.
+# CONFIG_ARCH_family - for use in C code. This identifies the
+# particular chip family that the architecture is implemented
+# in.
+# CONFIG_ARCH_architecture - for use in C code. This identifies the
+# specific architecture within the chip familyl.
+# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+# CONFIG_ARCH_CHIP_name - For use in C code
+# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
+# the board that supports the particular chip or SoC.
+# CONFIG_ARCH_BOARD_name - for use in C code
+# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
+# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
+# CONFIG_DRAM_SIZE - Describes the installed DRAM.
+# CONFIG_DRAM_START - The start address of DRAM (physical)
+# CONFIG_DRAM_END - Last address+1 of installed RAM
+# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization
+# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+# stack. If defined, this symbol is the size of the interrupt
+# stack in bytes. If not defined, the user task stacks will be
+# used during interrupt handling.
+# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
+# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
+# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+# cause a 100 second delay during boot-up. This 100 second delay
+# serves no purpose other than it allows you to calibrate
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
+# the delay actually is 100 seconds.
+# CONFIG_ARCH_DMA - Support DMA initialization
+#
+CONFIG_ARCH=arm
+CONFIG_ARCH_ARM=y
+CONFIG_ARCH_CORTEXM3=y
+CONFIG_ARCH_CHIP=stm32
+CONFIG_ARCH_CHIP_STM32F100C8=y
+CONFIG_ARCH_BOARD=px4io
+CONFIG_ARCH_BOARD_PX4IO=y
+CONFIG_BOARD_LOOPSPERMSEC=24000
+CONFIG_DRAM_SIZE=0x00002000
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARCH_BOOTLOADER=n
+CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=y
+CONFIG_ARCH_CALIBRATION=n
+CONFIG_ARCH_DMA=n
+CONFIG_ARMV7M_CMNVECTOR=y
+
+#
+# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
+#
+# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG
+#
+# JTAG Enable options:
+#
+# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# but without JNTRST.
+# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+#
+CONFIG_STM32_DFU=n
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
+CONFIG_STM32_JTAG_SW_ENABLE=n
+
+#
+# Individual subsystems can be enabled:
+# AHB:
+CONFIG_STM32_DMA1=n
+CONFIG_STM32_DMA2=n
+CONFIG_STM32_CRC=n
+# APB1:
+# Timers 2,3 and 4 are owned by the PWM driver
+CONFIG_STM32_TIM2=n
+CONFIG_STM32_TIM3=n
+CONFIG_STM32_TIM4=n
+CONFIG_STM32_TIM5=n
+CONFIG_STM32_TIM6=n
+CONFIG_STM32_TIM7=n
+CONFIG_STM32_WWDG=n
+CONFIG_STM32_SPI2=n
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=y
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=n
+CONFIG_STM32_BKP=n
+CONFIG_STM32_PWR=n
+CONFIG_STM32_DAC=n
+# APB2:
+CONFIG_STM32_ADC1=y
+CONFIG_STM32_ADC2=n
+# TIM1 is owned by the HRT
+CONFIG_STM32_TIM1=n
+CONFIG_STM32_SPI1=n
+CONFIG_STM32_TIM8=n
+CONFIG_STM32_USART1=y
+CONFIG_STM32_ADC3=n
+
+#
+# Timer and I2C devices may need to the following to force power to be applied:
+#
+#CONFIG_STM32_FORCEPOWER=y
+
+#
+# STM32F100 specific serial device driver settings
+#
+# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
+# console and ttys0 (default is the USART1).
+# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received.
+# This specific the size of the receive buffer
+# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before
+# being sent. This specific the size of the transmit buffer
+# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be
+# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8.
+# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+# CONFIG_USARTn_2STOP - Two stop bits
+#
+CONFIG_USART1_SERIAL_CONSOLE=y
+CONFIG_USART2_SERIAL_CONSOLE=n
+CONFIG_USART3_SERIAL_CONSOLE=n
+
+CONFIG_USART1_TXBUFSIZE=64
+CONFIG_USART2_TXBUFSIZE=64
+CONFIG_USART3_TXBUFSIZE=64
+
+CONFIG_USART1_RXBUFSIZE=64
+CONFIG_USART2_RXBUFSIZE=64
+CONFIG_USART3_RXBUFSIZE=64
+
+CONFIG_USART1_BAUD=57600
+CONFIG_USART2_BAUD=115200
+CONFIG_USART3_BAUD=115200
+
+CONFIG_USART1_BITS=8
+CONFIG_USART2_BITS=8
+CONFIG_USART3_BITS=8
+
+CONFIG_USART1_PARITY=0
+CONFIG_USART2_PARITY=0
+CONFIG_USART3_PARITY=0
+
+CONFIG_USART1_2STOP=0
+CONFIG_USART2_2STOP=0
+CONFIG_USART3_2STOP=0
+
+#
+# PX4IO specific driver settings
+#
+# CONFIG_HRT_TIMER
+# Enables the high-resolution timer. The board definition must
+# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/
+# compare channels to be used.
+# CONFIG_HRT_PPM
+# Enables R/C PPM input using the HRT. The board definition must
+# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
+# used, and define GPIO_PPM_IN to configure the appropriate timer
+# GPIO.
+# CONFIG_PWM_SERVO
+# Enables the PWM servo driver. The driver configuration must be
+# supplied by the board support at initialisation time.
+# Note that USART2 must be disabled on the PX4 board for this to
+# be available.
+#
+#
+CONFIG_HRT_TIMER=y
+CONFIG_HRT_PPM=y
+CONFIG_PWM_SERVO=y
+
+#
+# General build options
+#
+# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
+# BSPs from www.ridgerun.com using the tools/mkimage.sh script
+# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_RAW_BINARY - make a raw binary format file used with many
+# different loaders using the GNU objcopy program. This option
+# should not be selected if you are not using the GNU toolchain.
+# CONFIG_HAVE_LIBM - toolchain supports libm.a
+#
+CONFIG_RRLOAD_BINARY=n
+CONFIG_INTELHEX_BINARY=n
+CONFIG_MOTOROLA_SREC=n
+CONFIG_RAW_BINARY=y
+CONFIG_HAVE_LIBM=n
+
+#
+# General OS setup
+#
+# CONFIG_APPS_DIR - Identifies the relative path to the directory
+# that builds the application to link with NuttX. Default: ../apps
+# CONFIG_DEBUG - enables built-in debug options
+# CONFIG_DEBUG_VERBOSE - enables verbose debug output
+# CONFIG_DEBUG_SYMBOLS - build without optimization and with
+# debug symbols (needed for use with a debugger).
+# CONFIG_HAVE_CXX - Enable support for C++
+# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support
+# for initialization of static C++ instances for this architecture
+# and for the selected toolchain (via up_cxxinitialize()).
+# CONFIG_MM_REGIONS - If the architecture includes multiple
+# regions of memory to allocate from, this specifies the
+# number of memory regions that the memory manager must
+# handle and enables the API mm_addregion(start, end);
+# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
+# time console output
+# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
+# or MSEC_PER_TICK=10. This setting may be defined to
+# inform NuttX that the processor hardware is providing
+# system timer interrupts at some interrupt interval other
+# than 10 msec.
+# CONFIG_RR_INTERVAL - The round robin timeslice will be set
+# this number of milliseconds; Round robin scheduling can
+# be disabled by setting this value to zero.
+# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
+# scheduler to monitor system performance
+# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
+# task name to save in the TCB. Useful if scheduler
+# instrumentation is selected. Set to zero to disable.
+# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
+# Used to initialize the internal time logic.
+# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
+# You would only need this if you are concerned about accurate
+# time conversions in the past or in the distant future.
+# CONFIG_JULIAN_TIME - Enables Julian time conversions. You
+# would only need this if you are concerned about accurate
+# time conversion in the distand past. You must also define
+# CONFIG_GREGORIAN_TIME in order to use Julian time.
+# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
+# provides /dev/console. Enables stdout, stderr, stdin.
+# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console
+# driver (minimul support)
+# CONFIG_MUTEX_TYPES: Set to enable support for recursive and
+# errorcheck mutexes. Enables pthread_mutexattr_settype().
+# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority
+# inheritance on mutexes and semaphores.
+# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority
+# inheritance is enabled. It defines the maximum number of
+# different threads (minus one) that can take counts on a
+# semaphore with priority inheritance support. This may be
+# set to zero if priority inheritance is disabled OR if you
+# are only using semaphores as mutexes (only one holder) OR
+# if no more than two threads participate using a counting
+# semaphore.
+# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
+# then this setting is the maximum number of higher priority
+# threads (minus 1) than can be waiting for another thread
+# to release a count on a semaphore. This value may be set
+# to zero if no more than one thread is expected to wait for
+# a semaphore.
+# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
+# by task_create() when a new task is started. If set, all
+# files/drivers will appear to be closed in the new task.
+# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first
+# three file descriptors (stdin, stdout, stderr) by task_create()
+# when a new task is started. If set, all files/drivers will
+# appear to be closed in the new task except for stdin, stdout,
+# and stderr.
+# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
+# desciptors by task_create() when a new task is started. If
+# set, all sockets will appear to be closed in the new task.
+# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
+# This format will support execution of NuttX binaries located
+# in a ROMFS filesystem (see examples/nxflat).
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work in units of microseconds. Default: 50*1000 (50 MS).
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
+#
+#CONFIG_APPS_DIR=
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_HAVE_CXX=n
+CONFIG_HAVE_CXXINITIALIZE=n
+CONFIG_MM_REGIONS=1
+CONFIG_MM_SMALL=y
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_RR_INTERVAL=200
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_START_YEAR=2009
+CONFIG_START_MONTH=9
+CONFIG_START_DAY=21
+CONFIG_GREGORIAN_TIME=n
+CONFIG_JULIAN_TIME=n
+CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_LOWCONSOLE=n
+CONFIG_MUTEX_TYPES=n
+CONFIG_PRIORITY_INHERITANCE=n
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=0
+CONFIG_FDCLONE_DISABLE=n
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_NXFLAT=n
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=(50*1000)
+CONFIG_SCHED_WORKSTACKSIZE=512
+CONFIG_SIG_SIGWORK=4
+
+#
+# The following can be used to disable categories of
+# APIs supported by the OS. If the compiler supports
+# weak functions, then it should not be necessary to
+# disable functions unless you want to restrict usage
+# of those APIs.
+#
+# There are certain dependency relationships in these
+# features.
+#
+# o mq_notify logic depends on signals to awaken tasks
+# waiting for queues to become full or empty.
+# o pthread_condtimedwait() depends on signals to wake
+# up waiting tasks.
+#
+CONFIG_DISABLE_CLOCK=n
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=n
+CONFIG_DISABLE_SIGNALS=n
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_ENVIRON=y
+CONFIG_DISABLE_POLL=y
+
+#
+# Misc libc settings
+#
+# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
+# little smaller if we do not support fieldwidthes
+#
+CONFIG_NOPRINTF_FIELDWIDTH=n
+
+#
+# Allow for architecture optimized implementations
+#
+# The architecture can provide optimized versions of the
+# following to improve system performance
+#
+CONFIG_ARCH_MEMCPY=n
+CONFIG_ARCH_MEMCMP=n
+CONFIG_ARCH_MEMMOVE=n
+CONFIG_ARCH_MEMSET=n
+CONFIG_ARCH_STRCMP=n
+CONFIG_ARCH_STRCPY=n
+CONFIG_ARCH_STRNCPY=n
+CONFIG_ARCH_STRLEN=n
+CONFIG_ARCH_STRNLEN=n
+CONFIG_ARCH_BZERO=n
+
+#
+# Sizes of configurable things (0 disables)
+#
+# CONFIG_MAX_TASKS - The maximum number of simultaneously
+# active tasks. This value must be a power of two.
+# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
+# of parameters that a task may receive (i.e., maxmum value
+# of 'argc')
+# CONFIG_NPTHREAD_KEYS - The number of items of thread-
+# specific data that can be retained
+# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
+# descriptors (one for each open)
+# CONFIG_NFILE_STREAMS - The maximum number of streams that
+# can be fopen'ed
+# CONFIG_NAME_MAX - The maximum size of a file name.
+# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
+# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_NUNGET_CHARS - Number of characters that can be
+# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
+# structures. The system manages a pool of preallocated
+# message structures to minimize dynamic allocations
+# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
+# a fixed payload size given by this settin (does not include
+# other message structure overhead.
+# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
+# can be passed to a watchdog handler
+# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
+# structures. The system manages a pool of preallocated
+# watchdog structures to minimize dynamic allocations
+# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
+# timer structures. The system manages a pool of preallocated
+# timer structures to minimize dynamic allocations. Set to
+# zero for all dynamic allocations.
+#
+CONFIG_MAX_TASKS=4
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=2
+CONFIG_NFILE_DESCRIPTORS=6
+CONFIG_NFILE_STREAMS=4
+CONFIG_NAME_MAX=32
+CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_NUNGET_CHARS=2
+CONFIG_PREALLOC_MQ_MSGS=1
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=3
+CONFIG_PREALLOC_TIMERS=1
+
+
+#
+# Settings for apps/nshlib
+#
+# CONFIG_NSH_BUILTIN_APPS - Support external registered,
+# "named" applications that can be executed from the NSH
+# command line (see apps/README.txt for more information).
+# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
+# CONFIG_NSH_STRERROR - Use strerror(errno)
+# CONFIG_NSH_LINELEN - Maximum length of one command line
+# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
+# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
+# CONFIG_NSH_DISABLEBG - Disable background commands
+# CONFIG_NSH_ROMFSETC - Use startup script in /etc
+# CONFIG_NSH_CONSOLE - Use serial console front end
+# CONFIG_NSH_TELNET - Use telnetd console front end
+# CONFIG_NSH_ARCHINIT - Platform provides architecture
+# specific initialization (nsh_archinitialize()).
+#
+# If CONFIG_NSH_TELNET is selected:
+# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size
+# CONFIG_NSH_DHCPC - Obtain address using DHCP
+# CONFIG_NSH_IPADDR - Provides static IP address
+# CONFIG_NSH_DRIPADDR - Provides static router IP address
+# CONFIG_NSH_NETMASK - Provides static network mask
+# CONFIG_NSH_NOMAC - Use a bogus MAC address
+#
+# If CONFIG_NSH_ROMFSETC is selected:
+# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint
+# CONFIG_NSH_INITSCRIPT - Relative path to init script
+# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor
+# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size
+# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor
+# CONFIG_NSH_FATSECTSIZE - FAT FS sector size
+# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors
+# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint
+#
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_FILEIOSIZE=64
+CONFIG_NSH_STRERROR=n
+CONFIG_NSH_LINELEN=64
+CONFIG_NSH_NESTDEPTH=1
+CONFIG_NSH_DISABLESCRIPT=y
+CONFIG_NSH_DISABLEBG=n
+CONFIG_NSH_ROMFSETC=n
+CONFIG_NSH_CONSOLE=y
+CONFIG_NSH_TELNET=n
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_IOBUFFER_SIZE=256
+#CONFIG_NSH_STACKSIZE=1024
+CONFIG_NSH_DHCPC=n
+CONFIG_NSH_NOMAC=n
+CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2)
+CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1)
+CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0)
+CONFIG_NSH_ROMFSMOUNTPT="/etc"
+CONFIG_NSH_INITSCRIPT="init.d/rcS"
+CONFIG_NSH_ROMFSDEVNO=0
+CONFIG_NSH_ROMFSSECTSIZE=64
+CONFIG_NSH_FATDEVNO=1
+CONFIG_NSH_FATSECTSIZE=512
+CONFIG_NSH_FATNSECTORS=1024
+CONFIG_NSH_FATMOUNTPT=/tmp
+
+#
+# Architecture-specific NSH options
+#
+CONFIG_NSH_MMCSDSPIPORTNO=0
+CONFIG_NSH_MMCSDSLOTNO=0
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Stack and heap information
+#
+# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
+# operation from FLASH but must copy initialized .data sections to RAM.
+# (should also be =n for the STM3210E-EVAL which always runs from flash)
+# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
+# but copy themselves entirely into RAM for better performance.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
+# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
+# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack.
+# This is the thread that (1) performs the inital boot of the system up
+# to the point where user_start() is spawned, and (2) there after is the
+# IDLE thread that executes only when there is no other thread ready to
+# run.
+# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate
+# for the main user thread that begins at the user_start() entry point.
+# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
+# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
+# CONFIG_HEAP_BASE - The beginning of the heap
+# CONFIG_HEAP_SIZE - The size of the heap
+#
+CONFIG_BOOT_RUNFROMFLASH=n
+CONFIG_BOOT_COPYTORAM=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_STACK_POINTER=
+CONFIG_IDLETHREAD_STACKSIZE=800
+CONFIG_USERMAIN_STACKSIZE=1024
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=512
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx/configs/px4io-v1/nsh/setenv.sh b/nuttx/configs/px4io-v1/nsh/setenv.sh
new file mode 100755
index 000000000..d83685192
--- /dev/null
+++ b/nuttx/configs/px4io-v1/nsh/setenv.sh
@@ -0,0 +1,47 @@
+#!/bin/bash
+# configs/stm3210e-eval/dfu/setenv.sh
+#
+# Copyright (C) 2009 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.
+#
+
+if [ "$(basename $0)" = "setenv.sh" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
+
+WD=`pwd`
+export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
+export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
+export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/px4io-v1/src/Makefile b/nuttx/configs/px4io-v1/src/Makefile
new file mode 100644
index 000000000..bb9539d16
--- /dev/null
+++ b/nuttx/configs/px4io-v1/src/Makefile
@@ -0,0 +1,84 @@
+############################################################################
+# configs/stm3210e-eval/src/Makefile
+#
+# Copyright (C) 2009-2010 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = empty.c
+
+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)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/nuttx/configs/px4io-v1/src/README.txt b/nuttx/configs/px4io-v1/src/README.txt
new file mode 100644
index 000000000..d4eda82fd
--- /dev/null
+++ b/nuttx/configs/px4io-v1/src/README.txt
@@ -0,0 +1 @@
+This directory contains drivers unique to the STMicro STM3210E-EVAL development board.
diff --git a/nuttx/configs/px4io-v1/src/drv_i2c_device.c b/nuttx/configs/px4io-v1/src/drv_i2c_device.c
new file mode 100644
index 000000000..1f5931ae5
--- /dev/null
+++ b/nuttx/configs/px4io-v1/src/drv_i2c_device.c
@@ -0,0 +1,618 @@
+/****************************************************************************
+ *
+ * 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 A simple, polled I2C slave-mode driver.
+ *
+ * The master writes to and reads from a byte buffer, which the caller
+ * can update inbetween calls to the FSM.
+ */
+
+#include <stdbool.h>
+
+#include "stm32_i2c.h"
+
+#include <string.h>
+
+/*
+ * I2C register definitions.
+ */
+#define I2C_BASE STM32_I2C1_BASE
+
+#define REG(_reg) (*(volatile uint32_t *)(I2C_BASE + _reg))
+
+#define rCR1 REG(STM32_I2C_CR1_OFFSET)
+#define rCR2 REG(STM32_I2C_CR2_OFFSET)
+#define rOAR1 REG(STM32_I2C_OAR1_OFFSET)
+#define rOAR2 REG(STM32_I2C_OAR2_OFFSET)
+#define rDR REG(STM32_I2C_DR_OFFSET)
+#define rSR1 REG(STM32_I2C_SR1_OFFSET)
+#define rSR2 REG(STM32_I2C_SR2_OFFSET)
+#define rCCR REG(STM32_I2C_CCR_OFFSET)
+#define rTRISE REG(STM32_I2C_TRISE_OFFSET)
+
+/*
+ * "event" values (cr2 << 16 | cr1) as described in the ST DriverLib
+ */
+#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */
+#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */
+#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */
+#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */
+#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */
+#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */
+#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */
+
+/**
+ * States implemented by the I2C FSM.
+ */
+enum fsm_state {
+ BAD_PHASE, // must be zero, default exit on a bad state transition
+
+ WAIT_FOR_MASTER,
+
+ /* write from master */
+ WAIT_FOR_COMMAND,
+ RECEIVE_COMMAND,
+ RECEIVE_DATA,
+ HANDLE_COMMAND,
+
+ /* read from master */
+ WAIT_TO_SEND,
+ SEND_STATUS,
+ SEND_DATA,
+
+ NUM_STATES
+};
+
+/**
+ * Events recognised by the I2C FSM.
+ */
+enum fsm_event {
+ /* automatic transition */
+ AUTO,
+
+ /* write from master */
+ ADDRESSED_WRITE,
+ BYTE_RECEIVED,
+ STOP_RECEIVED,
+
+ /* read from master */
+ ADDRESSED_READ,
+ BYTE_SENDABLE,
+ ACK_FAILED,
+
+ NUM_EVENTS
+};
+
+/**
+ * Context for the I2C FSM
+ */
+static struct fsm_context {
+ enum fsm_state state;
+
+ /* XXX want to eliminate these */
+ uint8_t command;
+ uint8_t status;
+
+ uint8_t *data_ptr;
+ uint32_t data_count;
+
+ size_t buffer_size;
+ uint8_t *buffer;
+} context;
+
+/**
+ * Structure defining one FSM state and its outgoing transitions.
+ */
+struct fsm_transition {
+ void (*handler)(void);
+ enum fsm_state next_state[NUM_EVENTS];
+};
+
+static bool i2c_command_received;
+
+static void fsm_event(enum fsm_event event);
+
+static void go_bad(void);
+static void go_wait_master(void);
+
+static void go_wait_command(void);
+static void go_receive_command(void);
+static void go_receive_data(void);
+static void go_handle_command(void);
+
+static void go_wait_send(void);
+static void go_send_status(void);
+static void go_send_buffer(void);
+
+/**
+ * The FSM state graph.
+ */
+static const struct fsm_transition fsm[NUM_STATES] = {
+ [BAD_PHASE] = {
+ .handler = go_bad,
+ .next_state = {
+ [AUTO] = WAIT_FOR_MASTER,
+ },
+ },
+
+ [WAIT_FOR_MASTER] = {
+ .handler = go_wait_master,
+ .next_state = {
+ [ADDRESSED_WRITE] = WAIT_FOR_COMMAND,
+ [ADDRESSED_READ] = WAIT_TO_SEND,
+ },
+ },
+
+ /* write from master*/
+ [WAIT_FOR_COMMAND] = {
+ .handler = go_wait_command,
+ .next_state = {
+ [BYTE_RECEIVED] = RECEIVE_COMMAND,
+ [STOP_RECEIVED] = WAIT_FOR_MASTER,
+ },
+ },
+ [RECEIVE_COMMAND] = {
+ .handler = go_receive_command,
+ .next_state = {
+ [BYTE_RECEIVED] = RECEIVE_DATA,
+ [STOP_RECEIVED] = HANDLE_COMMAND,
+ },
+ },
+ [RECEIVE_DATA] = {
+ .handler = go_receive_data,
+ .next_state = {
+ [BYTE_RECEIVED] = RECEIVE_DATA,
+ [STOP_RECEIVED] = HANDLE_COMMAND,
+ },
+ },
+ [HANDLE_COMMAND] = {
+ .handler = go_handle_command,
+ .next_state = {
+ [AUTO] = WAIT_FOR_MASTER,
+ },
+ },
+
+ /* buffer send */
+ [WAIT_TO_SEND] = {
+ .handler = go_wait_send,
+ .next_state = {
+ [BYTE_SENDABLE] = SEND_STATUS,
+ },
+ },
+ [SEND_STATUS] = {
+ .handler = go_send_status,
+ .next_state = {
+ [BYTE_SENDABLE] = SEND_DATA,
+ [ACK_FAILED] = WAIT_FOR_MASTER,
+ },
+ },
+ [SEND_DATA] = {
+ .handler = go_send_buffer,
+ .next_state = {
+ [BYTE_SENDABLE] = SEND_DATA,
+ [ACK_FAILED] = WAIT_FOR_MASTER,
+ },
+ },
+};
+
+
+/* debug support */
+#if 1
+struct fsm_logentry {
+ char kind;
+ uint32_t code;
+};
+
+#define LOG_ENTRIES 32
+static struct fsm_logentry fsm_log[LOG_ENTRIES];
+int fsm_logptr;
+#define LOG_NEXT(_x) (((_x) + 1) % LOG_ENTRIES)
+#define LOGx(_kind, _code) \
+ do { \
+ fsm_log[fsm_logptr].kind = _kind; \
+ fsm_log[fsm_logptr].code = _code; \
+ fsm_logptr = LOG_NEXT(fsm_logptr); \
+ fsm_log[fsm_logptr].kind = 0; \
+ } while(0)
+
+#define LOG(_kind, _code) \
+ do {\
+ if (fsm_logptr < LOG_ENTRIES) { \
+ fsm_log[fsm_logptr].kind = _kind; \
+ fsm_log[fsm_logptr].code = _code; \
+ fsm_logptr++;\
+ }\
+ }while(0)
+
+#else
+#define LOG(_kind, _code)
+#endif
+
+
+static void i2c_setclock(uint32_t frequency);
+
+/**
+ * Initialise I2C
+ *
+ */
+void
+i2c_fsm_init(uint8_t *buffer, size_t buffer_size)
+{
+ /* save the buffer */
+ context.buffer = buffer;
+ context.buffer_size = buffer_size;
+
+ // initialise the FSM
+ context.status = 0;
+ context.command = 0;
+ context.state = BAD_PHASE;
+ fsm_event(AUTO);
+
+#if 0
+ // enable the i2c block clock and reset it
+ modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C1EN);
+ modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C1RST);
+ modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C1RST, 0);
+
+ // configure the i2c GPIOs
+ stm32_configgpio(GPIO_I2C1_SCL);
+ stm32_configgpio(GPIO_I2C1_SDA);
+
+ // set the peripheral clock to match the APB clock
+ rCR2 = STM32_PCLK1_FREQUENCY / 1000000;
+
+ // configure for 100kHz operation
+ i2c_setclock(100000);
+
+ // enable i2c
+ rCR1 = I2C_CR1_PE;
+#endif
+}
+
+/**
+ * Run the I2C FSM for some period.
+ *
+ * @return True if the buffer has been updated by a command.
+ */
+bool
+i2c_fsm(void)
+{
+ uint32_t event;
+ int idle_iterations = 0;
+
+ for (;;) {
+ // handle bus error states by discarding the current operation
+ if (rSR1 & I2C_SR1_BERR) {
+ context.state = WAIT_FOR_MASTER;
+ rSR1 = ~I2C_SR1_BERR;
+ }
+
+ // we do not anticipate over/underrun errors as clock-stretching is enabled
+
+ // fetch the most recent event
+ event = ((rSR2 << 16) | rSR1) & 0x00ffffff;
+
+ // generate FSM events based on I2C events
+ switch (event) {
+ case I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED:
+ LOG('w', 0);
+ fsm_event(ADDRESSED_WRITE);
+ break;
+
+ case I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED:
+ LOG('r', 0);
+ fsm_event(ADDRESSED_READ);
+ break;
+
+ case I2C_EVENT_SLAVE_BYTE_RECEIVED:
+ LOG('R', 0);
+ fsm_event(BYTE_RECEIVED);
+ break;
+
+ case I2C_EVENT_SLAVE_STOP_DETECTED:
+ LOG('s', 0);
+ fsm_event(STOP_RECEIVED);
+ break;
+
+ case I2C_EVENT_SLAVE_BYTE_TRANSMITTING:
+ //case I2C_EVENT_SLAVE_BYTE_TRANSMITTED:
+ LOG('T', 0);
+ fsm_event(BYTE_SENDABLE);
+ break;
+
+ case I2C_EVENT_SLAVE_ACK_FAILURE:
+ LOG('a', 0);
+ fsm_event(ACK_FAILED);
+ break;
+
+ default:
+ idle_iterations++;
+// if ((event) && (event != 0x00020000))
+// LOG('e', event);
+ break;
+ }
+
+ /* if we have just received something, drop out and let the caller handle it */
+ if (i2c_command_received) {
+ i2c_command_received = false;
+ return true;
+ }
+
+ /* if we have done nothing recently, drop out and let the caller have a slice */
+ if (idle_iterations > 1000)
+ return false;
+ }
+}
+
+/**
+ * Update the FSM with an event
+ *
+ * @param event New event.
+ */
+static void
+fsm_event(enum fsm_event event)
+{
+ // move to the next state
+ context.state = fsm[context.state].next_state[event];
+
+ LOG('f', context.state);
+
+ // call the state entry handler
+ if (fsm[context.state].handler) {
+ fsm[context.state].handler();
+ }
+}
+
+static void
+go_bad()
+{
+ LOG('B', 0);
+ fsm_event(AUTO);
+}
+
+/**
+ * Wait for the master to address us.
+ *
+ */
+static void
+go_wait_master()
+{
+ // We currently don't have a command byte.
+ //
+ context.command = '\0';
+
+ // The data pointer starts pointing to the start of the data buffer.
+ //
+ context.data_ptr = context.buffer;
+
+ // The data count is either:
+ // - the size of the data buffer
+ // - some value less than or equal the size of the data buffer during a write or a read
+ //
+ context.data_count = context.buffer_size;
+
+ // (re)enable the peripheral, clear the stop event flag in
+ // case we just finished receiving data
+ rCR1 |= I2C_CR1_PE;
+
+ // clear the ACK failed flag in case we just finished sending data
+ rSR1 = ~I2C_SR1_AF;
+}
+
+/**
+ * Prepare to receive a command byte.
+ *
+ */
+static void
+go_wait_command()
+{
+ // NOP
+}
+
+/**
+ * Command byte has been received, save it and prepare to handle the data.
+ *
+ */
+static void
+go_receive_command()
+{
+
+ // fetch the command byte
+ context.command = (uint8_t)rDR;
+ LOG('c', context.command);
+
+}
+
+/**
+ * Receive a data byte.
+ *
+ */
+static void
+go_receive_data()
+{
+ uint8_t d;
+
+ // fetch the byte
+ d = (uint8_t)rDR;
+ LOG('d', d);
+
+ // if we have somewhere to put it, do so
+ if (context.data_count) {
+ *context.data_ptr++ = d;
+ context.data_count--;
+ }
+}
+
+/**
+ * Handle a command once the host is done sending it to us.
+ *
+ */
+static void
+go_handle_command()
+{
+ // presume we are happy with the command
+ context.status = 0;
+
+ // make a note that the buffer contains a fresh command
+ i2c_command_received = true;
+
+ // kick along to the next state
+ fsm_event(AUTO);
+}
+
+/**
+ * Wait to be able to send the status byte.
+ *
+ */
+static void
+go_wait_send()
+{
+ // NOP
+}
+
+/**
+ * Send the status byte.
+ *
+ */
+static void
+go_send_status()
+{
+ rDR = context.status;
+ LOG('?', context.status);
+}
+
+/**
+ * Send a data or pad byte.
+ *
+ */
+static void
+go_send_buffer()
+{
+ if (context.data_count) {
+ LOG('D', *context.data_ptr);
+ rDR = *(context.data_ptr++);
+ context.data_count--;
+ } else {
+ LOG('-', 0);
+ rDR = 0xff;
+ }
+}
+
+/* cribbed directly from the NuttX master driver */
+static void
+i2c_setclock(uint32_t frequency)
+{
+ uint16_t cr1;
+ uint16_t ccr;
+ uint16_t trise;
+ uint16_t freqmhz;
+ uint16_t speed;
+
+ /* Disable the selected I2C peripheral to configure TRISE */
+
+ cr1 = rCR1;
+ rCR1 &= ~I2C_CR1_PE;
+
+ /* Update timing and control registers */
+
+ freqmhz = (uint16_t)(STM32_PCLK1_FREQUENCY / 1000000);
+ ccr = 0;
+
+ /* Configure speed in standard mode */
+
+ if (frequency <= 100000) {
+ /* Standard mode speed calculation */
+
+ speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency << 1));
+
+ /* The CCR fault must be >= 4 */
+
+ if (speed < 4) {
+ /* Set the minimum allowed value */
+
+ speed = 4;
+ }
+ ccr |= speed;
+
+ /* Set Maximum Rise Time for standard mode */
+
+ trise = freqmhz + 1;
+
+ /* Configure speed in fast mode */
+ } else { /* (frequency <= 400000) */
+ /* Fast mode speed calculation with Tlow/Thigh = 16/9 */
+
+#ifdef CONFIG_I2C_DUTY16_9
+ speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25));
+
+ /* Set DUTY and fast speed bits */
+
+ ccr |= (I2C_CCR_DUTY|I2C_CCR_FS);
+#else
+ /* Fast mode speed calculation with Tlow/Thigh = 2 */
+
+ speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 3));
+
+ /* Set fast speed bit */
+
+ ccr |= I2C_CCR_FS;
+#endif
+
+ /* Verify that the CCR speed value is nonzero */
+
+ if (speed < 1) {
+ /* Set the minimum allowed value */
+
+ speed = 1;
+ }
+ ccr |= speed;
+
+ /* Set Maximum Rise Time for fast mode */
+
+ trise = (uint16_t)(((freqmhz * 300) / 1000) + 1);
+ }
+
+ /* Write the new values of the CCR and TRISE registers */
+
+ rCCR = ccr;
+ rTRISE = trise;
+
+ /* Bit 14 of OAR1 must be configured and kept at 1 */
+
+ rOAR1 = I2C_OAR1_ONE);
+
+ /* Re-enable the peripheral (or not) */
+
+ rCR1 = cr1;
+}
diff --git a/nuttx/configs/px4io-v1/src/empty.c b/nuttx/configs/px4io-v1/src/empty.c
new file mode 100644
index 000000000..ace900866
--- /dev/null
+++ b/nuttx/configs/px4io-v1/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */