summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-09-13 12:45:33 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-09-13 12:45:33 -0600
commitc33ff64a29d5dcb9893cc0a93680628c73b50bb2 (patch)
treee627d0194289539fd317189cf89c1669b77db4fa
parentb89ef0051f92dc603fadf722c048a9f30c7f7406 (diff)
downloadpx4-nuttx-c33ff64a29d5dcb9893cc0a93680628c73b50bb2.tar.gz
px4-nuttx-c33ff64a29d5dcb9893cc0a93680628c73b50bb2.tar.bz2
px4-nuttx-c33ff64a29d5dcb9893cc0a93680628c73b50bb2.zip
STM32: Support for the LeafLabs Maple and Maple Mini boards. From Librae
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/Documentation/NuttX.html9
-rw-r--r--nuttx/Documentation/README.html2
-rw-r--r--nuttx/README.txt2
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig7
-rw-r--r--nuttx/arch/arm/src/stm32/chip.h4
-rw-r--r--nuttx/configs/Kconfig14
-rw-r--r--nuttx/configs/README.txt5
-rw-r--r--nuttx/configs/maple/Kconfig30
-rw-r--r--nuttx/configs/maple/README.txt100
-rw-r--r--nuttx/configs/maple/include/board.h194
-rw-r--r--nuttx/configs/maple/nsh/Make.defs114
-rw-r--r--nuttx/configs/maple/nsh/defconfig813
-rw-r--r--nuttx/configs/maple/nsh/setenv.sh68
-rw-r--r--nuttx/configs/maple/scripts/ld.script119
-rw-r--r--nuttx/configs/maple/scripts/ld.script.dfu119
-rw-r--r--nuttx/configs/maple/src/Makefile101
-rw-r--r--nuttx/configs/maple/src/maple-internal.h123
-rw-r--r--nuttx/configs/maple/src/up_boot.c96
-rw-r--r--nuttx/configs/maple/src/up_leds.c152
-rw-r--r--nuttx/configs/maple/src/up_usbdev.c117
-rw-r--r--nuttx/configs/maple/src/up_watchdog.c137
-rw-r--r--nuttx/configs/maple/tools/dfu.sh3
-rw-r--r--nuttx/configs/maple/tools/env.sh5
-rw-r--r--nuttx/configs/maple/usbnsh/Make.defs114
-rw-r--r--nuttx/configs/maple/usbnsh/defconfig835
-rw-r--r--nuttx/configs/maple/usbnsh/setenv.sh68
27 files changed, 3352 insertions, 1 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 7b608cedd..e97ec849b 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5552,4 +5552,6 @@
Provided by Lorenz Meier (2013-9-13).
* arch/arm/src/stm32/Kconfig: Fix STM32 UART7/8 kconfig names
and UART DMA. Provided by Lorenz Meier (2013-9-13).
+ * configs/maple: Board configuration for the LeafLabs Maple
+ and Maple Mini boards. From Librae (2013-9-13).
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index f63f673a0..f08711017 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -2378,6 +2378,12 @@ nsh>
See <a href="http://firestm32.taobao.com">http://firestm32.taobao.com</a> (the current board is version 3).
Refer to the NuttX board <a href="http://sourceforge.net/p/nuttx/git/ci/master/tree/nuttx/configs/fire-stm32v2/README.txt">README</a> file for further information.
</li>
+ <li>
+ LeafLab's Maple and Maple Mini boards.
+ These boards are based on the STM32F103RBT6 chip for the standard version and on the STM32F103CBT6 for the mini version.
+ See the <a href="http://leaflabs.com/docs/hardware/maple.html">LeafLabs</a> web site for hardware information;
+ see the NuttX board <a href="http://sourceforge.net/p/nuttx/git/ci/master/tree/nuttx/configs/maple/README.txt">README</a> file for further information about the NuttX port.
+ </li>
</ol>
<p>
These ports uses a GNU arm-nuttx-elf toolchain* under either Linux or Cygwin (with native Windows GNU tools or Cygwin-based GNU tools).
@@ -2412,6 +2418,9 @@ nsh>
The ENC28J60 network is functional (but required lifting the chip select pin on the W25x16 part).
Customizations for the v3 version of the Wildfire board are selectable (but untested).
</li>
+ <li><b>Maple</b>.
+ Support for the Maple boards was contributed by Yiran Liao and first appear in NuttX 6-30.
+ </li>
</ul>
</ul>
<p>
diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html
index 0dc73c1a8..748c51622 100644
--- a/nuttx/Documentation/README.html
+++ b/nuttx/Documentation/README.html
@@ -102,6 +102,8 @@
| | | `- <a href="http://sourceforge.net/p/nuttx/git/ci/master/tree/nuttx/configs/llpc4330-xplorer/README.txt"><b><i>README.txt</i></b></a>
| | |- lpcxpresso-lpc1768/
| | | `- <a href="http://sourceforge.net/p/nuttx/git/ci/master/tree/nuttx/configs/lpcxpresso-lpc1768/README.txt"><b><i>README.txt</i></b></a>
+ | | |- maple/
+ | | | `- <a href="http://sourceforge.net/p/nuttx/git/ci/master/tree/nuttx/configs/maple/README.txt"><b><i>README.txt</i></b></a>
| | |- mbed/
| | | `- <a href="http://sourceforge.net/p/nuttx/git/ci/master/tree/nuttx/configs/mbed/README.txt"><b><i>README.txt</i></b></a>
| | |- mcu123-lpc214x/
diff --git a/nuttx/README.txt b/nuttx/README.txt
index bbe4e9845..76d2b9b19 100644
--- a/nuttx/README.txt
+++ b/nuttx/README.txt
@@ -1030,6 +1030,8 @@ nuttx
| | `- README.txt
| |- lpcxpresso-lpc1768/
| | `- README.txt
+ | |- maple/
+ | | `- README.txt
| |- mbed/
| | `- README.txt
| |- mcu123-lpc214x/
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 9e9db86b1..3708b9e7b 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -255,6 +255,13 @@ config ARCH_CHIP_STM32F103C8
select STM32_PERFORMANCELINE
select STM32_MEDIUMDENSITY
+config ARCH_CHIP_STM32F103RBT6
+ bool "STM32F103RBT6"
+ select ARCH_CORTEXM3
+ select STM32_STM32F10XX
+ select STM32_PERFORMANCELINE
+ select STM32_MEDIUMDENSITY
+
config ARCH_CHIP_STM32F103RET6
bool "STM32F103RET6"
select ARCH_CORTEXM3
diff --git a/nuttx/arch/arm/src/stm32/chip.h b/nuttx/arch/arm/src/stm32/chip.h
index 28aeca1a0..de80415d1 100644
--- a/nuttx/arch/arm/src/stm32/chip.h
+++ b/nuttx/arch/arm/src/stm32/chip.h
@@ -70,7 +70,9 @@
# include "chip/stm32f100_pinmap.h"
/* STM32 F103 Low / Medium Density Family */
-# elif defined(CONFIG_ARCH_CHIP_STM32F103C4) || defined(CONFIG_ARCH_CHIP_STM32F103C8)
+# elif defined(CONFIG_ARCH_CHIP_STM32F103C4) || \
+ defined(CONFIG_ARCH_CHIP_STM32F103C8) || \
+ defined(CONFIG_ARCH_CHIP_STM32F103RBT6)
# include "chip/stm32f103c_pinmap.h"
/* STM32 F103 High Density Family */
diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig
index 1d14ea033..3a9672204 100644
--- a/nuttx/configs/Kconfig
+++ b/nuttx/configs/Kconfig
@@ -529,6 +529,16 @@ config ARCH_BOARD_SKP16C26
uses the GNU m32c toolchain. STATUS: The port is complete but untested
due to issues with compiler internal errors.
+config ARCH_BOARD_MAPLE
+ bool "maple board"
+ depends on ARCH_CHIP_STM32F103RBT6
+ select ARCH_HAVE_LEDS
+ ---help---
+ A configuration for the LeafLab's Maple and Maple Mini boards.
+ These boards are based on the STM32F103RBT6 chip for the standard
+ version and on the STM32F103CBT6 for the mini version
+ (See http://leaflabs.com/docs/hardware/maple.html)
+
config ARCH_BOARD_STM32_TINY
bool "STM32-Tiny board"
depends on ARCH_CHIP_STM32F103C8
@@ -812,6 +822,7 @@ config ARCH_BOARD
default "sam4s-xplained" if ARCH_BOARD_SAM4S_XPLAINED
default "shenzhou" if ARCH_BOARD_SHENZHOU
default "skp16c26" if ARCH_BOARD_SKP16C26
+ default "maple" if ARCH_BOARD_MAPLE
default "stm32_tiny" if ARCH_BOARD_STM32_TINY
default "stm3210e-eval" if ARCH_BOARD_STM3210E_EVAL
default "stm3220g-eval" if ARCH_BOARD_STM3220G_EVAL
@@ -1048,6 +1059,9 @@ endif
if ARCH_BOARD_SKP16C26
source "configs/skp16c26/Kconfig"
endif
+if ARCH_BOARD_MAPLE
+source "configs/maple/Kconfig"
+endif
if ARCH_BOARD_STM32_TINY
source "configs/stm32_tiny/Kconfig"
endif
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index c8237de02..d4610c894 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -1815,6 +1815,11 @@ configs/m68322evb
Motorola. This OS is also built with the arm-nuttx-elf toolchain*. STATUS:
This port was never completed.
+configs/maple
+ NuttX support for the LeafLab's Maple and Maple Mini boards. These boards
+ are based on the STM32F103RBT6 chip for the standard version and on the
+ STM32F103CBT6 for the mini version (See http://leaflabs.com/docs/hardware/maple.html)
+
configs/mbed
The configurations in this directory support the mbed board (http://mbed.org)
that features the NXP LPC1768 microcontroller. This OS is also built
diff --git a/nuttx/configs/maple/Kconfig b/nuttx/configs/maple/Kconfig
new file mode 100644
index 000000000..bcc7b30ef
--- /dev/null
+++ b/nuttx/configs/maple/Kconfig
@@ -0,0 +1,30 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+if ARCH_BOARD_MAPLE
+
+choice
+ prompt "Select board type"
+ default MAPLE_STANDARD
+ ---help---
+ Select the board hosting the architure. You must first select the
+ exact MCU part number, then the boards supporting that part will
+ be available for selection. Use ARCH_BOARD_CUSTOM to create a new
+ board configuration.
+
+config MAPLE_STANDARD
+ bool "Maple"
+ ---help---
+ This version is the standard maple board, with STM32F103RBT6.
+
+config MAPLE_MINI
+ bool "Maple Mini"
+ ---help---
+ This version is a mini layout of the normal one, with STM32F103CBT6.
+ It has different bootloader, memory size, and pin layout.
+
+endchoice
+
+endif
diff --git a/nuttx/configs/maple/README.txt b/nuttx/configs/maple/README.txt
new file mode 100644
index 000000000..893fe980e
--- /dev/null
+++ b/nuttx/configs/maple/README.txt
@@ -0,0 +1,100 @@
+README
+======
+
+This README discusses issues unique to NuttX configurations for the
+maple board from LeafLabs (http://leaflabs.com).
+
+Microprocessor: 32-bit ARM Cortex M3 at 72MHz STM32F103RBT6 (STM32F103CBT6 for mini version)
+Memory: 120 KB Flash and 20 KB SRAM
+I/O Pins Out: 43 (34 for mini version)
+ADCs: 9 (at 12-bit resolution)
+Peripherals: 4 timers, 2 I2Cs, 2 SPI ports, 3 USARTs
+Other: Sleep, stop, and standby modes; serial wire debug and JTAG interfaces
+
+Please see below link for a list of maple devices and documentations.
+
+ http://leaflabs.com/devices
+ http://leaflabs.com/docs
+
+This config supports Maple and Maple Mini.
+
+Contents
+========
+
+ - Development Environment
+ - DFU
+
+Development Environment
+=======================
+
+ Either Linux (recommended), Mac or Cygwin on Windows can be used for the development environment.
+ The source has been built only using the GNU toolchain (see below). Other
+ toolchains will likely cause problems. Testing was performed using the Cygwin
+ environment because the Raisonance R-Link emulatator and some RIDE7 development tools
+ were used and those tools works only under Windows.
+
+DFU
+===
+
+ The linker files in these projects can be configured to indicate that you
+ will be loading code using STMicro built-in USB Device Firmware Upgrade (DFU)
+ loader or via some JTAG emulator. You can specify the DFU bootloader by
+ adding the following line:
+
+ CONFIG_STM32_DFU=y
+
+ to your .config file. Most of the configurations in this directory are set
+ up to use the DFU loader.
+
+ If CONFIG_STM32_DFU is defined, the code will not be positioned at the beginning
+ of FLASH (0x08000000) but will be offset to 0x08005000. This offset is needed
+ to make space for the DFU loader and 0x08005000 is where the DFU loader expects
+ to find new applications at boot time. If you need to change that origin for some
+ other bootloader, you will need to edit the file(s) ld.script.dfu for each
+ configuration. In LeafLabs case, we are using maple bootloader:
+
+ http://leaflabs.com/docs/bootloader.html
+
+ For Linux or Mac:
+ ----------------
+
+ While on Linux or Mac, we can use dfu-util to upload nuttx binary.
+
+ 1. Make sure we have installed dfu-util. (From yum, apt-get or build from source.)
+ 2. Start the DFU loader (bootloader) on the maple board. You do this by
+ resetting the board while holding the "Key" button. Windows should
+ recognize that the DFU loader has been installed.
+ 3. Flash the nuttx.bin to the board use dfu-util. Here's an example:
+
+ $ dfu-util -a1 -d 1eaf:0003 -D nuttx.bin -R
+
+ For anything not clear, we can refer to LeafLabs official document:
+
+ http://leaflabs.com/docs/unix-toolchain.html
+
+ For Windows:
+ -----------
+
+ The DFU SE PC-based software is available from the STMicro website,
+ http://www.st.com. General usage instructions:
+
+ 1. Connect the maple board to your computer using a USB
+ cable.
+ 2. Start the DFU loader on the maple board. You do this by
+ resetting the board while holding the "Key" button. Windows should
+ recognize that the DFU loader has been installed.
+ 3. Run the DFU SE program to load nuttx.bin into FLASH.
+
+ What if the DFU loader is not in FLASH? The loader code is available
+ inside of the Demo dirctory of the USBLib ZIP file that can be downloaded
+ from the STMicro Website. You can build it using RIDE (or other toolchains);
+ you will need a JTAG emulator to burn it into FLASH the first time.
+
+ In order to use STMicro's built-in DFU loader, you will have to get
+ the NuttX binary into a special format with a .dfu extension. The
+ DFU SE PC_based software installation includes a file "DFU File Manager"
+ conversion program that a file in Intel Hex format to the special DFU
+ format. When you successfully build NuttX, you will find a file called
+ nutt.hex in the top-level directory. That is the file that you should
+ provide to the DFU File Manager. You will end up with a file called
+ nuttx.dfu that you can use with the STMicro DFU SE program.
diff --git a/nuttx/configs/maple/include/board.h b/nuttx/configs/maple/include/board.h
new file mode 100644
index 000000000..91e92f9d8
--- /dev/null
+++ b/nuttx/configs/maple/include/board.h
@@ -0,0 +1,194 @@
+/************************************************************************************
+ * configs/maple/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
+ * Librae <librae8226@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __CONFIGS_MAPLE_INCLUDE_BOARD_H
+#define __CONFIGS_MAPLE_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 *************************************************************************/
+
+/* On-board crystal frequency is 8MHz (HSE) */
+
+#define STM32_BOARD_XTAL 8000000ul
+
+/* PLL source is HSE/1, PLL multipler is 9: PLL frequency is 8MHz (XTAL) x 9 = 72MHz */
+
+#define STM32_CFGR_PLLSRC RCC_CFGR_PLLSRC
+#define STM32_CFGR_PLLXTPRE 0
+#define STM32_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx9
+#define STM32_PLL_FREQUENCY (9*STM32_BOARD_XTAL)
+
+/* Use the PLL and set the SYSCLK source to be the PLL */
+
+#define STM32_SYSCLK_SW RCC_CFGR_SW_PLL
+#define STM32_SYSCLK_SWS RCC_CFGR_SWS_PLL
+#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY
+
+/* AHB clock (HCLK) is SYSCLK (72MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
+#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB2 clock (PCLK2) is HCLK (72MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
+
+/* APB2 timers 1 and 8 will receive PCLK2. */
+
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* APB1 clock (PCLK1) is HCLK/2 (36MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* APB1 timers 2-4 will be twice PCLK1 (I presume the remaining will receive 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 (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (STM32_PCLK1_FREQUENCY)
+
+/* USB divider -- Divide PLL clock by 1.5 */
+
+#define STM32_CFGR_USBPRE 0
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
+ * otherwise frequency is 2xAPBx.
+ * Note: TIM1,8 are on APB2, others on APB1 */
+
+#define STM32_TIM18_FREQUENCY STM32_HCLK_FREQUENCY
+#define STM32_TIM27_FREQUENCY STM32_HCLK_FREQUENCY
+
+/* SDIO dividers. Note that slower clocking is required when DMA is disabled
+ * in order to avoid RX overrun/TX underrun errors due to delayed responses
+ * to service FIFOs in interrupt driven mode. These values have not been
+ * tuned!!!
+ *
+ * HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz
+ */
+
+#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT)
+
+/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz
+ * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
+ */
+
+#ifdef CONFIG_SDIO_DMA
+# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
+#else
+# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz
+ * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
+ */
+
+#ifdef CONFIG_SDIO_DMA
+# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
+#else
+# define SDIO_SDXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* LED definitions ******************************************************************/
+
+/* The board has only one controllable LED */
+#define LED_STARTED 0 /* No LEDs */
+#define LED_HEAPALLOCATE 1 /* LED1 on */
+#define LED_IRQSENABLED 2 /* LED2 on */
+#define LED_STACKCREATED 3 /* LED1 on */
+#define LED_INIRQ 4 /* LED1 off */
+#define LED_SIGNAL 5 /* LED2 on */
+#define LED_ASSERTION 6 /* LED1 + LED2 */
+#define LED_PANIC 7 /* LED1 / LED2 blinking */
+
+/************************************************************************************
+ * 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 initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_MAPLE_INCLUDE_BOARD_H */
diff --git a/nuttx/configs/maple/nsh/Make.defs b/nuttx/configs/maple/nsh/Make.defs
new file mode 100644
index 000000000..6daa950b7
--- /dev/null
+++ b/nuttx/configs/maple/nsh/Make.defs
@@ -0,0 +1,114 @@
+############################################################################
+# configs/maple/nsh/Make.defs
+#
+# 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}/.config
+include ${TOPDIR}/tools/Config.mk
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+ifeq ($(CONFIG_STM32_DFU),y)
+ LDSCRIPT = ld.script.dfu
+else
+ LDSCRIPT = ld.script
+endif
+
+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)}"
+ MAXOPTIMIZATION = -O2
+else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+endif
+
+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
+
+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}
+
+ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
+ ARCHOPTIMIZATION = -g -Os
+else
+ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
+endif
+
+ARCHCFLAGS = -fno-builtin
+ARCHCXXFLAGS = -fno-builtin -fno-exceptions
+ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
+ARCHWARNINGSXX = -Wall -Wshadow
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+ifneq ($(CROSSDEV),arm-nuttx-elf-)
+ LDFLAGS += -nostartfiles -nodefaultlibs
+endif
+ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
+ LDFLAGS += -g
+endif
+
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
diff --git a/nuttx/configs/maple/nsh/defconfig b/nuttx/configs/maple/nsh/defconfig
new file mode 100644
index 000000000..7d32bd5be
--- /dev/null
+++ b/nuttx/configs/maple/nsh/defconfig
@@ -0,0 +1,813 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+CONFIG_NUTTX_NEWCONFIG=y
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL 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_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
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDBOOL_H is not set
+# CONFIG_ARCH_MATH_H is not set
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+# CONFIG_DEBUG is not set
+# CONFIG_DEBUG_SYMBOLS is not set
+
+#
+# System Type
+#
+# CONFIG_ARCH_8051 is not set
+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_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_IMX 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_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_SAM34 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X 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=y
+# CONFIG_ARCH_CORTEXM4 is not set
+# CONFIG_ARCH_CORTEXA5 is not set
+# CONFIG_ARCH_CORTEXA8 is not set
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+# CONFIG_ARMV7M_USEBASEPRI is not set
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+# CONFIG_ARMV7M_CMNVECTOR is not set
+# CONFIG_ARCH_HAVE_FPU is not set
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARMV7M_MPU is not set
+
+#
+# ARMV7M Configuration Options
+#
+# 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_SERIAL_TERMIOS is not set
+
+#
+# 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_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_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+CONFIG_ARCH_CHIP_STM32F103RBT6=y
+# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
+# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG 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_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_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# 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_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+CONFIG_STM32_STM32F10XX=y
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+CONFIG_STM32_PERFORMANCELINE=y
+# CONFIG_STM32_HIGHDENSITY is not set
+CONFIG_STM32_MEDIUMDENSITY=y
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F30XX is not set
+# CONFIG_STM32_STM32F40XX is not set
+CONFIG_STM32_DFU=y
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKP is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_DMA1 is not set
+# CONFIG_STM32_DMA2 is not set
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=y
+# CONFIG_STM32_PWR is not set
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+# CONFIG_STM32_TIM4 is not set
+# CONFIG_STM32_TIM5 is not set
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_USART1=y
+# CONFIG_STM32_USART2 is not set
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+CONFIG_STM32_USB=y
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_WWDG is not set
+CONFIG_STM32_I2C=y
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_I2C1_REMAP is not set
+# CONFIG_STM32_USART1_REMAP is not set
+CONFIG_STM32_JTAG_DISABLE=y
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+# CONFIG_STM32_JTAG_SW_ENABLE is not set
+# CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG is not set
+# CONFIG_STM32_FORCEPOWER is not set
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+# CONFIG_SERIAL_DISABLE_REORDERING is not set
+# CONFIG_STM32_USART_SINGLEWIRE is not set
+
+#
+# I2C Configuration
+#
+# CONFIG_STM32_I2C_DYNTIMEO is not set
+CONFIG_STM32_I2CTIMEOSEC=1
+CONFIG_STM32_I2CTIMEOMS=500
+CONFIG_STM32_I2CTIMEOTICKS=500
+# CONFIG_STM32_I2C_DUTY16_9 is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+# CONFIG_ARCH_DMA is not set
+CONFIG_ARCH_IRQPRIO=y
+# CONFIG_CUSTOM_STACK is not set
+# CONFIG_ADDRENV is not set
+CONFIG_ARCH_HAVE_VFORK=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG 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=5483
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=0
+
+#
+# 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=20480
+
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_MAPLE=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="maple"
+
+#
+# Common Board Options
+#
+CONFIG_ARCH_HAVE_LEDS=y
+CONFIG_ARCH_LEDS=y
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+CONFIG_MAPLE_STANDARD=y
+# CONFIG_MAPLE_MINI is not set
+
+#
+# RTOS Features
+#
+# CONFIG_BOARD_INITIALIZE is not set
+CONFIG_MSEC_PER_TICK=10
+CONFIG_RR_INTERVAL=200
+# CONFIG_SCHED_INSTRUMENTATION is not set
+CONFIG_TASK_NAME_SIZE=0
+# CONFIG_SCHED_HAVE_PARENT is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=2009
+CONFIG_START_MONTH=10
+CONFIG_START_DAY=23
+CONFIG_DEV_CONSOLE=y
+# CONFIG_MUTEX_TYPES is not set
+# CONFIG_PRIORITY_INHERITANCE is not set
+# CONFIG_FDCLONE_DISABLE is not set
+# CONFIG_FDCLONE_STDIO is not set
+CONFIG_SDCLONE_DISABLE=y
+# CONFIG_SCHED_WAITPID is not set
+# CONFIG_SCHED_STARTHOOK is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nsh_main"
+# CONFIG_DISABLE_OS_API is not set
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+
+#
+# Sizes of configurable things (0 disables)
+#
+CONFIG_MAX_TASKS=16
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=4
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=8
+CONFIG_NAME_MAX=32
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=4
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=2048
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+
+#
+# Device Drivers
+#
+CONFIG_DISABLE_POLL=y
+CONFIG_DEV_NULL=y
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_PWM is not set
+CONFIG_I2C=y
+# CONFIG_I2C_SLAVE is not set
+CONFIG_I2C_TRANSFER=y
+# CONFIG_I2C_WRITEREAD is not set
+# CONFIG_I2C_POLLED is not set
+# CONFIG_I2C_TRACE is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_I2C_RESET is not set
+# CONFIG_SPI is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+# CONFIG_MTD is not set
+# CONFIG_PIPES is not set
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+CONFIG_SERIAL=y
+# CONFIG_DEV_LOWCONSOLE is not set
+# CONFIG_16550_UART is not set
+CONFIG_ARCH_HAVE_USART1=y
+
+#
+# USART Configuration
+#
+CONFIG_USART1_ISUART=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+CONFIG_USART1_SERIAL_CONSOLE=y
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=256
+CONFIG_USART1_TXBUFSIZE=256
+CONFIG_USART1_BAUD=115200
+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_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL 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=y
+# CONFIG_USBDEV_BUSPOWERED is not set
+CONFIG_USBDEV_MAXPOWER=100
+# CONFIG_USBDEV_DMA is not set
+CONFIG_USBDEV_TRACE=y
+CONFIG_USBDEV_TRACE_NRECORDS=32
+# CONFIG_USBDEV_TRACE_STRINGS is not set
+
+#
+# USB Device Class Driver Options
+#
+# CONFIG_USBDEV_COMPOSITE is not set
+# CONFIG_PL2303 is not set
+# CONFIG_CDCACM is not set
+# CONFIG_USBMSC is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+
+#
+# Networking Support
+#
+# CONFIG_NET is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_RAMMAP is not set
+# CONFIG_FS_FAT is not set
+# CONFIG_FS_NXFFS is not set
+# CONFIG_FS_ROMFS is not set
+# CONFIG_FS_SMARTFS is not set
+# CONFIG_FS_BINFS is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG_ENABLE is not set
+# CONFIG_SYSLOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=1
+# CONFIG_GRAN is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Formats
+#
+# 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=y
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_LIBM is not set
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+# CONFIG_LIBC_FLOATINGPOINT is not set
+CONFIG_LIB_RAND_ORDER=2
+# 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 is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_LIB_SENDFILE_BUFSIZE=512
+# CONFIG_ARCH_ROMGETC is not set
+# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
+
+#
+# Non-standard Library Support
+#
+# CONFIG_SCHED_WORKQUEUE is not set
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+# CONFIG_HAVE_CXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CC3000BASIC is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF 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_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_LCDRW is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+# CONFIG_EXAMPLES_MOUNT is not set
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+CONFIG_EXAMPLES_NSH=y
+# CONFIG_EXAMPLES_NULL is not set
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXCONSOLE is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PASHELLO is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART 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_UDP is not set
+# CONFIG_EXAMPLES_UIP is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBMSC is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_DHCPC is not set
+# CONFIG_NETUTILS_DHCPD is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_FTPD is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_RESOLV is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TELNETD is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_UIPLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_BUILTIN_APPS=y
+
+#
+# Disable Individual commands
+#
+# 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_DD 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 is not set
+# CONFIG_NSH_DISABLE_KILL is not set
+# CONFIG_NSH_DISABLE_LOSETUP is not set
+# 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_MW is not set
+# CONFIG_NSH_DISABLE_NSFMOUNT is not set
+# CONFIG_NSH_DISABLE_PS is not set
+# CONFIG_NSH_DISABLE_PING 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_TEST is not set
+# CONFIG_NSH_DISABLE_UMOUNT is not set
+# CONFIG_NSH_DISABLE_UNSET is not set
+# CONFIG_NSH_DISABLE_USLEEP is not set
+# CONFIG_NSH_DISABLE_WGET is not set
+# CONFIG_NSH_DISABLE_XD is not set
+
+#
+# Configure Command Options
+#
+# CONFIG_NSH_CMDOPT_DF_H is not set
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=1024
+CONFIG_NSH_LINELEN=80
+CONFIG_NSH_MAXARGUMENTS=6
+CONFIG_NSH_NESTDEPTH=3
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_CONSOLE=y
+# CONFIG_NSH_USBCONSOLE is not set
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_USBDEV_TRACE is not set
+# CONFIG_NSH_CONDEV is not set
+# CONFIG_NSH_ARCHINIT is not set
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+CONFIG_SYSTEM_I2CTOOL=y
+CONFIG_I2CTOOL_MINBUS=1
+CONFIG_I2CTOOL_MAXBUS=2
+CONFIG_I2CTOOL_MINADDR=0x0
+CONFIG_I2CTOOL_MAXADDR=0xf0
+CONFIG_I2CTOOL_MAXREGADDR=0xff
+CONFIG_I2CTOOL_DEFFREQ=100000
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# RAM test
+#
+# CONFIG_SYSTEM_RAMTEST is not set
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sysinfo
+#
+CONFIG_SYSTEM_SYSINFO=y
+
+#
+# USB Monitor
+#
+# CONFIG_SYSTEM_USBMONITOR is not set
+
+#
+# Zmodem Commands
+#
+# CONFIG_SYSTEM_ZMODEM is not set
diff --git a/nuttx/configs/maple/nsh/setenv.sh b/nuttx/configs/maple/nsh/setenv.sh
new file mode 100644
index 000000000..314245ad8
--- /dev/null
+++ b/nuttx/configs/maple/nsh/setenv.sh
@@ -0,0 +1,68 @@
+#!/bin/bash
+# configs/maple/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
+
+export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+
+export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# This is the path to the LM3S6995-EK tools directory
+
+export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
+
+# Update the PATH variable
+
+export PATH="${BUILDROOT_BIN}:${TOOL_BIN:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/maple/scripts/ld.script b/nuttx/configs/maple/scripts/ld.script
new file mode 100644
index 000000000..8fe3ae43f
--- /dev/null
+++ b/nuttx/configs/maple/scripts/ld.script
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * configs/maple/scripts/ld.script
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Librae <librae8226@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* The STM32F103xB has 128Kb of FLASH beginning at address 0x0800:0000 and
+ * 20Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH,
+ * FLASH memory is aliased to address 0x0000:0000 where the code expects to
+ * begin execution by jumping to the entry point in the 0x0800:0000 address
+ * range.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(_stext)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ *(.init_array .init_array.*)
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/maple/scripts/ld.script.dfu b/nuttx/configs/maple/scripts/ld.script.dfu
new file mode 100644
index 000000000..e69140c88
--- /dev/null
+++ b/nuttx/configs/maple/scripts/ld.script.dfu
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * configs/maple/scripts/ld.script.dfu
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Librae <librae8226@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* The STM32F103xB has 128Kb of FLASH beginning at address 0x0800:0000 and
+ * 20Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
+ * maple's DFU bootloader is being used. In that case, the correct
+ * load .text load address is 0x0800:5000 (leaving 108Kb).
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08005000, LENGTH = 108K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(_stext)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ *(.init_array .init_array.*)
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ /* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/maple/src/Makefile b/nuttx/configs/maple/src/Makefile
new file mode 100644
index 000000000..3f8cb2495
--- /dev/null
+++ b/nuttx/configs/maple/src/Makefile
@@ -0,0 +1,101 @@
+############################################################################
+# configs/maple/src/Makefile
+#
+# Copyright (C) 2013 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+# Librae <librae8226@gmail.com>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = up_boot.c up_leds.c up_usbdev.c
+
+ifeq ($(CONFIG_NX_LCDDRIVER),y)
+endif
+
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+endif
+
+ifeq ($(CONFIG_INPUT),y)
+endif
+
+ifeq ($(CONFIG_USBMSC),y)
+endif
+
+ifeq ($(CONFIG_WATCHDOG),y)
+ CSRCS += up_watchdog.c
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+ else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(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)
+
+-include Make.dep
diff --git a/nuttx/configs/maple/src/maple-internal.h b/nuttx/configs/maple/src/maple-internal.h
new file mode 100644
index 000000000..346084a98
--- /dev/null
+++ b/nuttx/configs/maple/src/maple-internal.h
@@ -0,0 +1,123 @@
+/************************************************************************************
+ * configs/maple/src/maple-internal.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Laurent Latil <laurent@latil.nom.fr>
+ * Librae <librae8226@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __CONFIGS_MAPLE_SRC_MAPLE_INTERNAL_H
+#define __CONFIGS_MAPLE_SRC_MAPLE_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* How many SPI modules does this chip support? The LM3S6918 supports 2 SPI
+ * modules (others may support more -- in such case, the following must be
+ * expanded).
+ */
+
+#if STM32_NSPI < 1
+# undef CONFIG_STM32_SPI1
+# undef CONFIG_STM32_SPI2
+#elif STM32_NSPI < 2
+# undef CONFIG_STM32_SPI2
+#endif
+
+/* GPIOs **************************************************************/
+
+#ifdef CONFIG_MAPLE_MINI
+#define GPIO_LED (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_USB_PULLUP (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
+#else
+#define GPIO_LED (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_USB_PULLUP (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN12)
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins.
+ *
+ ************************************************************************************/
+
+void stm32_spiinitialize(void);
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void);
+
+/************************************************************************************
+ * Name: up_wlinitialize
+ *
+ * Description:
+ * Called to configure wireless module (nRF24L01).
+ *
+ ************************************************************************************/
+
+void up_wlinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_MAPLE_SRC_MAPLE_INTERNAL_H */
diff --git a/nuttx/configs/maple/src/up_boot.c b/nuttx/configs/maple/src/up_boot.c
new file mode 100644
index 000000000..868e7a6d9
--- /dev/null
+++ b/nuttx/configs/maple/src/up_boot.c
@@ -0,0 +1,96 @@
+/************************************************************************************
+ * configs/maple/src/up_boot.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Librae <librae8226@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/spi/spi.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "maple-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void)
+{
+ /* Configure on-board LEDs if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
+
+ /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
+ * stm32_spiinitialize() has been brought into the link.
+ */
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)
+ stm32_spiinitialize();
+#endif
+
+ /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
+ * disabled, and 3) the weak function stm32_usbinitialize() has been brought
+ * into the build.
+ */
+
+#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB)
+ stm32_usbinitialize();
+#endif
+}
diff --git a/nuttx/configs/maple/src/up_leds.c b/nuttx/configs/maple/src/up_leds.c
new file mode 100644
index 000000000..638d506e5
--- /dev/null
+++ b/nuttx/configs/maple/src/up_leds.c
@@ -0,0 +1,152 @@
+/****************************************************************************
+ * configs/maple/src/up_leds.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Librae <librae8226@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32.h"
+#include "maple-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
+ */
+
+#ifdef CONFIG_DEBUG_LEDS
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static inline void set_led(bool v)
+{
+ ledvdbg("Turn LED %s\n", v? "on":"off");
+ stm32_gpiowrite(GPIO_LED, v);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+ /* Configure LED GPIO for output */
+
+ stm32_configgpio(GPIO_LED);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ ledvdbg("up_ledon(%d)\n", led);
+ switch (led)
+ {
+ case LED_STARTED:
+ case LED_HEAPALLOCATE:
+ /* As the board provides only one soft controllable LED, we simply turn
+ * it on when the board boots
+ */
+
+ set_led(true);
+ break;
+
+ case LED_PANIC:
+ /* For panic state, the LED is blinking */
+
+ set_led(true);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ ledvdbg("up_ledoff(%d)\n", led);
+
+ switch (led)
+ {
+ case LED_STARTED:
+ case LED_PANIC:
+ /* For panic state, the LED is blinking */
+
+ set_led(false);
+ break;
+
+ default:
+ break;
+ }
+}
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/maple/src/up_usbdev.c b/nuttx/configs/maple/src/up_usbdev.c
new file mode 100644
index 000000000..cc10cece4
--- /dev/null
+++ b/nuttx/configs/maple/src/up_usbdev.c
@@ -0,0 +1,117 @@
+/************************************************************************************
+ * configs/maple/src/up_usbdev.c
+ *
+ * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Librae <librae8226@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "up_arch.h"
+#include "stm32.h"
+#include "maple-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void)
+{
+ ulldbg("called\n");
+
+ /* USB Soft Connect Pullup */
+
+ stm32_configgpio(GPIO_USB_PULLUP);
+}
+
+/************************************************************************************
+ * Name: stm32_usbpullup
+ *
+ * Description:
+ * If USB is supported and the board supports a pullup via GPIO (for USB software
+ * connect and disconnect), then the board software must provide stm32_pullup.
+ * See include/nuttx/usb/usbdev.h for additional description of this method.
+ * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be
+ * NULL.
+ *
+ ************************************************************************************/
+
+int stm32_usbpullup(FAR struct usbdev_s *dev, bool enable)
+{
+ usbtrace(TRACE_DEVPULLUP, (uint16_t)enable);
+ stm32_gpiowrite(GPIO_USB_PULLUP, !enable);
+ return OK;
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
diff --git a/nuttx/configs/maple/src/up_watchdog.c b/nuttx/configs/maple/src/up_watchdog.c
new file mode 100644
index 000000000..c587fe69d
--- /dev/null
+++ b/nuttx/configs/maple/src/up_watchdog.c
@@ -0,0 +1,137 @@
+/************************************************************************************
+ * configs/maple/src/up_watchdog.c
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/watchdog.h>
+#include <arch/board/board.h>
+
+#include "stm32_wdg.h"
+
+#ifdef CONFIG_WATCHDOG
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration *******************************************************************/
+/* Wathdog hardware should be enabled */
+
+#if !defined(CONFIG_STM32_WWDG) && !defined(CONFIG_STM32_IWDG)
+# warning "One of CONFIG_STM32_WWDG or CONFIG_STM32_IWDG must be defined"
+#endif
+
+/* Select the path to the registered watchdog timer device */
+
+#ifndef CONFIG_STM32_WDG_DEVPATH
+# ifdef CONFIG_EXAMPLES_WATCHDOG_DEVPATH
+# define CONFIG_STM32_WDG_DEVPATH CONFIG_EXAMPLES_WATCHDOG_DEVPATH
+# else
+# define CONFIG_STM32_WDG_DEVPATH "/dev/watchdog0"
+# endif
+#endif
+
+/* Use the un-calibrated LSI frequency if we have nothing better */
+
+#if defined(CONFIG_STM32_IWDG) && !defined(CONFIG_STM32_LSIFREQ)
+# define CONFIG_STM32_LSIFREQ STM32_LSI_FREQUENCY
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing the watchdog timer */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_WATCHDOG
+#endif
+
+#ifdef CONFIG_DEBUG_WATCHDOG
+# define wdgdbg dbg
+# define wdglldbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define wdgvdbg vdbg
+# define wdgllvdbg llvdbg
+# else
+# define wdgvdbg(x...)
+# define wdgllvdbg(x...)
+# endif
+#else
+# define wdgdbg(x...)
+# define wdglldbg(x...)
+# define wdgvdbg(x...)
+# define wdgllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: up_wdginitialize()
+ *
+ * Description:
+ * Perform architecuture-specific initialization of the Watchdog hardware.
+ * This interface must be provided by all configurations using
+ * apps/examples/watchdog
+ *
+ ****************************************************************************/
+
+int up_wdginitialize(void)
+{
+ /* Initialize tha register the watchdog timer device */
+
+#if defined(CONFIG_STM32_WWDG)
+ stm32_wwdginitialize(CONFIG_STM32_WDG_DEVPATH);
+ return OK;
+
+#elif defined(CONFIG_STM32_IWDG)
+ stm32_iwdginitialize(CONFIG_STM32_WDG_DEVPATH, CONFIG_STM32_LSIFREQ);
+ return OK;
+
+#else
+ return -ENODEV;
+#endif
+}
+
+#endif /* CONFIG_WATCHDOG */
diff --git a/nuttx/configs/maple/tools/dfu.sh b/nuttx/configs/maple/tools/dfu.sh
new file mode 100644
index 000000000..4ca7e0eb1
--- /dev/null
+++ b/nuttx/configs/maple/tools/dfu.sh
@@ -0,0 +1,3 @@
+#!/bin/bash
+
+dfu-util -a1 -d 1eaf:0003 -D nuttx.bin -R
diff --git a/nuttx/configs/maple/tools/env.sh b/nuttx/configs/maple/tools/env.sh
new file mode 100644
index 000000000..91a15810a
--- /dev/null
+++ b/nuttx/configs/maple/tools/env.sh
@@ -0,0 +1,5 @@
+#!/bin/bash
+
+cd tools
+./configure.sh maple/$1
+cd - > /dev/null
diff --git a/nuttx/configs/maple/usbnsh/Make.defs b/nuttx/configs/maple/usbnsh/Make.defs
new file mode 100644
index 000000000..03f4533f3
--- /dev/null
+++ b/nuttx/configs/maple/usbnsh/Make.defs
@@ -0,0 +1,114 @@
+############################################################################
+# configs/maple/usbnsh/Make.defs
+#
+# 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}/.config
+include ${TOPDIR}/tools/Config.mk
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+ifeq ($(CONFIG_STM32_DFU),y)
+ LDSCRIPT = ld.script.dfu
+else
+ LDSCRIPT = ld.script
+endif
+
+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)}"
+ MAXOPTIMIZATION = -O2
+else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+endif
+
+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
+
+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}
+
+ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
+ ARCHOPTIMIZATION = -g -Os
+else
+ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
+endif
+
+ARCHCFLAGS = -fno-builtin
+ARCHCXXFLAGS = -fno-builtin -fno-exceptions
+ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
+ARCHWARNINGSXX = -Wall -Wshadow
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+ifneq ($(CROSSDEV),arm-nuttx-elf-)
+ LDFLAGS += -nostartfiles -nodefaultlibs
+endif
+ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
+ LDFLAGS += -g
+endif
+
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
diff --git a/nuttx/configs/maple/usbnsh/defconfig b/nuttx/configs/maple/usbnsh/defconfig
new file mode 100644
index 000000000..406a73d2a
--- /dev/null
+++ b/nuttx/configs/maple/usbnsh/defconfig
@@ -0,0 +1,835 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+CONFIG_NUTTX_NEWCONFIG=y
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL 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_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
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDBOOL_H is not set
+# CONFIG_ARCH_MATH_H is not set
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+# CONFIG_DEBUG is not set
+# CONFIG_DEBUG_SYMBOLS is not set
+
+#
+# System Type
+#
+# CONFIG_ARCH_8051 is not set
+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_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_IMX 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_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_SAM34 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X 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=y
+# CONFIG_ARCH_CORTEXM4 is not set
+# CONFIG_ARCH_CORTEXA5 is not set
+# CONFIG_ARCH_CORTEXA8 is not set
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+# CONFIG_ARMV7M_USEBASEPRI is not set
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+# CONFIG_ARMV7M_CMNVECTOR is not set
+# CONFIG_ARCH_HAVE_FPU is not set
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARMV7M_MPU is not set
+
+#
+# ARMV7M Configuration Options
+#
+# 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_SERIAL_TERMIOS is not set
+
+#
+# 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_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_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+CONFIG_ARCH_CHIP_STM32F103RBT6=y
+# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
+# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG 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_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_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# 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_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+CONFIG_STM32_STM32F10XX=y
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+CONFIG_STM32_PERFORMANCELINE=y
+# CONFIG_STM32_HIGHDENSITY is not set
+CONFIG_STM32_MEDIUMDENSITY=y
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F30XX is not set
+# CONFIG_STM32_STM32F40XX is not set
+CONFIG_STM32_DFU=y
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKP is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_DMA1 is not set
+# CONFIG_STM32_DMA2 is not set
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=y
+# CONFIG_STM32_PWR is not set
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+# CONFIG_STM32_TIM4 is not set
+# CONFIG_STM32_TIM5 is not set
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_USART1=y
+# CONFIG_STM32_USART2 is not set
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+CONFIG_STM32_USB=y
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_WWDG is not set
+CONFIG_STM32_I2C=y
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_I2C1_REMAP is not set
+# CONFIG_STM32_USART1_REMAP is not set
+CONFIG_STM32_JTAG_DISABLE=y
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+# CONFIG_STM32_JTAG_SW_ENABLE is not set
+# CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG is not set
+# CONFIG_STM32_FORCEPOWER is not set
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+# CONFIG_SERIAL_DISABLE_REORDERING is not set
+# CONFIG_STM32_USART_SINGLEWIRE is not set
+
+#
+# I2C Configuration
+#
+# CONFIG_STM32_I2C_DYNTIMEO is not set
+CONFIG_STM32_I2CTIMEOSEC=1
+CONFIG_STM32_I2CTIMEOMS=500
+CONFIG_STM32_I2CTIMEOTICKS=500
+# CONFIG_STM32_I2C_DUTY16_9 is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+# CONFIG_ARCH_DMA is not set
+CONFIG_ARCH_IRQPRIO=y
+# CONFIG_CUSTOM_STACK is not set
+# CONFIG_ADDRENV is not set
+CONFIG_ARCH_HAVE_VFORK=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG 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=5483
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=0
+
+#
+# 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=20480
+
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_MAPLE=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="maple"
+
+#
+# Common Board Options
+#
+CONFIG_ARCH_HAVE_LEDS=y
+CONFIG_ARCH_LEDS=y
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+CONFIG_MAPLE_STANDARD=y
+# CONFIG_MAPLE_MINI is not set
+
+#
+# RTOS Features
+#
+# CONFIG_BOARD_INITIALIZE is not set
+CONFIG_MSEC_PER_TICK=10
+CONFIG_RR_INTERVAL=200
+# CONFIG_SCHED_INSTRUMENTATION is not set
+CONFIG_TASK_NAME_SIZE=0
+# CONFIG_SCHED_HAVE_PARENT is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=2009
+CONFIG_START_MONTH=10
+CONFIG_START_DAY=23
+# CONFIG_DEV_CONSOLE is not set
+# CONFIG_MUTEX_TYPES is not set
+# CONFIG_PRIORITY_INHERITANCE is not set
+# CONFIG_FDCLONE_DISABLE is not set
+# CONFIG_FDCLONE_STDIO is not set
+CONFIG_SDCLONE_DISABLE=y
+# CONFIG_SCHED_WAITPID is not set
+# CONFIG_SCHED_STARTHOOK is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nsh_main"
+# CONFIG_DISABLE_OS_API is not set
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+
+#
+# Sizes of configurable things (0 disables)
+#
+CONFIG_MAX_TASKS=16
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=4
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=8
+CONFIG_NAME_MAX=32
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=4
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=2048
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+
+#
+# Device Drivers
+#
+CONFIG_DISABLE_POLL=y
+CONFIG_DEV_NULL=y
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_PWM is not set
+CONFIG_I2C=y
+# CONFIG_I2C_SLAVE is not set
+CONFIG_I2C_TRANSFER=y
+# CONFIG_I2C_WRITEREAD is not set
+# CONFIG_I2C_POLLED is not set
+# CONFIG_I2C_TRACE is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_I2C_RESET is not set
+# CONFIG_SPI is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+# CONFIG_MTD is not set
+# CONFIG_PIPES is not set
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+CONFIG_SERIAL=y
+CONFIG_DEV_LOWCONSOLE=y
+CONFIG_SERIAL_REMOVABLE=y
+# CONFIG_16550_UART is not set
+CONFIG_ARCH_HAVE_USART1=y
+
+#
+# USART Configuration
+#
+CONFIG_USART1_ISUART=y
+CONFIG_MCU_SERIAL=y
+CONFIG_USART1_SERIAL_CONSOLE=y
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=256
+CONFIG_USART1_TXBUFSIZE=256
+CONFIG_USART1_BAUD=115200
+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_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL 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=y
+# CONFIG_USBDEV_BUSPOWERED is not set
+CONFIG_USBDEV_MAXPOWER=100
+# CONFIG_USBDEV_DMA is not set
+CONFIG_USBDEV_TRACE=y
+CONFIG_USBDEV_TRACE_NRECORDS=32
+# CONFIG_USBDEV_TRACE_STRINGS 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=y
+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_NWRREQS=4
+CONFIG_CDCACM_NRDREQS=4
+CONFIG_CDCACM_BULKIN_REQLEN=96
+CONFIG_CDCACM_RXBUFSIZE=256
+CONFIG_CDCACM_TXBUFSIZE=256
+CONFIG_CDCACM_VENDORID=0x0525
+CONFIG_CDCACM_PRODUCTID=0xa4a7
+CONFIG_CDCACM_VENDORSTR="NuttX"
+CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial"
+# CONFIG_USBMSC is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+
+#
+# Networking Support
+#
+# CONFIG_NET is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_RAMMAP is not set
+# CONFIG_FS_FAT is not set
+# CONFIG_FS_NXFFS is not set
+# CONFIG_FS_ROMFS is not set
+# CONFIG_FS_SMARTFS is not set
+# CONFIG_FS_BINFS is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG_ENABLE is not set
+# CONFIG_SYSLOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=1
+# CONFIG_GRAN is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Formats
+#
+# 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=y
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_LIBM is not set
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+# CONFIG_LIBC_FLOATINGPOINT is not set
+CONFIG_LIB_RAND_ORDER=2
+# 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 is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_LIB_SENDFILE_BUFSIZE=512
+# CONFIG_ARCH_ROMGETC is not set
+# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
+
+#
+# Non-standard Library Support
+#
+# CONFIG_SCHED_WORKQUEUE is not set
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+# CONFIG_HAVE_CXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CC3000BASIC is not set
+# CONFIG_EXAMPLES_CDCACM is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF 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_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_LCDRW is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+# CONFIG_EXAMPLES_MOUNT is not set
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+CONFIG_EXAMPLES_NSH=y
+# CONFIG_EXAMPLES_NULL is not set
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXCONSOLE is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PASHELLO is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART 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_UDP is not set
+# CONFIG_EXAMPLES_UIP is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBMSC is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_DHCPC is not set
+# CONFIG_NETUTILS_DHCPD is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_FTPD is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_RESOLV is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TELNETD is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_UIPLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_BUILTIN_APPS=y
+
+#
+# Disable Individual commands
+#
+# 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_DD 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 is not set
+# CONFIG_NSH_DISABLE_KILL is not set
+# CONFIG_NSH_DISABLE_LOSETUP is not set
+# 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_MW is not set
+# CONFIG_NSH_DISABLE_NSFMOUNT is not set
+# CONFIG_NSH_DISABLE_PS is not set
+# CONFIG_NSH_DISABLE_PING 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_TEST is not set
+# CONFIG_NSH_DISABLE_UMOUNT is not set
+# CONFIG_NSH_DISABLE_UNSET is not set
+# CONFIG_NSH_DISABLE_USLEEP is not set
+# CONFIG_NSH_DISABLE_WGET is not set
+# CONFIG_NSH_DISABLE_XD is not set
+
+#
+# Configure Command Options
+#
+# CONFIG_NSH_CMDOPT_DF_H is not set
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=1024
+CONFIG_NSH_LINELEN=80
+CONFIG_NSH_MAXARGUMENTS=6
+CONFIG_NSH_NESTDEPTH=3
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_CONSOLE=y
+CONFIG_NSH_USBCONSOLE=y
+CONFIG_NSH_USBCONDEV="/dev/ttyACM0"
+CONFIG_USBDEV_MINOR=0
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_USBDEV_TRACE is not set
+# CONFIG_NSH_ARCHINIT is not set
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+CONFIG_SYSTEM_I2CTOOL=y
+CONFIG_I2CTOOL_MINBUS=1
+CONFIG_I2CTOOL_MAXBUS=2
+CONFIG_I2CTOOL_MINADDR=0x0
+CONFIG_I2CTOOL_MAXADDR=0xf0
+CONFIG_I2CTOOL_MAXREGADDR=0xff
+CONFIG_I2CTOOL_DEFFREQ=100000
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# RAM test
+#
+# CONFIG_SYSTEM_RAMTEST is not set
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sysinfo
+#
+CONFIG_SYSTEM_SYSINFO=y
+
+#
+# USB Monitor
+#
+# CONFIG_SYSTEM_USBMONITOR is not set
+
+#
+# Zmodem Commands
+#
+# CONFIG_SYSTEM_ZMODEM is not set
diff --git a/nuttx/configs/maple/usbnsh/setenv.sh b/nuttx/configs/maple/usbnsh/setenv.sh
new file mode 100644
index 000000000..c6e4cdd59
--- /dev/null
+++ b/nuttx/configs/maple/usbnsh/setenv.sh
@@ -0,0 +1,68 @@
+#!/bin/bash
+# configs/maple/usbnsh/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
+
+export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+
+export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# This is the path to the LM3S6995-EK tools directory
+
+export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
+
+# Update the PATH variable
+
+export PATH="${BUILDROOT_BIN}:${TOOL_BIN:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"