From a7ba7af89ac2c119bf24bfe502d03bcc0ca34871 Mon Sep 17 00:00:00 2001
From: David Sidrane <david_s5@nscdg.com>
Date: Thu, 10 Aug 2017 08:18:37 -1000
Subject: [PATCH] FMUv1:Removed FMUv1 board from PX4

---
 Images/px4fmu-v1.prototype                    |   12 -
 Makefile                                      |    1 -
 cmake/configs/nuttx_px4fmu-v1_default.cmake   |  189 ---
 nuttx-configs/px4fmu-v1/include/board.h       |  331 ----
 .../px4fmu-v1/include/nsh_romfsimg.h          |   42 -
 nuttx-configs/px4fmu-v1/nsh/Make.defs         |  164 --
 nuttx-configs/px4fmu-v1/nsh/defconfig         | 1467 -----------------
 nuttx-configs/px4fmu-v1/nsh/setenv.sh         |   75 -
 nuttx-configs/px4fmu-v1/scripts/ld.script     |  149 --
 nuttx-configs/px4fmu-v1/src/Makefile          |   87 -
 nuttx-configs/px4fmu-v1/src/empty.c           |    4 -
 src/drivers/boards/px4fmu-v1/CMakeLists.txt   |   49 -
 src/drivers/boards/px4fmu-v1/board_config.h   |  279 ----
 src/drivers/boards/px4fmu-v1/px4fmu_can.c     |  129 --
 src/drivers/boards/px4fmu-v1/px4fmu_init.c    |  285 ----
 src/drivers/boards/px4fmu-v1/px4fmu_led.c     |  116 --
 src/drivers/boards/px4fmu-v1/px4fmu_spi.c     |  157 --
 .../boards/px4fmu-v1/px4fmu_timer_config.c    |   99 --
 src/drivers/boards/px4fmu-v1/px4fmu_usb.c     |  108 --
 19 files changed, 3743 deletions(-)
 delete mode 100644 Images/px4fmu-v1.prototype
 delete mode 100644 cmake/configs/nuttx_px4fmu-v1_default.cmake
 delete mode 100644 nuttx-configs/px4fmu-v1/include/board.h
 delete mode 100644 nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h
 delete mode 100644 nuttx-configs/px4fmu-v1/nsh/Make.defs
 delete mode 100644 nuttx-configs/px4fmu-v1/nsh/defconfig
 delete mode 100755 nuttx-configs/px4fmu-v1/nsh/setenv.sh
 delete mode 100644 nuttx-configs/px4fmu-v1/scripts/ld.script
 delete mode 100644 nuttx-configs/px4fmu-v1/src/Makefile
 delete mode 100644 nuttx-configs/px4fmu-v1/src/empty.c
 delete mode 100644 src/drivers/boards/px4fmu-v1/CMakeLists.txt
 delete mode 100644 src/drivers/boards/px4fmu-v1/board_config.h
 delete mode 100644 src/drivers/boards/px4fmu-v1/px4fmu_can.c
 delete mode 100644 src/drivers/boards/px4fmu-v1/px4fmu_init.c
 delete mode 100644 src/drivers/boards/px4fmu-v1/px4fmu_led.c
 delete mode 100644 src/drivers/boards/px4fmu-v1/px4fmu_spi.c
 delete mode 100644 src/drivers/boards/px4fmu-v1/px4fmu_timer_config.c
 delete mode 100644 src/drivers/boards/px4fmu-v1/px4fmu_usb.c

diff --git a/Images/px4fmu-v1.prototype b/Images/px4fmu-v1.prototype
deleted file mode 100644
index da88f8490f..0000000000
--- a/Images/px4fmu-v1.prototype
+++ /dev/null
@@ -1,12 +0,0 @@
-{
-    "board_id": 5, 
-    "magic": "PX4FWv1", 
-    "description": "Firmware for the PX4FMU board", 
-    "image": "", 
-    "build_time": 0, 
-    "summary": "PX4FMU",
-    "version": "0.1",
-    "image_size": 0,
-    "git_identity": "",
-    "board_revision": 0
-}
diff --git a/Makefile b/Makefile
index b063130c01..67bd9697b4 100644
--- a/Makefile
+++ b/Makefile
@@ -189,7 +189,6 @@ qgc_firmware: px4fmu_firmware misc_qgc_extra_firmware sizes
 
 # px4fmu NuttX firmware
 px4fmu_firmware: \
-	check_px4fmu-v1_default \
 	check_px4fmu-v2_default \
 	check_px4fmu-v3_default \
 	check_px4fmu-v4_default \
