summaryrefslogtreecommitdiff
path: root/nuttx/configs/px4fmu-v1/src
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/px4fmu-v1/src')
-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
13 files changed, 19 insertions, 1582 deletions
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 */