diff --git a/cmake/configs/nuttx_px4fmu-v1_default.cmake b/cmake/configs/nuttx_px4fmu-v1_default.cmake
deleted file mode 100644
index 7a27e1da70..0000000000
--- a/cmake/configs/nuttx_px4fmu-v1_default.cmake
+++ /dev/null
@@ -1,189 +0,0 @@
-include(nuttx/px4_impl_nuttx)
-
-px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)
-
-set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
-
-set(config_module_list
-	#
-	# Board support modules
-	#
-	drivers/device
-	drivers/stm32
-	drivers/stm32/adc
-	drivers/stm32/tone_alarm
-	drivers/led
-	drivers/px4fmu
-	drivers/px4io
-	drivers/boards/px4fmu-v1
-	drivers/ardrone_interface
-	drivers/rgbled
-	drivers/mpu6000
-	drivers/lsm303d
-	drivers/l3gd20
-	drivers/hmc5883
-	drivers/ms5611
-	drivers/mb12xx
-	drivers/sf0x
-	#drivers/ll40ls
-	drivers/trone
-	drivers/gps
-	#drivers/pwm_out_sim
-	#drivers/hott
-	#drivers/hott/hott_telemetry
-	#drivers/hott/hott_sensors
-	drivers/blinkm
-	drivers/airspeed
-	drivers/ets_airspeed
-	drivers/ms4525_airspeed
-	drivers/ms5525_airspeed
-	drivers/sdp3x_airspeed
-	drivers/frsky_telemetry
-	modules/sensors
-	drivers/vmount
-	drivers/camera_trigger
-	drivers/mkblctrl
-	drivers/px4flow
-
-	#
-	# System commands
-	#
-	systemcmds/bl_update
-	systemcmds/mixer
-	systemcmds/param
-	systemcmds/perf
-	systemcmds/pwm
-	systemcmds/esc_calib
-	systemcmds/reboot
-	systemcmds/top
-	systemcmds/config
-	systemcmds/nshterm
-	systemcmds/mtd
-	systemcmds/dumpfile
-	systemcmds/ver
-
-	#
-	# General system control
-	#
-	modules/commander
-	modules/events
-	modules/load_mon
-	modules/navigator
-	modules/mavlink
-	modules/gpio_led
-	modules/land_detector
-
-	#
-	# Estimation modules
-	#
-	modules/attitude_estimator_q
-	#modules/position_estimator_inav
-	modules/local_position_estimator
-	modules/ekf2
-
-	#
-	# Vehicle Control
-	#
-	# modules/segway # XXX Needs GCC 4.7 fix
-	modules/fw_pos_control_l1
-	modules/fw_att_control
-	modules/mc_att_control
-	modules/mc_pos_control
-	modules/vtol_att_control
-
-	#
-	# Logging
-	#
-	#modules/sdlog2
-	modules/logger
-
-	#
-	# Library modules
-	#
-	modules/systemlib/param
-	modules/systemlib
-	modules/systemlib/mixer
-	modules/uORB
-	modules/dataman
-
-	#
-	# Libraries
-	#
-	lib/controllib
-	lib/mathlib
-	lib/mathlib/math/filter
-	lib/ecl
-	lib/external_lgpl
-	lib/geo
-	lib/geo_lookup
-	lib/conversion
-	lib/launchdetection
-	lib/led
-	lib/terrain_estimation
-	lib/runway_takeoff
-	lib/tailsitter_recovery
-	lib/version
-	lib/DriverFramework/framework
-	platforms/nuttx
-	lib/micro-CDR
-
-	# had to add for cmake, not sure why wasn't in original config
-	platforms/common
-	platforms/nuttx/px4_layer
-
-	#
-	# OBC challenge
-	#
-	# modules/bottle_drop
-
-	#
-	# Rover apps
-	#
-	# examples/rover_steering_control
-
-	#
-	# Demo apps
-	#
-	#examples/math_demo
-	# Tutorial code from
-	# https://px4.io/dev/px4_simple_app
-	#examples/px4_simple_app
-
-	# Tutorial code from
-	# https://px4.io/dev/daemon
-	#examples/px4_daemon_app
-
-	# Tutorial code from
-	# https://px4.io/dev/debug_values
-	#examples/px4_mavlink_debug
-
-	# Tutorial code from
-	# https://px4.io/dev/example_fixedwing_control
-	#examples/fixedwing_control
-
-	# Hardware test
-	#examples/hwtest
-)
-
-set(config_extra_builtin_cmds
-	serdis
-	sercon
-	)
-
-set(config_io_board
-	px4io-v1
-	)
-
-add_custom_target(sercon)
-set_target_properties(sercon PROPERTIES
-	PRIORITY "SCHED_PRIORITY_DEFAULT"
-	MAIN "sercon"
-	STACK_MAIN "2048"
-	COMPILE_FLAGS "-Os")
-
-add_custom_target(serdis)
-set_target_properties(serdis PROPERTIES
-	PRIORITY "SCHED_PRIORITY_DEFAULT"
-	MAIN "serdis"
-	STACK_MAIN "2048"
-	COMPILE_FLAGS "-Os")
diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h
deleted file mode 100644
index 4b10deada9..0000000000
--- a/nuttx-configs/px4fmu-v1/include/board.h
+++ /dev/null
@@ -1,331 +0,0 @@
-/************************************************************************************
- * nuttx-configs/px4fmu-v1/include/board.h
- * include/arch/board/board.h
- *
- *   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.
- *
- ************************************************************************************/
-
-#ifndef __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
-#define __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#ifndef __ASSEMBLY__
-# include <stdint.h>
-#endif
-
-#include "stm32_rcc.h"
-#include "stm32_sdio.h"
-#include "stm32.h"
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/* Clocking *************************************************************************/
-/* The PX4FMU uses a 24MHz crystal connected to the HSE.
- *
- * This is the canonical configuration:
- *   System Clock source           : PLL (HSE)
- *   SYSCLK(Hz)                    : 168000000    Determined by PLL configuration
- *   HCLK(Hz)                      : 168000000    (STM32_RCC_CFGR_HPRE)
- *   AHB Prescaler                 : 1            (STM32_RCC_CFGR_HPRE)
- *   APB1 Prescaler                : 4            (STM32_RCC_CFGR_PPRE1)
- *   APB2 Prescaler                : 2            (STM32_RCC_CFGR_PPRE2)
- *   HSE Frequency(Hz)             : 24000000     (STM32_BOARD_XTAL)
- *   PLLM                          : 24           (STM32_PLLCFG_PLLM)
- *   PLLN                          : 336          (STM32_PLLCFG_PLLN)
- *   PLLP                          : 2            (STM32_PLLCFG_PLLP)
- *   PLLQ                          : 7            (STM32_PLLCFG_PLLQ)
- *   Main regulator output voltage : Scale1 mode  Needed for high speed SYSCLK
- *   Flash Latency(WS)             : 5
- *   Prefetch Buffer               : OFF
- *   Instruction cache             : ON
- *   Data cache                    : ON
- *   Require 48MHz for USB OTG FS, : Enabled
- *   SDIO and RNG clock
- */
-
-/* HSI - 16 MHz RC factory-trimmed
- * LSI - 32 KHz RC
- * HSE - On-board crystal frequency is 24MHz
- * LSE - not installed
- */
-
-#define STM32_BOARD_XTAL        24000000ul
-
-#define STM32_HSI_FREQUENCY     16000000ul
-#define STM32_LSI_FREQUENCY     32000
-#define STM32_HSE_FREQUENCY     STM32_BOARD_XTAL
-//#define STM32_LSE_FREQUENCY     32768
-
-/* Main PLL Configuration.
- *
- * PLL source is HSE
- * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
- *         = (8,000,000 / 8) * 336
- *         = 336,000,000
- * SYSCLK  = PLL_VCO / PLLP
- *         = 336,000,000 / 2 = 168,000,000
- * USB OTG FS, SDIO and RNG Clock
- *         =  PLL_VCO / PLLQ
- *         = 48,000,000
- */
-
-#define STM32_PLLCFG_PLLM       RCC_PLLCFG_PLLM(24)
-#define STM32_PLLCFG_PLLN       RCC_PLLCFG_PLLN(336)
-#define STM32_PLLCFG_PLLP       RCC_PLLCFG_PLLP_2
-#define STM32_PLLCFG_PLLQ       RCC_PLLCFG_PLLQ(7)
-
-#define STM32_SYSCLK_FREQUENCY  168000000ul
-
-/* AHB clock (HCLK) is SYSCLK (168MHz) */
-
-#define STM32_RCC_CFGR_HPRE     RCC_CFGR_HPRE_SYSCLK  /* HCLK  = SYSCLK / 1 */
-#define STM32_HCLK_FREQUENCY    STM32_SYSCLK_FREQUENCY
-#define STM32_BOARD_HCLK        STM32_HCLK_FREQUENCY  /* same as above, to satisfy compiler */
-
-/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
-
-#define STM32_RCC_CFGR_PPRE1    RCC_CFGR_PPRE1_HCLKd4     /* PCLK1 = HCLK / 4 */
-#define STM32_PCLK1_FREQUENCY   (STM32_HCLK_FREQUENCY/4)
-
-/* Timers driven from APB1 will be twice PCLK1 */
-
-#define STM32_APB1_TIM2_CLKIN   (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM3_CLKIN   (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM4_CLKIN   (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM5_CLKIN   (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM6_CLKIN   (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM7_CLKIN   (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM12_CLKIN  (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM13_CLKIN  (2*STM32_PCLK1_FREQUENCY)
-#define STM32_APB1_TIM14_CLKIN  (2*STM32_PCLK1_FREQUENCY)
-
-/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
-
-#define STM32_RCC_CFGR_PPRE2    RCC_CFGR_PPRE2_HCLKd2     /* PCLK2 = HCLK / 2 */
-#define STM32_PCLK2_FREQUENCY   (STM32_HCLK_FREQUENCY/2)
-
-/* Timers driven from APB2 will be twice PCLK2 */
-
-#define STM32_APB2_TIM1_CLKIN   (2*STM32_PCLK2_FREQUENCY)
-#define STM32_APB2_TIM8_CLKIN   (2*STM32_PCLK2_FREQUENCY)
-#define STM32_APB2_TIM9_CLKIN   (2*STM32_PCLK2_FREQUENCY)
-#define STM32_APB2_TIM10_CLKIN  (2*STM32_PCLK2_FREQUENCY)
-#define STM32_APB2_TIM11_CLKIN  (2*STM32_PCLK2_FREQUENCY)
-
-/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
- * otherwise frequency is 2xAPBx.
- * Note: TIM1,8-11 are on APB2, others on APB1
- */
-
-#define BOARD_TIM1_FREQUENCY    STM32_APB2_TIM1_CLKIN
-#define BOARD_TIM2_FREQUENCY    STM32_APB1_TIM2_CLKIN
-#define BOARD_TIM3_FREQUENCY    STM32_APB1_TIM3_CLKIN
-#define BOARD_TIM4_FREQUENCY    STM32_APB1_TIM4_CLKIN
-#define BOARD_TIM5_FREQUENCY    STM32_APB1_TIM5_CLKIN
-#define BOARD_TIM6_FREQUENCY    STM32_APB1_TIM6_CLKIN
-#define BOARD_TIM7_FREQUENCY    STM32_APB1_TIM7_CLKIN
-#define BOARD_TIM8_FREQUENCY    STM32_APB2_TIM8_CLKIN
-#define BOARD_TIM9_FREQUENCY    STM32_APB2_TIM9_CLKIN
-#define BOARD_TIM10_FREQUENCY   STM32_APB2_TIM10_CLKIN
-#define BOARD_TIM11_FREQUENCY   STM32_APB2_TIM11_CLKIN
-#define BOARD_TIM12_FREQUENCY   STM32_APB1_TIM12_CLKIN
-#define BOARD_TIM13_FREQUENCY   STM32_APB1_TIM13_CLKIN
-#define BOARD_TIM14_FREQUENCY   STM32_APB1_TIM14_CLKIN
-
-/* LED definitions ******************************************************************/
-/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
- * way.  The following definitions are used to access individual LEDs.
- */
-
-/* LED index values for use with stm32_setled() */
-
-#define BOARD_LED1        0
-#define BOARD_LED2        1
-#define BOARD_NLEDS       2
-
-#define BOARD_LED_BLUE    BOARD_LED1
-#define BOARD_LED_RED     BOARD_LED2
-
-/* LED bits for use with stm32_setleds() */
-
-#define BOARD_LED1_BIT    (1 << BOARD_LED1)
-#define BOARD_LED2_BIT    (1 << BOARD_LED2)
-
-/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the
- * px4fmu-v1.  The following definitions describe how NuttX controls the LEDs:
- */
-
-#define LED_STARTED       0  /* LED1 */
-#define LED_HEAPALLOCATE  1  /* LED2 */
-#define LED_IRQSENABLED   2  /* LED1 */
-#define LED_STACKCREATED  3  /* LED1 + LED2 */
-#define LED_INIRQ         4  /* LED1 */
-#define LED_SIGNAL        5  /* LED2 */
-#define LED_ASSERTION     6  /* LED1 + LED2 */
-#define LED_PANIC         7  /* LED1 + LED2 */
-
-/* Alternate function pin selections ************************************************/
-
-/*
- * UARTs.
- *
- * Note that UART5 has no optional pinout, so it is not listed here.
- */
-#define GPIO_USART1_RX	GPIO_USART1_RX_2
-#define GPIO_USART1_TX	GPIO_USART1_TX_2
-
-#define GPIO_USART2_RX	GPIO_USART2_RX_1
-#define GPIO_USART2_TX	GPIO_USART2_TX_1
-#define GPIO_USART2_RTS	GPIO_USART2_RTS_1
-#define GPIO_USART2_CTS	GPIO_USART2_CTS_1
-
-#define GPIO_USART6_RX	GPIO_USART6_RX_1
-#define GPIO_USART6_TX	GPIO_USART6_TX_1
-
-/* UART DMA configuration for USART1/6 */
-#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
-#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
-
-/*
- * CAN
- *
- * CAN2 is routed to the expansion connector.
- */
-
-#define GPIO_CAN2_RX	GPIO_CAN2_RX_1
-#define GPIO_CAN2_TX	GPIO_CAN2_TX_1
-
-/*
- * I2C
- *
- * The optional _GPIO configurations allow the I2C driver to manually
- * reset the bus to clear stuck slaves.  They match the pin configuration,
- * but are normally-high GPIOs.
- */
-#define GPIO_I2C1_SCL		GPIO_I2C1_SCL_2
-#define GPIO_I2C1_SDA		GPIO_I2C1_SDA_2
-#define GPIO_I2C1_SCL_GPIO	(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
-#define GPIO_I2C1_SDA_GPIO	(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
-
-#define GPIO_I2C2_SCL		GPIO_I2C2_SCL_1
-#define GPIO_I2C2_SDA		GPIO_I2C2_SDA_1
-#define GPIO_I2C2_SCL_GPIO	(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
-#define GPIO_I2C2_SDA_GPIO	(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
-
-#define GPIO_I2C3_SCL		GPIO_I2C3_SCL_1
-#define GPIO_I2C3_SDA		GPIO_I2C3_SDA_1
-#define GPIO_I2C3_SCL_GPIO	(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8)
-#define GPIO_I2C3_SDA_GPIO	(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9)
-
-/*
- * SPI
- *
- * There are sensors on SPI1, and SPI3 is connected to the microSD slot.
- */
-#define GPIO_SPI1_MISO	(GPIO_SPI1_MISO_1|GPIO_SPEED_50MHz)
-#define GPIO_SPI1_MOSI	(GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
-#define GPIO_SPI1_SCK	(GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
-
-#define GPIO_SPI3_MISO	(GPIO_SPI3_MISO_2|GPIO_SPEED_50MHz)
-#define GPIO_SPI3_MOSI	(GPIO_SPI3_MOSI_1|GPIO_SPEED_50MHz)
-#define GPIO_SPI3_SCK	(GPIO_SPI3_SCK_2|GPIO_SPEED_50MHz)
-#define GPIO_SPI3_NSS	(GPIO_SPI3_NSS_2|GPIO_SPEED_50MHz)
-
-/* SPI DMA configuration for SPI3 (microSD) */
-#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1
-#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_2
-/* XXX since we allocate the HP work stack from CCM RAM on normal system startup,
-   SPI1 will never run in DMA mode - so we can just give it a random config here.
-   What we really need to do is to make DMA configurable per channel, and always
-   disable it for SPI1. */
-#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
-#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2
-
-/************************************************************************************
- * 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);
-
-/************************************************************************************
- * Name:  stm32_ledinit, stm32_setled, and stm32_setleds
- *
- * Description:
- *   If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs.  If
- *   CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
- *   control the LEDs from user applications.
- *
- ************************************************************************************/
-
-#ifndef CONFIG_ARCH_LEDS
-EXTERN void stm32_ledinit(void);
-EXTERN void stm32_setled(int led, bool ledon);
-EXTERN void stm32_setleds(uint8_t ledset);
-#endif
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __ASSEMBLY__ */
-#endif  /* __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H */
diff --git a/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h b/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h
deleted file mode 100644
index 15e4e7a8d5..0000000000
--- a/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h
+++ /dev/null
@@ -1,42 +0,0 @@
-/****************************************************************************
- *
- *   Copyright (C) 2013 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- *    notice, this list of conditions and the following disclaimer in
- *    the documentation and/or other materials provided with the
- *    distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- *    used to endorse or promote products derived from this software
- *    without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * nsh_romfsetc.h
- *
- * This file is a stub for 'make export' purposes; the actual ROMFS
- * must be supplied by the library client.
- */
-
-extern unsigned char romfs_img[];
-extern unsigned int romfs_img_len;
diff --git a/nuttx-configs/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs
deleted file mode 100644
index 2f777425c3..0000000000
--- a/nuttx-configs/px4fmu-v1/nsh/Make.defs
+++ /dev/null
@@ -1,164 +0,0 @@
-############################################################################
-# nuttx-configs/px4fmu-v1/nsh/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.
-#
-############################################################################
-
-include ${TOPDIR}/.config
-include ${TOPDIR}/tools/Config.mk
-include $(TOPDIR)/PX4_Warnings.mk
-include $(TOPDIR)/PX4_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${HOST_OS_FIRST_LETTER}
-
-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		 = -Os
-ARCHCPUFLAGS		 = -mcpu=cortex-m4 \
-			   -mthumb \
-			   -march=armv7e-m \
-			   -mfpu=fpv4-sp-d16 \
-			   -mfloat-abi=hard
-
-# Enable precise stack overflow tracking
-
-ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
-INSTRUMENTATIONDEFINES	 = -finstrument-functions -ffixed-r10
-endif
-
-# Pull in *just* libm from the toolchain ... this is grody
-LIBM			 = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
-EXTRA_LIBS		+= $(LIBM)
-
-# 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)/scripts/$(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)/scripts/$(LDSCRIPT)
-  else
-    # Linux/Cygwin-native toolchain
-    MKDEP		 = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
-    ARCHINCLUDES	 = -I. -isystem $(TOPDIR)/include
-    ARCHXXINCLUDES	 = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
-    ARCHSCRIPT		 = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(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}
-
-# Optimization 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		 = $(PX4_ARCHWARNINGS)
-ARCHCWARNINGS		 = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
-ARCHWARNINGSXX		 = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
-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/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
deleted file mode 100644
index c5baecda53..0000000000
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ /dev/null
@@ -1,1467 +0,0 @@
-#
-# Automatically generated file; DO NOT EDIT.
-# Nuttx/ Configuration
-#
-
-#
-# Build Setup
-#
-# CONFIG_EXPERIMENTAL is not set
-# CONFIG_DEFAULT_SMALL is not set
-CONFIG_HOST_LINUX=y
-# CONFIG_HOST_OSX is not set
-# CONFIG_HOST_WINDOWS is not set
-# CONFIG_HOST_OTHER is not set
-
-#
-# Build Configuration
-#
-CONFIG_APPS_DIR="../apps"
-CONFIG_BUILD_FLAT=y
-# CONFIG_BUILD_2PASS is not set
-
-#
-# Binary Output Formats
-#
-# CONFIG_RRLOAD_BINARY is not set
-# CONFIG_INTELHEX_BINARY is not set
-# CONFIG_MOTOROLA_SREC is not set
-CONFIG_RAW_BINARY=y
-# CONFIG_UBOOT_UIMAGE is not set
-
-#
-# Customize Header Files
-#
-# CONFIG_ARCH_STDINT_H is not set
-# CONFIG_ARCH_STDBOOL_H is not set
-CONFIG_ARCH_MATH_H=y
-# CONFIG_ARCH_FLOAT_H is not set
-# CONFIG_ARCH_STDARG_H is not set
-# CONFIG_ARCH_DEBUG_H is not set
-
-#
-# Debug Options
-#
-CONFIG_DEBUG_ALERT=y
-# CONFIG_DEBUG_FEATURES is not set
-CONFIG_ARCH_HAVE_STACKCHECK=y
-CONFIG_STACK_COLORATION=y
-CONFIG_ARCH_HAVE_HEAPCHECK=y
-# CONFIG_HEAP_COLORATION is not set
-CONFIG_DEBUG_SYMBOLS=y
-CONFIG_ARCH_HAVE_CUSTOMOPT=y
-# CONFIG_DEBUG_NOOPT is not set
-# CONFIG_DEBUG_CUSTOMOPT is not set
-CONFIG_DEBUG_FULLOPT=y
-
-#
-# System Type
-#
-CONFIG_ARCH_ARM=y
-# CONFIG_ARCH_AVR is not set
-# CONFIG_ARCH_HC is not set
-# CONFIG_ARCH_MIPS is not set
-# CONFIG_ARCH_RGMP is not set
-# CONFIG_ARCH_SH is not set
-# CONFIG_ARCH_SIM is not set
-# CONFIG_ARCH_X86 is not set
-# CONFIG_ARCH_Z16 is not set
-# CONFIG_ARCH_Z80 is not set
-CONFIG_ARCH="arm"
-
-#
-# ARM Options
-#
-# CONFIG_ARCH_CHIP_A1X is not set
-# CONFIG_ARCH_CHIP_C5471 is not set
-# CONFIG_ARCH_CHIP_CALYPSO is not set
-# CONFIG_ARCH_CHIP_DM320 is not set
-# CONFIG_ARCH_CHIP_EFM32 is not set
-# CONFIG_ARCH_CHIP_IMX1 is not set
-# CONFIG_ARCH_CHIP_IMX6 is not set
-# CONFIG_ARCH_CHIP_KINETIS is not set
-# CONFIG_ARCH_CHIP_KL is not set
-# CONFIG_ARCH_CHIP_LM is not set
-# CONFIG_ARCH_CHIP_TIVA is not set
-# CONFIG_ARCH_CHIP_LPC11XX is not set
-# CONFIG_ARCH_CHIP_LPC17XX is not set
-# CONFIG_ARCH_CHIP_LPC214X is not set
-# CONFIG_ARCH_CHIP_LPC2378 is not set
-# CONFIG_ARCH_CHIP_LPC31XX is not set
-# CONFIG_ARCH_CHIP_LPC43XX is not set
-# CONFIG_ARCH_CHIP_NUC1XX is not set
-# CONFIG_ARCH_CHIP_SAMA5 is not set
-# CONFIG_ARCH_CHIP_SAMD is not set
-# CONFIG_ARCH_CHIP_SAML is not set
-# CONFIG_ARCH_CHIP_SAM34 is not set
-# CONFIG_ARCH_CHIP_SAMV7 is not set
-CONFIG_ARCH_CHIP_STM32=y
-# CONFIG_ARCH_CHIP_STM32F7 is not set
-# CONFIG_ARCH_CHIP_STM32L4 is not set
-# CONFIG_ARCH_CHIP_STR71X is not set
-# CONFIG_ARCH_CHIP_TMS570 is not set
-# CONFIG_ARCH_CHIP_MOXART is not set
-# CONFIG_ARCH_ARM7TDMI is not set
-# CONFIG_ARCH_ARM926EJS is not set
-# CONFIG_ARCH_ARM920T is not set
-# CONFIG_ARCH_CORTEXM0 is not set
-# CONFIG_ARCH_CORTEXM3 is not set
-CONFIG_ARCH_CORTEXM4=y
-# CONFIG_ARCH_CORTEXM7 is not set
-# CONFIG_ARCH_CORTEXA5 is not set
-# CONFIG_ARCH_CORTEXA8 is not set
-# CONFIG_ARCH_CORTEXA9 is not set
-# CONFIG_ARCH_CORTEXR4 is not set
-# CONFIG_ARCH_CORTEXR4F is not set
-# CONFIG_ARCH_CORTEXR5 is not set
-# CONFIG_ARCH_CORTEX5F is not set
-# CONFIG_ARCH_CORTEXR7 is not set
-# CONFIG_ARCH_CORTEXR7F is not set
-CONFIG_ARCH_FAMILY="armv7-m"
-CONFIG_ARCH_CHIP="stm32"
-# CONFIG_ARM_TOOLCHAIN_IAR is not set
-CONFIG_ARM_TOOLCHAIN_GNU=y
-CONFIG_ARMV7M_USEBASEPRI=y
-CONFIG_ARCH_HAVE_CMNVECTOR=y
-CONFIG_ARMV7M_CMNVECTOR=y
-# CONFIG_ARMV7M_LAZYFPU is not set
-CONFIG_ARCH_HAVE_FPU=y
-# CONFIG_ARCH_HAVE_DPFPU is not set
-CONFIG_ARCH_FPU=y
-# CONFIG_ARCH_HAVE_TRUSTZONE is not set
-CONFIG_ARM_HAVE_MPU_UNIFIED=y
-# CONFIG_ARM_MPU is not set
-
-#
-# ARMV7M Configuration Options
-#
-# CONFIG_ARMV7M_HAVE_ICACHE is not set
-# CONFIG_ARMV7M_HAVE_DCACHE is not set
-# CONFIG_ARMV7M_HAVE_ITCM is not set
-# CONFIG_ARMV7M_HAVE_DTCM is not set
-# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set
-# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
-# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
-# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set
-CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y
-CONFIG_ARMV7M_HAVE_STACKCHECK=y
-# CONFIG_ARMV7M_STACKCHECK is not set
-# CONFIG_ARMV7M_ITMSYSLOG is not set
-CONFIG_SERIAL_TERMIOS=y
-
-#
-# STM32 Configuration Options
-#
-# CONFIG_ARCH_CHIP_STM32L151C6 is not set
-# CONFIG_ARCH_CHIP_STM32L151C8 is not set
-# CONFIG_ARCH_CHIP_STM32L151CB is not set
-# CONFIG_ARCH_CHIP_STM32L151R6 is not set
-# CONFIG_ARCH_CHIP_STM32L151R8 is not set
-# CONFIG_ARCH_CHIP_STM32L151RB is not set
-# CONFIG_ARCH_CHIP_STM32L151V6 is not set
-# CONFIG_ARCH_CHIP_STM32L151V8 is not set
-# CONFIG_ARCH_CHIP_STM32L151VB is not set
-# CONFIG_ARCH_CHIP_STM32L152C6 is not set
-# CONFIG_ARCH_CHIP_STM32L152C8 is not set
-# CONFIG_ARCH_CHIP_STM32L152CB is not set
-# CONFIG_ARCH_CHIP_STM32L152R6 is not set
-# CONFIG_ARCH_CHIP_STM32L152R8 is not set
-# CONFIG_ARCH_CHIP_STM32L152RB is not set
-# CONFIG_ARCH_CHIP_STM32L152V6 is not set
-# CONFIG_ARCH_CHIP_STM32L152V8 is not set
-# CONFIG_ARCH_CHIP_STM32L152VB is not set
-# CONFIG_ARCH_CHIP_STM32L162ZD is not set
-# CONFIG_ARCH_CHIP_STM32L162VE is not set
-# CONFIG_ARCH_CHIP_STM32F100C8 is not set
-# CONFIG_ARCH_CHIP_STM32F100CB is not set
-# CONFIG_ARCH_CHIP_STM32F100R8 is not set
-# CONFIG_ARCH_CHIP_STM32F100RB is not set
-# CONFIG_ARCH_CHIP_STM32F100RC is not set
-# CONFIG_ARCH_CHIP_STM32F100RD is not set
-# CONFIG_ARCH_CHIP_STM32F100RE is not set
-# CONFIG_ARCH_CHIP_STM32F100V8 is not set
-# CONFIG_ARCH_CHIP_STM32F100VB is not set
-# CONFIG_ARCH_CHIP_STM32F100VC is not set
-# CONFIG_ARCH_CHIP_STM32F100VD is not set
-# CONFIG_ARCH_CHIP_STM32F100VE is not set
-# CONFIG_ARCH_CHIP_STM32F102CB is not set
-# CONFIG_ARCH_CHIP_STM32F103T8 is not set
-# CONFIG_ARCH_CHIP_STM32F103TB is not set
-# CONFIG_ARCH_CHIP_STM32F103C4 is not set
-# CONFIG_ARCH_CHIP_STM32F103C8 is not set
-# CONFIG_ARCH_CHIP_STM32F103CB is not set
-# CONFIG_ARCH_CHIP_STM32F103R8 is not set
-# CONFIG_ARCH_CHIP_STM32F103RB is not set
-# CONFIG_ARCH_CHIP_STM32F103RC is not set
-# CONFIG_ARCH_CHIP_STM32F103RD is not set
-# CONFIG_ARCH_CHIP_STM32F103RE is not set
-# CONFIG_ARCH_CHIP_STM32F103RG is not set
-# CONFIG_ARCH_CHIP_STM32F103V8 is not set
-# CONFIG_ARCH_CHIP_STM32F103VB is not set
-# CONFIG_ARCH_CHIP_STM32F103VC is not set
-# CONFIG_ARCH_CHIP_STM32F103VE is not set
-# CONFIG_ARCH_CHIP_STM32F103ZE is not set
-# CONFIG_ARCH_CHIP_STM32F105VB is not set
-# CONFIG_ARCH_CHIP_STM32F105RB is not set
-# CONFIG_ARCH_CHIP_STM32F107VC is not set
-# CONFIG_ARCH_CHIP_STM32F205RG is not set
-# CONFIG_ARCH_CHIP_STM32F207IG is not set
-# CONFIG_ARCH_CHIP_STM32F207ZE is not set
-# CONFIG_ARCH_CHIP_STM32F302K6 is not set
-# CONFIG_ARCH_CHIP_STM32F302K8 is not set
-# CONFIG_ARCH_CHIP_STM32F302CB is not set
-# CONFIG_ARCH_CHIP_STM32F302CC is not set
-# CONFIG_ARCH_CHIP_STM32F302RB is not set
-# CONFIG_ARCH_CHIP_STM32F302RC is not set
-# CONFIG_ARCH_CHIP_STM32F302VB is not set
-# CONFIG_ARCH_CHIP_STM32F302VC is not set
-# CONFIG_ARCH_CHIP_STM32F303K6 is not set
-# CONFIG_ARCH_CHIP_STM32F303K8 is not set
-# CONFIG_ARCH_CHIP_STM32F303C6 is not set
-# CONFIG_ARCH_CHIP_STM32F303C8 is not set
-# CONFIG_ARCH_CHIP_STM32F303CB is not set
-# CONFIG_ARCH_CHIP_STM32F303CC is not set
-# CONFIG_ARCH_CHIP_STM32F303RB is not set
-# CONFIG_ARCH_CHIP_STM32F303RC is not set
-# CONFIG_ARCH_CHIP_STM32F303RD is not set
-# CONFIG_ARCH_CHIP_STM32F303RE is not set
-# CONFIG_ARCH_CHIP_STM32F303VB is not set
-# CONFIG_ARCH_CHIP_STM32F303VC is not set
-# CONFIG_ARCH_CHIP_STM32F372C8 is not set
-# CONFIG_ARCH_CHIP_STM32F372R8 is not set
-# CONFIG_ARCH_CHIP_STM32F372V8 is not set
-# CONFIG_ARCH_CHIP_STM32F372CB is not set
-# CONFIG_ARCH_CHIP_STM32F372RB is not set
-# CONFIG_ARCH_CHIP_STM32F372VB is not set
-# CONFIG_ARCH_CHIP_STM32F372CC is not set
-# CONFIG_ARCH_CHIP_STM32F372RC is not set
-# CONFIG_ARCH_CHIP_STM32F372VC is not set
-# CONFIG_ARCH_CHIP_STM32F373C8 is not set
-# CONFIG_ARCH_CHIP_STM32F373R8 is not set
-# CONFIG_ARCH_CHIP_STM32F373V8 is not set
-# CONFIG_ARCH_CHIP_STM32F373CB is not set
-# CONFIG_ARCH_CHIP_STM32F373RB is not set
-# CONFIG_ARCH_CHIP_STM32F373VB is not set
-# CONFIG_ARCH_CHIP_STM32F373CC is not set
-# CONFIG_ARCH_CHIP_STM32F373RC is not set
-# CONFIG_ARCH_CHIP_STM32F373VC is not set
-# CONFIG_ARCH_CHIP_STM32F401RE is not set
-# CONFIG_ARCH_CHIP_STM32F411RE is not set
-# CONFIG_ARCH_CHIP_STM32F411VE is not set
-CONFIG_ARCH_CHIP_STM32F405RG=y
-# CONFIG_ARCH_CHIP_STM32F405VG is not set
-# CONFIG_ARCH_CHIP_STM32F405ZG is not set
-# CONFIG_ARCH_CHIP_STM32F407VE is not set
-# CONFIG_ARCH_CHIP_STM32F407VG is not set
-# CONFIG_ARCH_CHIP_STM32F407ZE is not set
-# CONFIG_ARCH_CHIP_STM32F407ZG is not set
-# CONFIG_ARCH_CHIP_STM32F407IE is not set
-# CONFIG_ARCH_CHIP_STM32F407IG is not set
-# CONFIG_ARCH_CHIP_STM32F427V is not set
-# CONFIG_ARCH_CHIP_STM32F427Z is not set
-# CONFIG_ARCH_CHIP_STM32F427I is not set
-# CONFIG_ARCH_CHIP_STM32F429V is not set
-# CONFIG_ARCH_CHIP_STM32F429Z is not set
-# CONFIG_ARCH_CHIP_STM32F429I is not set
-# CONFIG_ARCH_CHIP_STM32F429B is not set
-# CONFIG_ARCH_CHIP_STM32F429N is not set
-# CONFIG_ARCH_CHIP_STM32F446M is not set
-# CONFIG_ARCH_CHIP_STM32F446R is not set
-# CONFIG_ARCH_CHIP_STM32F446V is not set
-# CONFIG_ARCH_CHIP_STM32F446Z is not set
-# CONFIG_ARCH_CHIP_STM32F469A is not set
-# CONFIG_ARCH_CHIP_STM32F469I is not set
-# CONFIG_ARCH_CHIP_STM32F469B is not set
-# CONFIG_ARCH_CHIP_STM32F469N is not set
-# CONFIG_STM32_FLASH_CONFIG_DEFAULT is not set
-# CONFIG_STM32_FLASH_CONFIG_4 is not set
-# CONFIG_STM32_FLASH_CONFIG_6 is not set
-# CONFIG_STM32_FLASH_CONFIG_8 is not set
-# CONFIG_STM32_FLASH_CONFIG_B is not set
-# CONFIG_STM32_FLASH_CONFIG_C is not set
-# CONFIG_STM32_FLASH_CONFIG_D is not set
-# CONFIG_STM32_FLASH_CONFIG_E is not set
-# CONFIG_STM32_FLASH_CONFIG_F is not set
-CONFIG_STM32_FLASH_CONFIG_G=y
-# CONFIG_STM32_FLASH_CONFIG_I is not set
-# CONFIG_STM32_STM32L15XX is not set
-# CONFIG_STM32_ENERGYLITE is not set
-# CONFIG_STM32_STM32F10XX is not set
-# CONFIG_STM32_VALUELINE is not set
-# CONFIG_STM32_CONNECTIVITYLINE is not set
-# CONFIG_STM32_PERFORMANCELINE is not set
-# CONFIG_STM32_USBACCESSLINE is not set
-# CONFIG_STM32_HIGHDENSITY is not set
-# CONFIG_STM32_MEDIUMDENSITY is not set
-# CONFIG_STM32_LOWDENSITY is not set
-# CONFIG_STM32_STM32F20XX is not set
-# CONFIG_STM32_STM32F205 is not set
-# CONFIG_STM32_STM32F207 is not set
-# CONFIG_STM32_STM32F30XX is not set
-# CONFIG_STM32_STM32F302 is not set
-# CONFIG_STM32_STM32F303 is not set
-# CONFIG_STM32_STM32F37XX is not set
-CONFIG_STM32_STM32F40XX=y
-# CONFIG_STM32_STM32F401 is not set
-# CONFIG_STM32_STM32F411 is not set
-CONFIG_STM32_STM32F405=y
-# CONFIG_STM32_STM32F407 is not set
-# CONFIG_STM32_STM32F427 is not set
-# CONFIG_STM32_STM32F429 is not set
-# CONFIG_STM32_STM32F446 is not set
-# CONFIG_STM32_STM32F469 is not set
-# CONFIG_STM32_DFU is not set
-
-#
-# STM32 Peripheral Support
-#
-CONFIG_STM32_HAVE_CCM=y
-# CONFIG_STM32_HAVE_USBDEV is not set
-CONFIG_STM32_HAVE_OTGFS=y
-CONFIG_STM32_HAVE_FSMC=y
-# CONFIG_STM32_HAVE_LTDC is not set
-CONFIG_STM32_HAVE_USART3=y
-CONFIG_STM32_HAVE_UART4=y
-CONFIG_STM32_HAVE_UART5=y
-CONFIG_STM32_HAVE_USART6=y
-# CONFIG_STM32_HAVE_UART7 is not set
-# CONFIG_STM32_HAVE_UART8 is not set
-CONFIG_STM32_HAVE_TIM1=y
-# CONFIG_STM32_HAVE_TIM2 is not set
-CONFIG_STM32_HAVE_TIM3=y
-CONFIG_STM32_HAVE_TIM4=y
-CONFIG_STM32_HAVE_TIM5=y
-CONFIG_STM32_HAVE_TIM6=y
-CONFIG_STM32_HAVE_TIM7=y
-CONFIG_STM32_HAVE_TIM8=y
-CONFIG_STM32_HAVE_TIM9=y
-CONFIG_STM32_HAVE_TIM10=y
-CONFIG_STM32_HAVE_TIM11=y
-CONFIG_STM32_HAVE_TIM12=y
-CONFIG_STM32_HAVE_TIM13=y
-CONFIG_STM32_HAVE_TIM14=y
-# CONFIG_STM32_HAVE_TIM15 is not set
-# CONFIG_STM32_HAVE_TIM16 is not set
-# CONFIG_STM32_HAVE_TIM17 is not set
-CONFIG_STM32_HAVE_ADC2=y
-CONFIG_STM32_HAVE_ADC3=y
-# CONFIG_STM32_HAVE_ADC4 is not set
-CONFIG_STM32_HAVE_ADC1_DMA=y
-# CONFIG_STM32_HAVE_ADC2_DMA is not set
-# CONFIG_STM32_HAVE_ADC3_DMA is not set
-# CONFIG_STM32_HAVE_ADC4_DMA is not set
-CONFIG_STM32_HAVE_CAN1=y
-CONFIG_STM32_HAVE_CAN2=y
-CONFIG_STM32_HAVE_DAC1=y
-CONFIG_STM32_HAVE_DAC2=y
-CONFIG_STM32_HAVE_RNG=y
-# CONFIG_STM32_HAVE_ETHMAC is not set
-CONFIG_STM32_HAVE_I2C2=y
-CONFIG_STM32_HAVE_I2C3=y
-CONFIG_STM32_HAVE_SPI2=y
-CONFIG_STM32_HAVE_SPI3=y
-# CONFIG_STM32_HAVE_SPI4 is not set
-# CONFIG_STM32_HAVE_SPI5 is not set
-# CONFIG_STM32_HAVE_SPI6 is not set
-# CONFIG_STM32_HAVE_SAIPLL is not set
-# CONFIG_STM32_HAVE_I2SPLL is not set
-CONFIG_STM32_ADC1=y
-# CONFIG_STM32_ADC2 is not set
-# CONFIG_STM32_ADC3 is not set
-CONFIG_STM32_BKPSRAM=y
-# CONFIG_STM32_CAN1 is not set
-# CONFIG_STM32_CAN2 is not set
-CONFIG_STM32_CCMDATARAM=y
-# CONFIG_STM32_CRC is not set
-# CONFIG_STM32_CRYP is not set
-CONFIG_STM32_DMA1=y
-CONFIG_STM32_DMA2=y
-# CONFIG_STM32_DAC1 is not set
-# CONFIG_STM32_DAC2 is not set
-# CONFIG_STM32_DCMI is not set
-# CONFIG_STM32_FSMC is not set
-# CONFIG_STM32_HASH is not set
-CONFIG_STM32_I2C1=y
-CONFIG_STM32_I2C2=y
-CONFIG_STM32_I2C3=y
-CONFIG_STM32_OTGFS=y
-# CONFIG_STM32_OTGHS is not set
-CONFIG_STM32_PWR=y
-# CONFIG_STM32_RNG is not set
-# CONFIG_STM32_SDIO is not set
-CONFIG_STM32_SPI1=y
-# CONFIG_STM32_SPI2 is not set
-CONFIG_STM32_SPI3=y
-CONFIG_STM32_SYSCFG=y
-# CONFIG_STM32_TIM1 is not set
-# CONFIG_STM32_TIM2 is not set
-# CONFIG_STM32_TIM3 is not set
-CONFIG_STM32_TIM4=y
-CONFIG_STM32_TIM5=y
-CONFIG_STM32_TIM6=y
-CONFIG_STM32_TIM7=y
-# CONFIG_STM32_TIM8 is not set
-CONFIG_STM32_TIM9=y
-CONFIG_STM32_TIM10=y
-CONFIG_STM32_TIM11=y
-CONFIG_STM32_TIM12=y
-CONFIG_STM32_TIM13=y
-CONFIG_STM32_TIM14=y
-CONFIG_STM32_USART1=y
-CONFIG_STM32_USART2=y
-# CONFIG_STM32_USART3 is not set
-# CONFIG_STM32_UART4 is not set
-CONFIG_STM32_UART5=y
-CONFIG_STM32_USART6=y
-# CONFIG_STM32_IWDG is not set
-CONFIG_STM32_WWDG=y
-CONFIG_STM32_ADC=y
-CONFIG_STM32_SPI=y
-CONFIG_STM32_I2C=y
-# CONFIG_STM32_NOEXT_VECTORS is not set
-
-#
-# Alternate Pin Mapping
-#
-CONFIG_STM32_FLASH_PREFETCH=y
-# CONFIG_STM32_JTAG_DISABLE is not set
-CONFIG_STM32_JTAG_FULL_ENABLE=y
-# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
-# CONFIG_STM32_JTAG_SW_ENABLE is not set
-CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
-# CONFIG_STM32_FORCEPOWER is not set
-# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
-# CONFIG_STM32_CCMEXCLUDE is not set
-CONFIG_STM32_DMACAPABLE=y
-
-#
-# Timer Configuration
-#
-# CONFIG_STM32_ONESHOT is not set
-# CONFIG_STM32_FREERUN is not set
-# CONFIG_STM32_TIM4_PWM is not set
-# CONFIG_STM32_TIM5_PWM is not set
-# CONFIG_STM32_TIM9_PWM is not set
-# CONFIG_STM32_TIM10_PWM is not set
-# CONFIG_STM32_TIM11_PWM is not set
-# CONFIG_STM32_TIM12_PWM is not set
-# CONFIG_STM32_TIM13_PWM is not set
-# CONFIG_STM32_TIM14_PWM is not set
-# CONFIG_STM32_TIM4_ADC is not set
-# CONFIG_STM32_TIM5_ADC is not set
-# CONFIG_STM32_TIM1_CAP is not set
-# CONFIG_STM32_TIM3_CAP is not set
-# CONFIG_STM32_TIM4_CAP is not set
-# CONFIG_STM32_TIM5_CAP is not set
-# CONFIG_STM32_TIM8_CAP is not set
-# CONFIG_STM32_TIM9_CAP is not set
-# CONFIG_STM32_TIM10_CAP is not set
-# CONFIG_STM32_TIM11_CAP is not set
-# CONFIG_STM32_TIM12_CAP is not set
-# CONFIG_STM32_TIM13_CAP is not set
-# CONFIG_STM32_TIM14_CAP is not set
-
-#
-# ADC Configuration
-#
-# CONFIG_STM32_ADC1_DMA is not set
-CONFIG_STM32_USART=y
-CONFIG_STM32_SERIALDRIVER=y
-
-#
-# U[S]ART Configuration
-#
-
-#
-# U[S]ART Device Configuration
-#
-CONFIG_STM32_USART1_SERIALDRIVER=y
-# CONFIG_STM32_USART1_1WIREDRIVER is not set
-# CONFIG_USART1_RS485 is not set
-# CONFIG_USART1_RXDMA is not set
-CONFIG_STM32_USART2_SERIALDRIVER=y
-# CONFIG_STM32_USART2_1WIREDRIVER is not set
-# CONFIG_USART2_RS485 is not set
-CONFIG_USART2_RXDMA=y
-CONFIG_STM32_UART5_SERIALDRIVER=y
-# CONFIG_STM32_UART5_1WIREDRIVER is not set
-# CONFIG_UART5_RS485 is not set
-CONFIG_UART5_RXDMA=y
-CONFIG_STM32_USART6_SERIALDRIVER=y
-# CONFIG_STM32_USART6_1WIREDRIVER is not set
-# CONFIG_USART6_RS485 is not set
-CONFIG_USART6_RXDMA=y
-
-#
-# Serial Driver Configuration
-#
-CONFIG_SERIAL_DISABLE_REORDERING=y
-CONFIG_STM32_FLOWCONTROL_BROKEN=y
-CONFIG_STM32_USART_BREAKS=y
-CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
-CONFIG_STM32_USART_SINGLEWIRE=y
-
-#
-# SPI Configuration
-#
-# CONFIG_STM32_SPI_INTERRUPTS is not set
-# CONFIG_STM32_SPI_DMA is not set
-
-#
-# I2C Configuration
-#
-# CONFIG_STM32_I2C_ALT is not set
-# CONFIG_STM32_I2C_DYNTIMEO is not set
-CONFIG_STM32_I2CTIMEOSEC=0
-CONFIG_STM32_I2CTIMEOMS=10
-CONFIG_STM32_I2CTIMEOTICKS=10
-# CONFIG_STM32_I2C_DUTY16_9 is not set
-# CONFIG_STM32_BBSRAM is not set
-CONFIG_STM32_BBSRAM_FILES=5
-# CONFIG_STM32_SAVE_CRASHDUMP is not set
-# CONFIG_STM32_HAVE_RTC_COUNTER is not set
-# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
-
-#
-# USB FS Host Configuration
-#
-
-#
-# USB HS Host Configuration
-#
-
-#
-# USB Host Debug Configuration
-#
-
-#
-# USB Device Configuration
-#
-
-#
-# Architecture Options
-#
-# CONFIG_ARCH_NOINTC is not set
-# CONFIG_ARCH_VECNOTIRQ is not set
-CONFIG_ARCH_DMA=y
-CONFIG_ARCH_HAVE_IRQPRIO=y
-# CONFIG_ARCH_L2CACHE is not set
-# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set
-# CONFIG_ARCH_HAVE_ADDRENV is not set
-# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set
-# CONFIG_ARCH_HAVE_MULTICPU is not set
-CONFIG_ARCH_HAVE_VFORK=y
-# CONFIG_ARCH_HAVE_MMU is not set
-CONFIG_ARCH_HAVE_MPU=y
-# CONFIG_ARCH_NAND_HWECC is not set
-# CONFIG_ARCH_HAVE_EXTCLK is not set
-# CONFIG_ARCH_HAVE_POWEROFF is not set
-CONFIG_ARCH_HAVE_RESET=y
-# CONFIG_ARCH_USE_MPU is not set
-# CONFIG_ARCH_IRQPRIO is not set
-CONFIG_ARCH_STACKDUMP=y
-# CONFIG_ENDIAN_BIG is not set
-# CONFIG_ARCH_IDLE_CUSTOM is not set
-# CONFIG_ARCH_HAVE_RAMFUNCS is not set
-CONFIG_ARCH_HAVE_RAMVECTORS=y
-# CONFIG_ARCH_RAMVECTORS is not set
-
-#
-# Board Settings
-#
-CONFIG_BOARD_LOOPSPERMSEC=16717
-# CONFIG_ARCH_CALIBRATION is not set
-
-#
-# Interrupt options
-#
-CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
-CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y
-# CONFIG_ARCH_HIPRI_INTERRUPT is not set
-CONFIG_ARCH_INTERRUPTSTACK=750
-
-#
-# Boot options
-#
-# CONFIG_BOOT_RUNFROMEXTSRAM is not set
-CONFIG_BOOT_RUNFROMFLASH=y
-# CONFIG_BOOT_RUNFROMISRAM is not set
-# CONFIG_BOOT_RUNFROMSDRAM is not set
-# CONFIG_BOOT_COPYTORAM is not set
-
-#
-# Boot Memory Configuration
-#
-CONFIG_RAM_START=0x20000000
-CONFIG_RAM_SIZE=196608
-# CONFIG_ARCH_HAVE_SDRAM is not set
-
-#
-# Board Selection
-#
-CONFIG_ARCH_BOARD_PX4FMU_V1=y
-CONFIG_ARCH_BOARD="px4fmu-v1"
-
-#
-# Custom Board Configuration
-#
-# CONFIG_BOARD_CUSTOM_LEDS is not set
-# CONFIG_BOARD_CUSTOM_BUTTONS is not set
-
-#
-# Common Board Options
-#
-
-#
-# Board-Specific Options
-#
-# CONFIG_BOARD_CRASHDUMP is not set
-CONFIG_LIB_BOARDCTL=y
-CONFIG_BOARDCTL_RESET=y
-# CONFIG_BOARDCTL_UNIQUEID is not set
-CONFIG_BOARDCTL_USBDEVCTRL=y
-# CONFIG_BOARDCTL_TSCTEST is not set
-# CONFIG_BOARDCTL_ADCTEST is not set
-# CONFIG_BOARDCTL_PWMTEST is not set
-# CONFIG_BOARDCTL_GRAPHICS is not set
-# CONFIG_BOARDCTL_IOCTL is not set
-
-#
-# RTOS Features
-#
-CONFIG_DISABLE_OS_API=y
-# CONFIG_DISABLE_POSIX_TIMERS is not set
-# CONFIG_DISABLE_PTHREAD is not set
-# CONFIG_DISABLE_SIGNALS is not set
-# CONFIG_DISABLE_MQUEUE is not set
-# CONFIG_DISABLE_ENVIRON is not set
-
-#
-# Clocks and Timers
-#
-CONFIG_ARCH_HAVE_TICKLESS=y
-# CONFIG_SCHED_TICKLESS is not set
-CONFIG_USEC_PER_TICK=1000
-# CONFIG_SYSTEM_TIME64 is not set
-# CONFIG_CLOCK_MONOTONIC is not set
-CONFIG_ARCH_HAVE_TIMEKEEPING=y
-# CONFIG_JULIAN_TIME is not set
-CONFIG_START_YEAR=1970
-CONFIG_START_MONTH=1
-CONFIG_START_DAY=1
-CONFIG_MAX_WDOGPARMS=2
-CONFIG_PREALLOC_WDOGS=50
-CONFIG_WDOG_INTRESERVE=4
-CONFIG_PREALLOC_TIMERS=50
-
-#
-# Tasks and Scheduling
-#
-# CONFIG_INIT_NONE is not set
-CONFIG_INIT_ENTRYPOINT=y
-# CONFIG_INIT_FILEPATH is not set
-CONFIG_USER_ENTRYPOINT="nsh_main"
-CONFIG_RR_INTERVAL=0
-# CONFIG_SCHED_SPORADIC is not set
-CONFIG_TASK_NAME_SIZE=24
-CONFIG_MAX_TASKS=32
-# CONFIG_SCHED_HAVE_PARENT is not set
-CONFIG_SCHED_WAITPID=y
-
-#
-# Pthread Options
-#
-# CONFIG_MUTEX_TYPES is not set
-CONFIG_NPTHREAD_KEYS=4
-
-#
-# Performance Monitoring
-#
-# CONFIG_SCHED_CPULOAD is not set
-CONFIG_SCHED_INSTRUMENTATION=y
-# CONFIG_SCHED_INSTRUMENTATION_PREEMPTION is not set
-# CONFIG_SCHED_INSTRUMENTATION_CSECTION is not set
-# CONFIG_SCHED_INSTRUMENTATION_BUFFER is not set
-
-#
-# Files and I/O
-#
-CONFIG_DEV_CONSOLE=y
-# CONFIG_FDCLONE_DISABLE is not set
-CONFIG_FDCLONE_STDIO=y
-CONFIG_SDCLONE_DISABLE=y
-CONFIG_NFILE_DESCRIPTORS=53
-CONFIG_NFILE_STREAMS=8
-CONFIG_NAME_MAX=32
-CONFIG_PRIORITY_INHERITANCE=y
-CONFIG_SEM_PREALLOCHOLDERS=0
-CONFIG_SEM_NNESTPRIO=8
-
-#
-# RTOS hooks
-#
-# CONFIG_BOARD_INITIALIZE is not set
-# CONFIG_SCHED_STARTHOOK is not set
-CONFIG_SCHED_ATEXIT=y
-CONFIG_SCHED_ATEXIT_MAX=1
-# CONFIG_SCHED_ONEXIT is not set
-# CONFIG_SIG_EVTHREAD is not set
-
-#
-# Signal Numbers
-#
-CONFIG_SIG_SIGUSR1=1
-CONFIG_SIG_SIGUSR2=2
-CONFIG_SIG_SIGALARM=3
-CONFIG_SIG_SIGCONDTIMEDOUT=16
-CONFIG_SIG_SIGWORK=4
-
-#
-# POSIX Message Queue Options
-#
-CONFIG_PREALLOC_MQ_MSGS=4
-CONFIG_MQ_MAXMSGSIZE=32
-# CONFIG_MODULE is not set
-
-#
-# Work queue support
-#
-CONFIG_SCHED_WORKQUEUE=y
-CONFIG_SCHED_HPWORK=y
-CONFIG_SCHED_HPWORKPRIORITY=192
-CONFIG_SCHED_HPWORKPERIOD=5000
-CONFIG_SCHED_HPWORKSTACKSIZE=1600
-CONFIG_SCHED_LPWORK=y
-CONFIG_SCHED_LPNTHREADS=1
-CONFIG_SCHED_LPWORKPRIORITY=50
-CONFIG_SCHED_LPWORKPRIOMAX=176
-CONFIG_SCHED_LPWORKPERIOD=50000
-CONFIG_SCHED_LPWORKSTACKSIZE=1600
-
-#
-# Stack and heap information
-#
-CONFIG_IDLETHREAD_STACKSIZE=600
-CONFIG_USERMAIN_STACKSIZE=1800
-CONFIG_PTHREAD_STACK_MIN=512
-CONFIG_PTHREAD_STACK_DEFAULT=2048
-# CONFIG_LIB_SYSCALL is not set
-
-#
-# Device Drivers
-#
-# CONFIG_DISABLE_POLL is not set
-CONFIG_DEV_NULL=y
-# CONFIG_DEV_ZERO is not set
-# CONFIG_DEV_URANDOM is not set
-# CONFIG_DEV_LOOP is not set
-
-#
-# Buffering
-#
-# CONFIG_DRVR_WRITEBUFFER is not set
-# CONFIG_DRVR_READAHEAD is not set
-# CONFIG_RAMDISK is not set
-# CONFIG_CAN is not set
-# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set
-# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set
-# CONFIG_PWM is not set
-CONFIG_ARCH_HAVE_I2CRESET=y
-CONFIG_I2C=y
-# CONFIG_I2C_SLAVE is not set
-# CONFIG_I2C_POLLED is not set
-CONFIG_I2C_RESET=y
-# CONFIG_I2C_TRACE is not set
-# CONFIG_I2C_DRIVER is not set
-CONFIG_SPI=y
-# CONFIG_SPI_SLAVE is not set
-CONFIG_SPI_EXCHANGE=y
-# CONFIG_SPI_CMDDATA is not set
-# CONFIG_SPI_CALLBACK is not set
-# CONFIG_SPI_BITBANG is not set
-# CONFIG_SPI_HWFEATURES is not set
-# CONFIG_SPI_CRCGENERATION is not set
-# CONFIG_SPI_CS_CONTROL is not set
-# CONFIG_SPI_CS_DELAY_CONTROL is not set
-# CONFIG_I2S is not set
-
-#
-# Timer Driver Support
-#
-# CONFIG_TIMER is not set
-# CONFIG_RTC is not set
-CONFIG_WATCHDOG=y
-CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0"
-# CONFIG_TIMERS_CS2100CP is not set
-# CONFIG_ANALOG is not set
-# CONFIG_AUDIO_DEVICES is not set
-# CONFIG_VIDEO_DEVICES is not set
-# CONFIG_BCH is not set
-# CONFIG_INPUT is not set
-
-#
-# IO Expander/GPIO Support
-#
-# CONFIG_IOEXPANDER is not set
-# CONFIG_DEV_GPIO is not set
-
-#
-# LCD Driver Support
-#
-# CONFIG_LCD is not set
-# CONFIG_SLCD is not set
-
-#
-# LED Support
-#
-# CONFIG_RGBLED is not set
-# CONFIG_PCA9635PW is not set
-# CONFIG_NCP5623C is not set
-CONFIG_MMCSD=y
-CONFIG_MMCSD_NSLOTS=1
-# CONFIG_MMCSD_READONLY is not set
-# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
-# CONFIG_MMCSD_MMCSUPPORT is not set
-# CONFIG_MMCSD_HAVECARDDETECT is not set
-CONFIG_MMCSD_SPI=y
-CONFIG_MMCSD_SPICLOCK=24000000
-CONFIG_MMCSD_SPIMODE=0
-# CONFIG_ARCH_HAVE_SDIO is not set
-# CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE is not set
-# CONFIG_MODEM is not set
-CONFIG_MTD=y
-
-#
-# MTD Configuration
-#
-CONFIG_MTD_PARTITION=y
-# CONFIG_MTD_SECT512 is not set
-# CONFIG_MTD_PARTITION_NAMES is not set
-CONFIG_MTD_BYTE_WRITE=y
-# CONFIG_MTD_PROGMEM is not set
-# CONFIG_MTD_CONFIG is not set
-
-#
-# MTD Device Drivers
-#
-# CONFIG_MTD_NAND is not set
-# CONFIG_RAMMTD is not set
-# CONFIG_FILEMTD is not set
-# CONFIG_MTD_AT24XX is not set
-# CONFIG_MTD_AT25 is not set
-# CONFIG_MTD_AT45DB is not set
-# CONFIG_MTD_IS25XP is not set
-# CONFIG_MTD_M25P is not set
-# CONFIG_MTD_S25FL1 is not set
-# CONFIG_MTD_N25QXXX is not set
-# CONFIG_MTD_SMART is not set
-# CONFIG_MTD_RAMTRON is not set
-# CONFIG_MTD_SST25 is not set
-# CONFIG_MTD_SST25XX is not set
-# CONFIG_MTD_SST26 is not set
-# CONFIG_MTD_SST39FV is not set
-# CONFIG_MTD_W25 is not set
-CONFIG_EEPROM=y
-# CONFIG_SPI_EE_25XX is not set
-CONFIG_PIPES=y
-CONFIG_DEV_PIPE_MAXSIZE=1024
-CONFIG_DEV_PIPE_SIZE=70
-CONFIG_DEV_FIFO_SIZE=0
-# CONFIG_PM is not set
-# CONFIG_POWER is not set
-# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
-CONFIG_SERIAL=y
-# CONFIG_DEV_LOWCONSOLE is not set
-CONFIG_SERIAL_REMOVABLE=y
-CONFIG_SERIAL_CONSOLE=y
-# CONFIG_16550_UART is not set
-# CONFIG_UART_SERIALDRIVER is not set
-# CONFIG_UART0_SERIALDRIVER is not set
-# CONFIG_UART1_SERIALDRIVER is not set
-# CONFIG_UART2_SERIALDRIVER is not set
-# CONFIG_UART3_SERIALDRIVER is not set
-# CONFIG_UART4_SERIALDRIVER is not set
-CONFIG_UART5_SERIALDRIVER=y
-# CONFIG_UART6_SERIALDRIVER is not set
-# CONFIG_UART7_SERIALDRIVER is not set
-# CONFIG_UART8_SERIALDRIVER is not set
-# CONFIG_SCI0_SERIALDRIVER is not set
-# CONFIG_SCI1_SERIALDRIVER is not set
-# CONFIG_USART0_SERIALDRIVER is not set
-CONFIG_USART1_SERIALDRIVER=y
-CONFIG_USART2_SERIALDRIVER=y
-# CONFIG_USART3_SERIALDRIVER is not set
-# CONFIG_USART4_SERIALDRIVER is not set
-# CONFIG_USART5_SERIALDRIVER is not set
-CONFIG_USART6_SERIALDRIVER=y
-# CONFIG_USART7_SERIALDRIVER is not set
-# CONFIG_USART8_SERIALDRIVER is not set
-# CONFIG_OTHER_UART_SERIALDRIVER is not set
-CONFIG_MCU_SERIAL=y
-CONFIG_STANDARD_SERIAL=y
-CONFIG_SERIAL_NPOLLWAITERS=2
-CONFIG_SERIAL_IFLOWCONTROL=y
-CONFIG_SERIAL_OFLOWCONTROL=y
-# CONFIG_SERIAL_DMA is not set
-CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
-CONFIG_SERIAL_IFLOWCONTROL_LOWER_WATERMARK=10
-CONFIG_SERIAL_IFLOWCONTROL_UPPER_WATERMARK=90
-CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
-CONFIG_USART1_SERIAL_CONSOLE=y
-# CONFIG_USART2_SERIAL_CONSOLE is not set
-# CONFIG_UART5_SERIAL_CONSOLE is not set
-# CONFIG_USART6_SERIAL_CONSOLE is not set
-# CONFIG_OTHER_SERIAL_CONSOLE is not set
-# CONFIG_NO_SERIAL_CONSOLE is not set
-
-#
-# USART1 Configuration
-#
-CONFIG_USART1_RXBUFSIZE=128
-CONFIG_USART1_TXBUFSIZE=128
-CONFIG_USART1_BAUD=57600
-CONFIG_USART1_BITS=8
-CONFIG_USART1_PARITY=0
-CONFIG_USART1_2STOP=0
-# CONFIG_USART1_IFLOWCONTROL is not set
-# CONFIG_USART1_OFLOWCONTROL is not set
-# CONFIG_USART1_DMA is not set
-
-#
-# USART2 Configuration
-#
-CONFIG_USART2_RXBUFSIZE=300
-CONFIG_USART2_TXBUFSIZE=300
-CONFIG_USART2_BAUD=57600
-CONFIG_USART2_BITS=8
-CONFIG_USART2_PARITY=0
-CONFIG_USART2_2STOP=0
-CONFIG_USART2_IFLOWCONTROL=y
-CONFIG_USART2_OFLOWCONTROL=y
-# CONFIG_USART2_DMA is not set
-
-#
-# UART5 Configuration
-#
-CONFIG_UART5_RXBUFSIZE=300
-CONFIG_UART5_TXBUFSIZE=300
-CONFIG_UART5_BAUD=57600
-CONFIG_UART5_BITS=8
-CONFIG_UART5_PARITY=0
-CONFIG_UART5_2STOP=0
-# CONFIG_UART5_IFLOWCONTROL is not set
-# CONFIG_UART5_OFLOWCONTROL is not set
-# CONFIG_UART5_DMA is not set
-
-#
-# USART6 Configuration
-#
-CONFIG_USART6_RXBUFSIZE=128
-CONFIG_USART6_TXBUFSIZE=64
-CONFIG_USART6_BAUD=57600
-CONFIG_USART6_BITS=8
-CONFIG_USART6_PARITY=0
-CONFIG_USART6_2STOP=0
-# CONFIG_USART6_IFLOWCONTROL is not set
-# CONFIG_USART6_OFLOWCONTROL is not set
-# CONFIG_USART6_DMA is not set
-# CONFIG_PSEUDOTERM is not set
-CONFIG_USBDEV=y
-
-#
-# USB Device Controller Driver Options
-#
-# CONFIG_USBDEV_ISOCHRONOUS is not set
-# CONFIG_USBDEV_DUALSPEED is not set
-# CONFIG_USBDEV_SELFPOWERED is not set
-CONFIG_USBDEV_BUSPOWERED=y
-CONFIG_USBDEV_MAXPOWER=500
-# CONFIG_USBDEV_DMA is not set
-# CONFIG_ARCH_USBDEV_STALLQUEUE is not set
-# CONFIG_USBDEV_TRACE is not set
-
-#
-# USB Device Class Driver Options
-#
-# CONFIG_USBDEV_COMPOSITE is not set
-# CONFIG_PL2303 is not set
-CONFIG_CDCACM=y
-# CONFIG_CDCACM_CONSOLE is not set
-CONFIG_CDCACM_EP0MAXPACKET=64
-CONFIG_CDCACM_EPINTIN=1
-CONFIG_CDCACM_EPINTIN_FSSIZE=64
-CONFIG_CDCACM_EPINTIN_HSSIZE=64
-CONFIG_CDCACM_EPBULKOUT=3
-CONFIG_CDCACM_EPBULKOUT_FSSIZE=64
-CONFIG_CDCACM_EPBULKOUT_HSSIZE=512
-CONFIG_CDCACM_EPBULKIN=2
-CONFIG_CDCACM_EPBULKIN_FSSIZE=64
-CONFIG_CDCACM_EPBULKIN_HSSIZE=512
-CONFIG_CDCACM_NRDREQS=4
-CONFIG_CDCACM_NWRREQS=4
-CONFIG_CDCACM_BULKIN_REQLEN=96
-CONFIG_CDCACM_RXBUFSIZE=300
-CONFIG_CDCACM_TXBUFSIZE=1000
-CONFIG_CDCACM_VENDORID=0x26ac
-CONFIG_CDCACM_PRODUCTID=0x0010
-CONFIG_CDCACM_VENDORSTR="3D Robotics"
-CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.x"
-# CONFIG_USBMSC is not set
-# CONFIG_USBHOST is not set
-# CONFIG_HAVE_USBTRACE is not set
-# CONFIG_DRIVERS_WIRELESS is not set
-
-#
-# System Logging
-#
-# CONFIG_ARCH_SYSLOG is not set
-# CONFIG_RAMLOG is not set
-# CONFIG_SYSLOG_INTBUFFER is not set
-# CONFIG_SYSLOG_TIMESTAMP is not set
-# CONFIG_SYSLOG_SERIAL_CONSOLE is not set
-CONFIG_SYSLOG_CHAR=y
-# CONFIG_SYSLOG_CONSOLE is not set
-# CONFIG_SYSLOG_NONE is not set
-# CONFIG_SYSLOG_FILE is not set
-# CONFIG_CONSOLE_SYSLOG is not set
-CONFIG_SYSLOG_CHAR_CRLF=y
-CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
-# CONFIG_SYSLOG_CHARDEV is not set
-
-#
-# Networking Support
-#
-# CONFIG_ARCH_HAVE_NET is not set
-# CONFIG_ARCH_HAVE_PHY is not set
-# CONFIG_NET is not set
-
-#
-# Crypto API
-#
-# CONFIG_CRYPTO is not set
-
-#
-# File Systems
-#
-
-#
-# File system configuration
-#
-# CONFIG_DISABLE_MOUNTPOINT is not set
-# CONFIG_FS_AUTOMOUNTER is not set
-# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
-CONFIG_FS_READABLE=y
-CONFIG_FS_WRITABLE=y
-# CONFIG_FS_AIO is not set
-# CONFIG_FS_NAMED_SEMAPHORES is not set
-CONFIG_FS_MQUEUE_MPATH="/var/mqueue"
-# CONFIG_FS_RAMMAP is not set
-CONFIG_FS_FAT=y
-CONFIG_FAT_LCNAMES=y
-CONFIG_FAT_LFN=y
-CONFIG_FAT_MAXFNAME=32
-CONFIG_FS_FATTIME=y
-# CONFIG_FAT_FORCE_INDIRECT is not set
-# CONFIG_FAT_DMAMEMORY is not set
-# CONFIG_FAT_DIRECT_RETRY is not set
-# CONFIG_FS_NXFFS is not set
-CONFIG_FS_ROMFS=y
-# CONFIG_FS_TMPFS is not set
-# CONFIG_FS_SMARTFS is not set
-CONFIG_FS_BINFS=y
-CONFIG_FS_PROCFS=y
-# CONFIG_FS_PROCFS_REGISTER is not set
-
-#
-# Exclude individual procfs entries
-#
-# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set
-# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set
-# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set
-# CONFIG_FS_PROCFS_EXCLUDE_MTD is not set
-# CONFIG_FS_PROCFS_EXCLUDE_PARTITIONS is not set
-# CONFIG_FS_UNIONFS is not set
-
-#
-# Graphics Support
-#
-# CONFIG_NX is not set
-
-#
-# Memory Management
-#
-# CONFIG_MM_SMALL is not set
-CONFIG_MM_REGIONS=2
-# CONFIG_ARCH_HAVE_HEAP2 is not set
-CONFIG_GRAN=y
-CONFIG_GRAN_SINGLE=y
-CONFIG_GRAN_INTR=y
-
-#
-# Audio Support
-#
-# CONFIG_AUDIO is not set
-
-#
-# Wireless Support
-#
-
-#
-# Binary Loader
-#
-# CONFIG_BINFMT_DISABLE is not set
-# CONFIG_BINFMT_EXEPATH is not set
-# CONFIG_NXFLAT is not set
-# CONFIG_ELF is not set
-CONFIG_BUILTIN=y
-# CONFIG_PIC is not set
-# CONFIG_SYMTAB_ORDEREDBYNAME is not set
-
-#
-# Library Routines
-#
-
-#
-# Standard C Library Options
-#
-CONFIG_STDIO_BUFFER_SIZE=180
-CONFIG_STDIO_LINEBUFFER=y
-CONFIG_NUNGET_CHARS=2
-CONFIG_LIB_HOMEDIR="/"
-# CONFIG_NOPRINTF_FIELDWIDTH is not set
-CONFIG_LIBC_FLOATINGPOINT=y
-CONFIG_LIBC_LONG_LONG=y
-# CONFIG_LIBC_IOCTL_VARIADIC is not set
-CONFIG_LIB_RAND_ORDER=1
-# CONFIG_EOL_IS_CR is not set
-# CONFIG_EOL_IS_LF is not set
-# CONFIG_EOL_IS_BOTH_CRLF is not set
-CONFIG_EOL_IS_EITHER_CRLF=y
-# CONFIG_LIBC_EXECFUNCS is not set
-CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
-CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
-CONFIG_LIBC_STRERROR=y
-# CONFIG_LIBC_STRERROR_SHORT is not set
-# CONFIG_LIBC_PERROR_STDOUT is not set
-CONFIG_LIBC_TMPDIR="/tmp"
-CONFIG_LIBC_MAX_TMPFILE=32
-CONFIG_ARCH_LOWPUTC=y
-# CONFIG_LIBC_LOCALTIME is not set
-CONFIG_TIME_EXTENDED=y
-CONFIG_LIB_SENDFILE_BUFSIZE=512
-# CONFIG_ARCH_ROMGETC is not set
-CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y
-CONFIG_ARCH_MEMCPY=y
-# CONFIG_ARCH_MEMCMP is not set
-# CONFIG_ARCH_MEMMOVE is not set
-# CONFIG_ARCH_MEMSET is not set
-# CONFIG_MEMSET_OPTSPEED is not set
-# CONFIG_ARCH_STRCHR is not set
-# CONFIG_ARCH_STRCMP is not set
-# CONFIG_ARCH_STRCPY is not set
-# CONFIG_ARCH_STRNCPY is not set
-# CONFIG_ARCH_STRLEN is not set
-# CONFIG_ARCH_STRNLEN is not set
-# CONFIG_ARCH_BZERO is not set
-CONFIG_ARCH_HAVE_TLS=y
-# CONFIG_TLS is not set
-# CONFIG_LIBC_NETDB is not set
-# CONFIG_NETDB_HOSTFILE is not set
-
-#
-# Non-standard Library Support
-#
-# CONFIG_LIB_CRC64_FAST is not set
-# CONFIG_LIB_KBDCODEC is not set
-# CONFIG_LIB_SLCDCODEC is not set
-# CONFIG_LIB_HEX2BIN is not set
-
-#
-# Basic CXX Support
-#
-CONFIG_C99_BOOL8=y
-CONFIG_HAVE_CXX=y
-CONFIG_HAVE_CXXINITIALIZE=y
-# CONFIG_CXX_NEWLONG is not set
-
-#
-# uClibc++ Standard C++ Library
-#
-# CONFIG_UCLIBCXX is not set
-
-#
-# Application Configuration
-#
-
-#
-# Built-In Applications
-#
-CONFIG_BUILTIN_PROXY_STACKSIZE=1024
-
-#
-# CAN Utilities
-#
-# CONFIG_CANUTILS_LIBUAVCAN is not set
-
-#
-# Examples
-#
-# CONFIG_EXAMPLES_CHAT is not set
-# CONFIG_EXAMPLES_CONFIGDATA is not set
-# CONFIG_EXAMPLES_CPUHOG is not set
-# CONFIG_EXAMPLES_CXXTEST is not set
-# CONFIG_EXAMPLES_DHCPD is not set
-# CONFIG_EXAMPLES_ELF is not set
-# CONFIG_EXAMPLES_FSTEST is not set
-# CONFIG_EXAMPLES_FTPC is not set
-# CONFIG_EXAMPLES_FTPD is not set
-# CONFIG_EXAMPLES_HELLO is not set
-# CONFIG_EXAMPLES_HELLOXX is not set
-# CONFIG_EXAMPLES_HIDKBD is not set
-# CONFIG_EXAMPLES_IGMP is not set
-# CONFIG_EXAMPLES_JSON is not set
-# CONFIG_EXAMPLES_KEYPADTEST is not set
-# CONFIG_EXAMPLES_MEDIA is not set
-# CONFIG_EXAMPLES_MM is not set
-# CONFIG_EXAMPLES_MODBUS is not set
-CONFIG_EXAMPLES_MOUNT=y
-# CONFIG_EXAMPLES_MOUNT_BLOCKDEVICE is not set
-CONFIG_EXAMPLES_MOUNT_NSECTORS=2048
-CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512
-CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0
-# CONFIG_EXAMPLES_MTDPART is not set
-# CONFIG_EXAMPLES_NRF24L01TERM is not set
-CONFIG_EXAMPLES_NSH=y
-# CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set
-# CONFIG_EXAMPLES_NULL is not set
-# CONFIG_EXAMPLES_NXFFS is not set
-# CONFIG_EXAMPLES_NXHELLO is not set
-# CONFIG_EXAMPLES_NXIMAGE is not set
-# CONFIG_EXAMPLES_NX is not set
-# CONFIG_EXAMPLES_NXLINES is not set
-# CONFIG_EXAMPLES_NXTERM is not set
-# CONFIG_EXAMPLES_NXTEXT is not set
-# CONFIG_EXAMPLES_OSTEST is not set
-# CONFIG_EXAMPLES_PCA9635 is not set
-# CONFIG_EXAMPLES_PIPE is not set
-# CONFIG_EXAMPLES_POSIXSPAWN is not set
-# CONFIG_EXAMPLES_PPPD is not set
-# CONFIG_EXAMPLES_RGBLED is not set
-# CONFIG_EXAMPLES_RGMP is not set
-# CONFIG_EXAMPLES_ROMFS is not set
-# CONFIG_EXAMPLES_SENDMAIL is not set
-# CONFIG_EXAMPLES_SERIALBLASTER is not set
-# CONFIG_EXAMPLES_SERIALRX is not set
-# CONFIG_EXAMPLES_SERLOOP is not set
-# CONFIG_EXAMPLES_SLCD is not set
-# CONFIG_EXAMPLES_SMART is not set
-# CONFIG_EXAMPLES_SMART_TEST is not set
-# CONFIG_EXAMPLES_SMP is not set
-# CONFIG_EXAMPLES_TCPECHO is not set
-# CONFIG_EXAMPLES_TELNETD is not set
-# CONFIG_EXAMPLES_THTTPD is not set
-# CONFIG_EXAMPLES_TIFF is not set
-# CONFIG_EXAMPLES_TOUCHSCREEN is not set
-# CONFIG_EXAMPLES_UNIONFS is not set
-# CONFIG_EXAMPLES_USBSERIAL is not set
-# CONFIG_EXAMPLES_USBTERM is not set
-# CONFIG_EXAMPLES_WATCHDOG is not set
-# CONFIG_EXAMPLES_WEBSERVER is not set
-
-#
-# File System Utilities
-#
-# CONFIG_FSUTILS_FLASH_ERASEALL is not set
-# CONFIG_FSUTILS_INIFILE is not set
-# CONFIG_FSUTILS_PASSWD is not set
-
-#
-# GPS Utilities
-#
-# CONFIG_GPSUTILS_MINMEA_LIB is not set
-
-#
-# Graphics Support
-#
-# CONFIG_TIFF is not set
-# CONFIG_GRAPHICS_TRAVELER is not set
-
-#
-# Interpreters
-#
-# CONFIG_INTERPRETERS_BAS is not set
-# CONFIG_INTERPRETERS_FICL is not set
-# CONFIG_INTERPRETERS_MICROPYTHON is not set
-# CONFIG_INTERPRETERS_PCODE is not set
-
-#
-# FreeModBus
-#
-# CONFIG_MODBUS is not set
-
-#
-# Network Utilities
-#
-# CONFIG_NETUTILS_CHAT is not set
-# CONFIG_NETUTILS_CODECS is not set
-# CONFIG_NETUTILS_ESP8266 is not set
-# CONFIG_NETUTILS_FTPC is not set
-# CONFIG_NETUTILS_JSON is not set
-# CONFIG_NETUTILS_SMTP is not set
-# CONFIG_NETUTILS_THTTPD is not set
-
-#
-# NSH Library
-#
-CONFIG_NSH_LIBRARY=y
-# CONFIG_NSH_MOTD is not set
-
-#
-# Command Line Configuration
-#
-CONFIG_NSH_READLINE=y
-# CONFIG_NSH_CLE is not set
-CONFIG_NSH_LINELEN=128
-# CONFIG_NSH_DISABLE_SEMICOLON is not set
-CONFIG_NSH_CMDPARMS=y
-CONFIG_NSH_MAXARGUMENTS=12
-CONFIG_NSH_ARGCAT=y
-CONFIG_NSH_NESTDEPTH=8
-# CONFIG_NSH_DISABLEBG is not set
-CONFIG_NSH_BUILTIN_APPS=y
-
-#
-# Disable Individual commands
-#
-CONFIG_NSH_DISABLE_ADDROUTE=y
-# CONFIG_NSH_DISABLE_BASENAME is not set
-# CONFIG_NSH_DISABLE_CAT is not set
-# CONFIG_NSH_DISABLE_CD is not set
-# CONFIG_NSH_DISABLE_CP is not set
-# CONFIG_NSH_DISABLE_CMP is not set
-# CONFIG_NSH_DISABLE_DATE is not set
-# CONFIG_NSH_DISABLE_DD is not set
-# CONFIG_NSH_DISABLE_DF is not set
-CONFIG_NSH_DISABLE_DELROUTE=y
-# CONFIG_NSH_DISABLE_DIRNAME is not set
-# CONFIG_NSH_DISABLE_ECHO is not set
-# CONFIG_NSH_DISABLE_EXEC is not set
-# CONFIG_NSH_DISABLE_EXIT is not set
-# CONFIG_NSH_DISABLE_FREE is not set
-# CONFIG_NSH_DISABLE_GET is not set
-# CONFIG_NSH_DISABLE_HELP is not set
-# CONFIG_NSH_DISABLE_HEXDUMP is not set
-CONFIG_NSH_DISABLE_IFCONFIG=y
-CONFIG_NSH_DISABLE_IFUPDOWN=y
-# CONFIG_NSH_DISABLE_KILL is not set
-# CONFIG_NSH_DISABLE_LOSETUP is not set
-CONFIG_NSH_DISABLE_LOSMART=y
-# CONFIG_NSH_DISABLE_LS is not set
-# CONFIG_NSH_DISABLE_MB is not set
-# CONFIG_NSH_DISABLE_MKDIR is not set
-# CONFIG_NSH_DISABLE_MKFATFS is not set
-# CONFIG_NSH_DISABLE_MKFIFO is not set
-# CONFIG_NSH_DISABLE_MKRD is not set
-# CONFIG_NSH_DISABLE_MH is not set
-# CONFIG_NSH_DISABLE_MOUNT is not set
-# CONFIG_NSH_DISABLE_MV is not set
-# CONFIG_NSH_DISABLE_MW is not set
-# CONFIG_NSH_DISABLE_PS is not set
-# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
-# CONFIG_NSH_DISABLE_PUT is not set
-# CONFIG_NSH_DISABLE_PWD is not set
-# CONFIG_NSH_DISABLE_RM is not set
-# CONFIG_NSH_DISABLE_RMDIR is not set
-# CONFIG_NSH_DISABLE_SET is not set
-# CONFIG_NSH_DISABLE_SH is not set
-# CONFIG_NSH_DISABLE_SLEEP is not set
-# CONFIG_NSH_DISABLE_TIME is not set
-# CONFIG_NSH_DISABLE_TEST is not set
-# CONFIG_NSH_DISABLE_UMOUNT is not set
-# CONFIG_NSH_DISABLE_UNAME is not set
-# CONFIG_NSH_DISABLE_UNSET is not set
-# CONFIG_NSH_DISABLE_USLEEP is not set
-CONFIG_NSH_DISABLE_WGET=y
-# CONFIG_NSH_DISABLE_XD is not set
-CONFIG_NSH_MMCSDMINOR=0
-CONFIG_NSH_MMCSDSLOTNO=0
-CONFIG_NSH_MMCSDSPIPORTNO=3
-
-#
-# Configure Command Options
-#
-# CONFIG_NSH_CMDOPT_DF_H is not set
-CONFIG_NSH_CODECS_BUFSIZE=128
-CONFIG_NSH_CMDOPT_HEXDUMP=y
-CONFIG_NSH_PROC_MOUNTPOINT="/proc"
-CONFIG_NSH_FILEIOSIZE=512
-CONFIG_NSH_STRERROR=y
-
-#
-# Scripting Support
-#
-# CONFIG_NSH_DISABLESCRIPT is not set
-# CONFIG_NSH_DISABLE_ITEF is not set
-# CONFIG_NSH_DISABLE_LOOPS is not set
-CONFIG_NSH_ROMFSETC=y
-# CONFIG_NSH_ROMFSRC is not set
-CONFIG_NSH_ROMFSMOUNTPT="/etc"
-CONFIG_NSH_INITSCRIPT="init.d/rcS"
-CONFIG_NSH_ROMFSDEVNO=0
-CONFIG_NSH_ROMFSSECTSIZE=128
-# CONFIG_NSH_DEFAULTROMFS is not set
-CONFIG_NSH_ARCHROMFS=y
-# CONFIG_NSH_CUSTOMROMFS is not set
-CONFIG_NSH_FATDEVNO=1
-CONFIG_NSH_FATSECTSIZE=512
-CONFIG_NSH_FATNSECTORS=1024
-CONFIG_NSH_FATMOUNTPT="/tmp"
-
-#
-# Console Configuration
-#
-CONFIG_NSH_CONSOLE=y
-# CONFIG_NSH_USBCONSOLE is not set
-# CONFIG_NSH_ALTCONDEV is not set
-CONFIG_NSH_ARCHINIT=y
-# CONFIG_NSH_LOGIN is not set
-# CONFIG_NSH_CONSOLE_LOGIN is not set
-
-#
-# NxWidgets/NxWM
-#
-
-#
-# Platform-specific Support
-#
-# CONFIG_PLATFORM_CONFIGDATA is not set
-
-#
-# System Libraries and NSH Add-Ons
-#
-CONFIG_SYSTEM_CDCACM=y
-CONFIG_SYSTEM_CDCACM_DEVMINOR=0
-# CONFIG_SYSTEM_CLE is not set
-CONFIG_SYSTEM_CUTERM=y
-CONFIG_SYSTEM_CUTERM_DEFAULT_DEVICE="/dev/ttyS0"
-CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600
-CONFIG_SYSTEM_CUTERM_STACKSIZE=2048
-CONFIG_SYSTEM_CUTERM_PRIORITY=100
-# CONFIG_SYSTEM_FLASH_ERASEALL is not set
-# CONFIG_SYSTEM_FREE is not set
-# CONFIG_SYSTEM_HEX2BIN is not set
-# CONFIG_SYSTEM_HEXED is not set
-# CONFIG_SYSTEM_I2CTOOL is not set
-# CONFIG_SYSTEM_INSTALL is not set
-# CONFIG_SYSTEM_RAMTEST is not set
-CONFIG_READLINE_HAVE_EXTMATCH=y
-CONFIG_SYSTEM_READLINE=y
-CONFIG_READLINE_ECHO=y
-# CONFIG_READLINE_TABCOMPLETION is not set
-# CONFIG_READLINE_CMD_HISTORY is not set
-# CONFIG_SYSTEM_STACKMONITOR is not set
-# CONFIG_SYSTEM_SUDOKU is not set
-# CONFIG_SYSTEM_UBLOXMODEM is not set
-# CONFIG_SYSTEM_VI is not set
-# CONFIG_SYSTEM_ZMODEM is not set
diff --git a/nuttx-configs/px4fmu-v1/nsh/setenv.sh b/nuttx-configs/px4fmu-v1/nsh/setenv.sh
deleted file mode 100755
index 80a6ffe067..0000000000
--- a/nuttx-configs/px4fmu-v1/nsh/setenv.sh
+++ /dev/null
@@ -1,75 +0,0 @@
-#!/bin/bash
-# nuttx-configs/px4fmu-v1/nsh/setenv.sh
-#
-#   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
-# 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 [ "$_" = "$0" ] ; then
-  echo "You must source this script, not run it!" 1>&2
-  exit 1
-fi
-
-WD=`pwd`
-if [ ! -x "setenv.sh" ]; then
-  echo "This script must be executed from the top-level NuttX build directory"
-  exit 1
-fi
-
-if [ -z "${PATH_ORIG}" ]; then
-  export PATH_ORIG="${PATH}"
-fi
-
-# This is the Cygwin path to the location where I installed the RIDE
-# toolchain under windows.  You will also have to edit this if you install
-# the RIDE toolchain in any other location
-#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
-
-# This is the Cygwin path to the location where I installed the CodeSourcery
-# toolchain under windows.  You will also have to edit this if you install
-# the CodeSourcery toolchain in any other location
-export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
-
-# These are the Cygwin paths to the locations where I installed the Atollic
-# toolchain under windows.  You will also have to edit this if you install
-# the Atollic toolchain in any other location.  /usr/bin is added before
-# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
-# at those locations as well.
-#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
-#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
-
-# This is the Cygwin path to the location where I build the buildroot
-# toolchain.
-#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-
-# Add the path to the toolchain to the PATH varialble
-export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
-
-echo "PATH : ${PATH}"
diff --git a/nuttx-configs/px4fmu-v1/scripts/ld.script b/nuttx-configs/px4fmu-v1/scripts/ld.script
deleted file mode 100644
index f7eaeed90a..0000000000
--- a/nuttx-configs/px4fmu-v1/scripts/ld.script
+++ /dev/null
@@ -1,149 +0,0 @@
-/****************************************************************************
- * nuttx-configs/px4fmu-v1/scripts/ld.script
- *
- *   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.
- *
- ****************************************************************************/
-
-/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
- *
- * 1) 112Kb of SRAM beginning at address 0x2000:0000
- * 2)  16Kb of SRAM beginning at address 0x2001:c000
- * 3)  64Kb of CCM SRAM beginning at address 0x1000: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.
- *
- * The first 0x4000 of flash is reserved for the bootloader.
- */
-
-MEMORY
-{
-    flash (rx)   : ORIGIN = 0x08004000, LENGTH = 1008K
-    sram (rwx)   : ORIGIN = 0x20000000, LENGTH = 128K
-    ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
-}
-
-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.*)
-		*(.got)
-		*(.gcc_except_table)
-		*(.gnu.linkonce.r.*)
-		_etext = ABSOLUTE(.);
-
-		/* 
-		 * This is a hack to make the newlib libm __errno() call
-		 * use the NuttX get_errno_ptr() function.
-		 */
-		__errno = get_errno_ptr;
-	} > flash
-
-	/*
-	 * Init functions (static constructors and the like)
-	 */
-        .init_section : {
-                _sinit = ABSOLUTE(.);
-                KEEP(*(.init_array .init_array.*))
-                _einit = ABSOLUTE(.);
-        } > flash
-
-	/*
-	 * Construction data for parameters.
-	 */
-	__param ALIGN(4): {
-		__param_start = ABSOLUTE(.);
-		KEEP(*(__param*))
-		__param_end = ABSOLUTE(.);
-	} > flash
-
-	.ARM.extab : {
-		*(.ARM.extab*)
-	} > flash
-
-	__exidx_start = ABSOLUTE(.);
-	.ARM.exidx : {
-		*(.ARM.exidx*)
-	} > flash
-	__exidx_end = ABSOLUTE(.);
-
-	_eronly = ABSOLUTE(.);
-
-	.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/px4fmu-v1/src/Makefile b/nuttx-configs/px4fmu-v1/src/Makefile
deleted file mode 100644
index 367746479e..0000000000
--- a/nuttx-configs/px4fmu-v1/src/Makefile
+++ /dev/null
@@ -1,87 +0,0 @@
-############################################################################
-#
-#   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
-# 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)
-	$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
-	$(Q) touch $@
-
-depend: .depend
-
-clean:
-	$(call DELFILE, libboard$(LIBEXT))
-	$(call CLEAN)
-
-distclean: clean
-	$(call DELFILE, Make.dep)
-	$(call DELFILE, .depend)
-
-ifneq ($(BOARD_CONTEXT),y)
-context:
-endif
-
--include Make.dep
-
diff --git a/nuttx-configs/px4fmu-v1/src/empty.c b/nuttx-configs/px4fmu-v1/src/empty.c
deleted file mode 100644
index 5de10699fb..0000000000
--- a/nuttx-configs/px4fmu-v1/src/empty.c
+++ /dev/null
@@ -1,4 +0,0 @@
-/*
- * 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/src/drivers/boards/px4fmu-v1/CMakeLists.txt b/src/drivers/boards/px4fmu-v1/CMakeLists.txt
deleted file mode 100644
index 4473cdded6..0000000000
--- a/src/drivers/boards/px4fmu-v1/CMakeLists.txt
+++ /dev/null
@@ -1,49 +0,0 @@
-############################################################################
-#
-#   Copyright (c) 2015 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.
-#
-############################################################################
-px4_add_module(
-	MODULE drivers__boards__px4fmu-v1
-	COMPILE_FLAGS
-	SRCS
-		../common/stm32/board_reset.c
-		../common/stm32/board_identity.c
-		../common/stm32/board_mcu_version.c
-		px4fmu_can.c
-		px4fmu_init.c
-		px4fmu_timer_config.c
-		px4fmu_spi.c
-		px4fmu_usb.c
-		px4fmu_led.c
-	DEPENDS
-		platforms__common
-	)
-# vim: set noet ft=cmake fenc=utf-8 ff=unix :
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
deleted file mode 100644
index c239610ce0..0000000000
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ /dev/null
@@ -1,279 +0,0 @@
-/****************************************************************************
- *
- *   Copyright (c) 2012-2016 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 board_config.h
- *
- * PX4FMUv1 internal definitions
- */
-
-#pragma once
-
-/****************************************************************************************************
- * Included Files
- ****************************************************************************************************/
-
-#include <px4_config.h>
-#include <nuttx/compiler.h>
-#include <stdint.h>
-#include <nuttx/board.h>
-
-/****************************************************************************************************
- * Definitions
- ****************************************************************************************************/
-/* Configuration ************************************************************************************/
-
-/* PX4IO connection configuration */
-#define BOARD_USES_PX4IO_VERSION       1
-#define PX4IO_SERIAL_DEVICE	"/dev/ttyS2"
-
-//#ifdef CONFIG_STM32_SPI2
-//#  error "SPI2 is not supported on this board"
-//#endif
-
-#if defined(CONFIG_STM32_CAN1)
-#  warning "CAN1 is not supported on this board"
-#endif
-
-/* PX4FMU GPIOs ***********************************************************************************/
-/* LEDs */
-
-#define GPIO_LED1		(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
-#define GPIO_LED2		(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
-
-/* External interrupts */
-#define GPIO_EXTI_COMPASS	(GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
-
-/* 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)
-
-#define PX4_SPI_BUS_SENSORS	1
-
-/*
- * Use these in place of the spi_dev_e enumeration to
- * select a specific SPI device on SPI1
- */
-#define PX4_SPIDEV_GYRO		1
-#define PX4_SPIDEV_ACCEL	2
-#define PX4_SPIDEV_MPU		3
-
-/*
- * Optional devices on IO's external port
- */
-#define PX4_SPIDEV_ACCEL_MAG	2
-
-/*
- * I2C busses
- */
-#define PX4_I2C_BUS_ESC		1
-#define PX4_I2C_BUS_ONBOARD	2
-#define PX4_I2C_BUS_EXPANSION	3
-#define PX4_I2C_BUS_LED		3
-
-/*
- * Devices on the onboard bus.
- *
- * Note that these are unshifted addresses.
- */
-#define PX4_I2C_OBDEV_HMC5883	0x1e
-#define PX4_I2C_OBDEV_EEPROM	NOTDEFINED
-#define PX4_I2C_OBDEV_LED	0x55
-
-#define PX4_I2C_OBDEV_PX4IO_BL	0x18
-#define PX4_I2C_OBDEV_PX4IO	0x1a
-
-/*
- * ADC channels
- *
- * These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
- */
-#define ADC_CHANNELS (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13)
-
-// ADC defines to be used in sensors.cpp to read from a particular channel
-#define ADC_BATTERY_VOLTAGE_CHANNEL	10
-#define ADC_BATTERY_CURRENT_CHANNEL	((uint8_t)(-1))
-#define ADC_AIRSPEED_VOLTAGE_CHANNEL	11
-
-/* Define Battery 1 Voltage Divider and A per V
- */
-
-#define BOARD_BATTERY1_V_DIV   (5.7013919372f)
-#define BOARD_BATTERY1_A_PER_V (15.391030303f)
-
-/* User GPIOs
- *
- * GPIO0-1 are the buffered high-power GPIOs.
- * GPIO2-5 are the USART2 pins.
- * GPIO6-7 are the CAN2 pins.
- */
-#define GPIO_GPIO0_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_GPIO1_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
-#define GPIO_GPIO2_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_GPIO3_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_GPIO4_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_GPIO5_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_GPIO6_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN13)
-#define GPIO_GPIO7_INPUT	(GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN2)
-#define GPIO_GPIO0_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_GPIO1_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN5)
-#define GPIO_GPIO2_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_GPIO3_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_GPIO4_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_GPIO5_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_GPIO6_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
-#define GPIO_GPIO7_OUTPUT	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
-#define GPIO_GPIO_DIR		(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
-#define BOARD_GPIO_SHARED_BUFFERED_BITS 3
-/*
- * Tone alarm output
- */
-#define TONE_ALARM_TIMER	3	/* timer 3 */
-#define TONE_ALARM_CHANNEL	3	/* channel 3 */
-#define GPIO_TONE_ALARM_IDLE	(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
-#define GPIO_TONE_ALARM		(GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
-
-/*
- * PWM
- *
- * Four PWM outputs can be configured on pins otherwise shared with
- * USART2; two can take the flow control pins if they are not being used.
- *
- * Pins:
- *
- * CTS - PA0 - TIM2CH1
- * RTS - PA1 - TIM2CH2
- * TX  - PA2 - TIM2CH3
- * RX  - PA3 - TIM2CH4
- *
- */
-#define GPIO_TIM2_CH1OUT	GPIO_TIM2_CH1OUT_1
-#define GPIO_TIM2_CH2OUT	GPIO_TIM2_CH2OUT_1
-#define GPIO_TIM2_CH3OUT	GPIO_TIM2_CH3OUT_1
-#define GPIO_TIM2_CH4OUT	GPIO_TIM2_CH4OUT_1
-#define DIRECT_PWM_OUTPUT_CHANNELS	4
-
-#define GPIO_TIM2_CH1IN		GPIO_TIM2_CH1IN_1
-#define GPIO_TIM2_CH2IN		GPIO_TIM2_CH2IN_1
-#define GPIO_TIM2_CH3IN		GPIO_TIM2_CH3IN_1
-#define GPIO_TIM2_CH4IN		GPIO_TIM2_CH4IN_1
-#define DIRECT_INPUT_TIMER_CHANNELS  4
-
-/* 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)
-
-/* High-resolution timer
- */
-#define HRT_TIMER		1	/* use timer1 for the HRT */
-#define HRT_TIMER_CHANNEL	1	/* use capture/compare channel */
-#define HRT_PPM_CHANNEL		3	/* use capture/compare channel 3 */
-#define GPIO_PPM_IN		(GPIO_ALT|GPIO_AF1|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
-
-
-#define	BOARD_NAME "PX4FMU_V1"
-
-#define BOARD_HAS_PWM	DIRECT_PWM_OUTPUT_CHANNELS
-
-#define BOARD_FMU_GPIO_TAB  { \
-		{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, \
-		{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, \
-		{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1}, \
-		{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1}, \
-		{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1}, \
-		{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1}, \
-		{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2}, \
-		{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2}, }
-
-/*
- * GPIO numbers.
- *
- * For shared pins, alternate function 1 selects the non-GPIO mode
- * (USART2, CAN2, etc.)
- */
-#define GPIO_EXT_1     (1<<0)  /**< high-power GPIO 1 */
-#define GPIO_EXT_2     (1<<1)  /**< high-power GPIO 1 */
-#define GPIO_MULTI_1   (1<<2)  /**< USART2 CTS */
-#define GPIO_MULTI_2   (1<<3)  /**< USART2 RTS */
-#define GPIO_MULTI_3   (1<<4)  /**< USART2 TX */
-#define GPIO_MULTI_4   (1<<5)  /**< USART2 RX */
-#define GPIO_CAN_TX    (1<<6)  /**< CAN2 TX */
-#define GPIO_CAN_RX    (1<<7)  /**< CAN2 RX */
-
-
-/* BOARD_HAS_MULTI_PURPOSE_GPIO defined because the board
- * has alternate uses for GPIO as noted in that the third
- * column above has entries.
- */
-#define BOARD_HAS_MULTI_PURPOSE_GPIO 1
-
-__BEGIN_DECLS
-
-/****************************************************************************************************
- * Public Types
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Public data
- ****************************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/****************************************************************************************************
- * Public Functions
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Name: stm32_spiinitialize
- *
- * Description:
- *   Called to configure SPI chip select GPIO pins for the PX4FMU board.
- *
- ****************************************************************************************************/
-
-extern void stm32_spiinitialize(void);
-#define board_spi_reset(ms)
-
-extern void stm32_usbinitialize(void);
-
-#define board_peripheral_reset(ms)
-
-#include "../common/board_common.h"
-
-#endif /* __ASSEMBLY__ */
-
-__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_can.c b/src/drivers/boards/px4fmu-v1/px4fmu_can.c
deleted file mode 100644
index b811544fea..0000000000
--- a/src/drivers/boards/px4fmu-v1/px4fmu_can.c
+++ /dev/null
@@ -1,129 +0,0 @@
-/****************************************************************************
- *
- *   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 px4fmu_can.c
- *
- * Board-specific CAN functions.
- */
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <px4_config.h>
-
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/drivers/can.h>
-#include <arch/board/board.h>
-
-#include "chip.h"
-#include "up_arch.h"
-
-#include "stm32.h"
-#include "stm32_can.h"
-#include "board_config.h"
-
-#ifdef CONFIG_CAN
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-/* Configuration ********************************************************************/
-
-#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
-#  warning "Both CAN1 and CAN2 are enabled.  Assuming only CAN1."
-#  undef CONFIG_STM32_CAN2
-#endif
-
-#ifdef CONFIG_STM32_CAN1
-#  define CAN_PORT 1
-#else
-#  define CAN_PORT 2
-#endif
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: can_devinit
- *
- * Description:
- *   All STM32 architectures must provide the following interface to work with
- *   examples/can.
- *
- ************************************************************************************/
-
-int can_devinit(void)
-{
-	static bool initialized = false;
-	struct can_dev_s *can;
-	int ret;
-
-	/* Check if we have already initialized */
-
-	if (!initialized) {
-		/* Call stm32_caninitialize() to get an instance of the CAN interface */
-
-		can = stm32_caninitialize(CAN_PORT);
-
-		if (can == NULL) {
-			canerr("ERROR:  Failed to get CAN interface\n");
-			return -ENODEV;
-		}
-
-		/* Register the CAN driver at "/dev/can0" */
-
-		ret = can_register("/dev/can0", can);
-
-		if (ret < 0) {
-			canerr("ERROR: can_register failed: %d\n", ret);
-			return ret;
-		}
-
-		/* Now we are initialized */
-
-		initialized = true;
-	}
-
-	return OK;
-}
-
-#endif
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_init.c b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
deleted file mode 100644
index a646a076dd..0000000000
--- a/src/drivers/boards/px4fmu-v1/px4fmu_init.c
+++ /dev/null
@@ -1,285 +0,0 @@
-/****************************************************************************
- *
- *   Copyright (c) 2012-2015 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 px4fmu_init.c
- *
- * PX4FMU-specific early startup code.  This file implements the
- * board_app_initialize() function that is called early by nsh during startup.
- *
- * Code here is run before the rcS script is invoked; it should start required
- * subsystems and perform board-specific initialization.
- */
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <px4_config.h>
-
-#include <stdbool.h>
-#include <stdio.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/arch.h>
-#include <nuttx/board.h>
-#include <nuttx/spi/spi.h>
-#include <nuttx/i2c/i2c_master.h>
-#include <nuttx/mmcsd.h>
-#include <nuttx/analog/adc.h>
-
-#include "stm32.h"
-#include "board_config.h"
-#include "stm32_uart.h"
-
-#include <arch/board/board.h>
-
-#include <drivers/drv_hrt.h>
-#include <drivers/drv_board_led.h>
-
-#include <systemlib/cpuload.h>
-#include <systemlib/param/param.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
-/*
- * Ideally we'd be able to get these from up_internal.h,
- * but since we want to be able to disable the NuttX use
- * of leds for system indication at will and there is no
- * separate switch, we need to build independent of the
- * CONFIG_ARCH_LEDS configuration switch.
- */
-__BEGIN_DECLS
-extern void led_init(void);
-extern void led_on(int led);
-extern void led_off(int led);
-__END_DECLS
-
-/****************************************************************************
- * Protected 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.
- *
- ************************************************************************************/
-
-__EXPORT void stm32_boardinitialize(void)
-{
-	/* configure always-on ADC pins */
-	stm32_configgpio(GPIO_ADC1_IN10);
-	stm32_configgpio(GPIO_ADC1_IN11);
-
-	/* configure SPI interfaces */
-	stm32_spiinitialize();
-
-	/* configure LEDs (empty call to NuttX' ) */
-	board_autoled_initialize();
-}
-
-/****************************************************************************
- * Name: board_app_initialize
- *
- * Description:
- *   Perform application specific initialization.  This function is never
- *   called directly from application code, but only indirectly via the
- *   (non-standard) boardctl() interface using the command BOARDIOC_INIT.
- *
- * Input Parameters:
- *   arg - The boardctl() argument is passed to the board_app_initialize()
- *         implementation without modification.  The argument has no
- *         meaning to NuttX; the meaning of the argument is a contract
- *         between the board-specific initalization logic and the the
- *         matching application logic.  The value cold be such things as a
- *         mode enumeration value, a set of DIP switch switch settings, a
- *         pointer to configuration data read from a file or serial FLASH,
- *         or whatever you would like to do with it.  Every implementation
- *         should accept zero/NULL as a default configuration.
- *
- * Returned Value:
- *   Zero (OK) is returned on success; a negated errno value is returned on
- *   any failure to indicate the nature of the failure.
- *
- ****************************************************************************/
-
-static struct spi_dev_s *spi1;
-static struct spi_dev_s *spi2;
-static struct spi_dev_s *spi3;
-
-__EXPORT int board_app_initialize(uintptr_t arg)
-{
-
-	int result;
-
-	/* IN12 and IN13 further below */
-
-#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
-
-	/* run C++ ctors before we go any further */
-
-	up_cxxinitialize();
-
-#	if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
-#  		error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
-#	endif
-
-#else
-#  error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
-#endif
-
-	/* configure the high-resolution time/callout interface */
-	hrt_init();
-
-	param_init();
-
-	/* configure CPU load estimation */
-#ifdef CONFIG_SCHED_INSTRUMENTATION
-	cpuload_initialize_once();
-#endif
-
-	/* set up the serial DMA polling */
-	static struct hrt_call serial_dma_call;
-	struct timespec ts;
-
-	/*
-	 * Poll at 1ms intervals for received bytes that have not triggered
-	 * a DMA event.
-	 */
-	ts.tv_sec = 0;
-	ts.tv_nsec = 1000000;
-
-	hrt_call_every(&serial_dma_call,
-		       ts_to_abstime(&ts),
-		       ts_to_abstime(&ts),
-		       (hrt_callout)stm32_serial_dma_poll,
-		       NULL);
-
-	/* initial LED state */
-	drv_led_start();
-	led_off(LED_AMBER);
-	led_off(LED_BLUE);
-
-
-	/* Configure SPI-based devices */
-
-	spi1 = stm32_spibus_initialize(1);
-
-	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port 1\r\n");
-		board_autoled_on(LED_AMBER);
-		return -ENODEV;
-	}
-
-	/* Default SPI1 to 1MHz and de-assert the known chip selects. */
-	SPI_SETFREQUENCY(spi1, 10000000);
-	SPI_SETBITS(spi1, 8);
-	SPI_SETMODE(spi1, SPIDEV_MODE3);
-	SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
-	SPI_SELECT(spi1, PX4_SPIDEV_ACCEL, false);
-	SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
-	up_udelay(20);
-
-	/*
-	 * If SPI2 is enabled in the defconfig, we loose some ADC pins as chip selects.
-	 * Keep the SPI2 init optional and conditionally initialize the ADC pins
-	 */
-
-#ifdef CONFIG_STM32_SPI2
-	spi2 = stm32_spibus_initialize(2);
-	/* Default SPI2 to 1MHz and de-assert the known chip selects. */
-	SPI_SETFREQUENCY(spi2, 10000000);
-	SPI_SETBITS(spi2, 8);
-	SPI_SETMODE(spi2, SPIDEV_MODE3);
-	SPI_SELECT(spi2, PX4_SPIDEV_GYRO, false);
-	SPI_SELECT(spi2, PX4_SPIDEV_ACCEL_MAG, false);
-
-	message("[boot] Initialized SPI port2 (ADC IN12/13 blocked)\n");
-#else
-	spi2 = NULL;
-	message("[boot] Enabling IN12/13 instead of SPI2\n");
-	/* no SPI2, use pins for ADC */
-	stm32_configgpio(GPIO_ADC1_IN12);
-	stm32_configgpio(GPIO_ADC1_IN13);	// jumperable to MPU6000 DRDY on some boards
-#endif
-
-	/* Get the SPI port for the microSD slot */
-
-	spi3 = stm32_spibus_initialize(3);
-
-	if (!spi3) {
-		message("[boot] FAILED to initialize SPI port 3\n");
-		board_autoled_on(LED_AMBER);
-		return -ENODEV;
-	}
-
-	/* Now bind the SPI interface to the MMCSD driver */
-	result = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi3);
-
-	if (result != OK) {
-		message("[boot] FAILED to bind SPI port 3 to the MMCSD driver\n");
-		board_autoled_on(LED_AMBER);
-		return -ENODEV;
-	}
-
-	return OK;
-}
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_led.c b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
deleted file mode 100644
index 8a92cc6e3f..0000000000
--- a/src/drivers/boards/px4fmu-v1/px4fmu_led.c
+++ /dev/null
@@ -1,116 +0,0 @@
-/****************************************************************************
- *
- *   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 px4fmu_led.c
- *
- * PX4FMU LED backend.
- */
-
-#include <px4_config.h>
-
-#include <stdbool.h>
-
-#include "stm32.h"
-#include "board_config.h"
-
-#include <arch/board/board.h>
-
-/*
- * Ideally we'd be able to get these from up_internal.h,
- * but since we want to be able to disable the NuttX use
- * of leds for system indication at will and there is no
- * separate switch, we need to build independent of the
- * CONFIG_ARCH_LEDS configuration switch.
- */
-__BEGIN_DECLS
-extern void led_init(void);
-extern void led_on(int led);
-extern void led_off(int led);
-extern void led_toggle(int led);
-__END_DECLS
-
-__EXPORT void led_init(void)
-{
-	/* Configure LED1-2 GPIOs for output */
-
-	stm32_configgpio(GPIO_LED1);
-	stm32_configgpio(GPIO_LED2);
-}
-
-__EXPORT void led_on(int led)
-{
-	if (led == 0) {
-		/* Pull down to switch on */
-		stm32_gpiowrite(GPIO_LED1, false);
-	}
-
-	if (led == 1) {
-		/* Pull down to switch on */
-		stm32_gpiowrite(GPIO_LED2, false);
-	}
-}
-
-__EXPORT void led_off(int led)
-{
-	if (led == 0) {
-		/* Pull up to switch off */
-		stm32_gpiowrite(GPIO_LED1, true);
-	}
-
-	if (led == 1) {
-		/* Pull up to switch off */
-		stm32_gpiowrite(GPIO_LED2, true);
-	}
-}
-
-__EXPORT void led_toggle(int led)
-{
-	if (led == 0) {
-		if (stm32_gpioread(GPIO_LED1)) {
-			stm32_gpiowrite(GPIO_LED1, false);
-
-		} else {
-			stm32_gpiowrite(GPIO_LED1, true);
-		}
-	}
-
-	if (led == 1) {
-		if (stm32_gpioread(GPIO_LED2)) {
-			stm32_gpiowrite(GPIO_LED2, false);
-
-		} else {
-			stm32_gpiowrite(GPIO_LED2, true);
-		}
-	}
-}
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_spi.c b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
deleted file mode 100644
index ab7af7512c..0000000000
--- a/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
+++ /dev/null
@@ -1,157 +0,0 @@
-/****************************************************************************
- *
- *   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 px4fmu_spi.c
- *
- * Board-specific SPI functions.
- */
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <px4_config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-
-#include <nuttx/spi/spi.h>
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "chip.h"
-#include "stm32.h"
-#include "board_config.h"
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: stm32_spiinitialize
- *
- * Description:
- *   Called to configure SPI chip select GPIO pins for the PX4FMU board.
- *
- ************************************************************************************/
-
-__EXPORT void stm32_spiinitialize(void)
-{
-	stm32_configgpio(GPIO_SPI_CS_GYRO);
-	stm32_configgpio(GPIO_SPI_CS_ACCEL);
-	stm32_configgpio(GPIO_SPI_CS_MPU);
-	stm32_configgpio(GPIO_SPI_CS_SDCARD);
-
-	/* De-activate all peripherals,
-	 * required for some peripheral
-	 * state machines
-	 */
-	stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
-	stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
-	stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
-	stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 1);
-}
-
-__EXPORT 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_ACCEL, !selected);
-		stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
-		stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
-		break;
-
-	case PX4_SPIDEV_MPU:
-		/* Making sure the other peripherals are not selected */
-		stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
-		stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
-		stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
-		break;
-
-	default:
-		break;
-
-	}
-}
-
-__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
-{
-	return SPI_STATUS_PRESENT;
-}
-
-
-#ifdef CONFIG_STM32_SPI2
-__EXPORT void stm32_spi2select(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) {
-		break;
-
-	default:
-		break;
-
-	}
-}
-
-__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
-{
-	return SPI_STATUS_PRESENT;
-}
-#endif
-
-
-__EXPORT 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);
-}
-
-__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
-{
-	/* this is actually bogus, but PX4 has no way to sense the presence of an SD card */
-	return SPI_STATUS_PRESENT;
-}
-
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_timer_config.c b/src/drivers/boards/px4fmu-v1/px4fmu_timer_config.c
deleted file mode 100644
index 3ee84a9ef0..0000000000
--- a/src/drivers/boards/px4fmu-v1/px4fmu_timer_config.c
+++ /dev/null
@@ -1,99 +0,0 @@
-/****************************************************************************
- *
- *   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 px4fmu_timer_config.c
- *
- * Configuration data for the stm32 pwm_servo, input capture and pwm input driver.
- *
- * Note that these arrays must always be fully-sized.
- */
-
-#include <stdint.h>
-
-#include <stm32.h>
-#include <stm32_gpio.h>
-#include <stm32_tim.h>
-
-#include <drivers/drv_pwm_output.h>
-#include <drivers/stm32/drv_io_timer.h>
-
-#include "board_config.h"
-
-__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
-	{
-		.base = STM32_TIM2_BASE,
-		.clock_register = STM32_RCC_APB1ENR,
-		.clock_bit = RCC_APB1ENR_TIM2EN,
-		.clock_freq = STM32_APB1_TIM2_CLKIN,
-		.first_channel_index = 0,
-		.last_channel_index = 3,
-		.handler = io_timer_handler0,
-		.vectorno =  STM32_IRQ_TIM2,
-	}
-};
-
-__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
-	{
-		.gpio_out = GPIO_TIM2_CH1OUT,
-		.gpio_in = GPIO_TIM2_CH1IN,
-		.timer_index = 0,
-		.timer_channel = 1,
-		.ccr_offset = STM32_GTIM_CCR1_OFFSET,
-		.masks  = GTIM_SR_CC1IF | GTIM_SR_CC1OF
-	},
-	{
-		.gpio_out = GPIO_TIM2_CH2OUT,
-		.gpio_in = GPIO_TIM2_CH2IN,
-		.timer_index = 0,
-		.timer_channel = 2,
-		.ccr_offset = STM32_GTIM_CCR2_OFFSET,
-		.masks  = GTIM_SR_CC2IF | GTIM_SR_CC2OF
-	},
-	{
-		.gpio_out = GPIO_TIM2_CH3OUT,
-		.gpio_in = GPIO_TIM2_CH3IN,
-		.timer_index = 0,
-		.timer_channel = 3,
-		.ccr_offset = STM32_GTIM_CCR3_OFFSET,
-		.masks  = GTIM_SR_CC3IF | GTIM_SR_CC3OF
-	},
-	{
-		.gpio_out = GPIO_TIM2_CH4OUT,
-		.gpio_in = GPIO_TIM2_CH4IN,
-		.timer_index = 0,
-		.timer_channel = 4,
-		.ccr_offset = STM32_GTIM_CCR4_OFFSET,
-		.masks  = GTIM_SR_CC4IF | GTIM_SR_CC4OF
-	}
-};
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_usb.c b/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
deleted file mode 100644
index 85448ef6d6..0000000000
--- a/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
+++ /dev/null
@@ -1,108 +0,0 @@
-/****************************************************************************
- *
- *   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 px4fmu_usb.c
- *
- * Board-specific USB functions.
- */
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <px4_config.h>
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-
-#include <nuttx/usb/usbdev.h>
-#include <nuttx/usb/usbdev_trace.h>
-
-#include "up_arch.h"
-#include "stm32.h"
-#include "board_config.h"
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: stm32_usbinitialize
- *
- * Description:
- *   Called to setup USB-related GPIO pins for the PX4FMU board.
- *
- ************************************************************************************/
-
-__EXPORT void stm32_usbinitialize(void)
-{
-	/* The OTG FS has an internal soft pull-up */
-
-	/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
-
-#ifdef CONFIG_STM32_OTGFS
-	stm32_configgpio(GPIO_OTGFS_VBUS);
-	/* XXX We only support device mode
-	stm32_configgpio(GPIO_OTGFS_PWRON);
-	stm32_configgpio(GPIO_OTGFS_OVER);
-	*/
-#endif
-}
-
-/************************************************************************************
- * Name:  stm32_usbsuspend
- *
- * Description:
- *   Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
- *   used.  This function is called whenever the USB enters or leaves suspend mode.
- *   This is an opportunity for the board logic to shutdown clocks, power, etc.
- *   while the USB is suspended.
- *
- ************************************************************************************/
-
-__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
-{
-	uinfo("resume: %d\n", resume);
-}
-
-- 
GitLab