summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-07 14:34:09 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-07 14:34:09 -0600
commit63403bacdb661897db9a6aeaac2e57b6065613fc (patch)
treeed8dbce0dac3f80668978f40ef388fa699168ac6
parentac5855212c360abd2694688f799aa141b11b4b26 (diff)
downloadpx4-nuttx-63403bacdb661897db9a6aeaac2e57b6065613fc.tar.gz
px4-nuttx-63403bacdb661897db9a6aeaac2e57b6065613fc.tar.bz2
px4-nuttx-63403bacdb661897db9a6aeaac2e57b6065613fc.zip
configs/mikroe-stm32f4: Add new configurations plus support for the MIO283QT2 display from Ken Pettit
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/configs/mikroe-stm32f4/README.txt95
-rw-r--r--nuttx/configs/mikroe-stm32f4/fulldemo/Make.defs111
-rw-r--r--nuttx/configs/mikroe-stm32f4/fulldemo/defconfig916
-rwxr-xr-xnuttx/configs/mikroe-stm32f4/fulldemo/setenv.sh77
-rw-r--r--nuttx/configs/mikroe-stm32f4/nsh/defconfig151
-rw-r--r--nuttx/configs/mikroe-stm32f4/nx/Make.defs111
-rw-r--r--nuttx/configs/mikroe-stm32f4/nx/defconfig786
-rwxr-xr-xnuttx/configs/mikroe-stm32f4/nx/setenv.sh77
-rw-r--r--nuttx/configs/mikroe-stm32f4/nxlines/Make.defs111
-rw-r--r--nuttx/configs/mikroe-stm32f4/nxlines/defconfig786
-rwxr-xr-xnuttx/configs/mikroe-stm32f4/nxlines/setenv.sh77
-rw-r--r--nuttx/configs/mikroe-stm32f4/nxtext/Make.defs111
-rw-r--r--nuttx/configs/mikroe-stm32f4/nxtext/defconfig797
-rwxr-xr-xnuttx/configs/mikroe-stm32f4/nxtext/setenv.sh77
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/Makefile2
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h91
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_boot.c6
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c470
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_nsh.c13
-rw-r--r--nuttx/configs/mikroe-stm32f4/usbnsh/defconfig4
-rw-r--r--nuttx/drivers/lcd/Kconfig7
22 files changed, 4555 insertions, 326 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index f49d81528..c24c9ecbf 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4687,4 +4687,7 @@
the "wfi" sleep mode. This is needed with certain JTAG debuggers to
to prevent the debug session from begin disconnected. From Ken Pettit
(2013-5-7).
-
+* configs/mikroe-stm32f4/fulldemo/, nx/, nxlines/, nxtext/: Add more
+ configurationsf for the Mikroelektronika Multimedia STM32-M4 board.
+ From Ken Pettit (2013-5-7).
+* \ No newline at end of file
diff --git a/nuttx/configs/mikroe-stm32f4/README.txt b/nuttx/configs/mikroe-stm32f4/README.txt
index 7d46fbc5c..559e0eaba 100644
--- a/nuttx/configs/mikroe-stm32f4/README.txt
+++ b/nuttx/configs/mikroe-stm32f4/README.txt
@@ -405,6 +405,16 @@ There are two version of the FPU support built into the STM32 port.
+ENTRY(__start) /* Treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* Force the vectors to be included in the output */
+MIO283QT-2
+==========
+
+The Mikroe-SMT32F4 board as an on-board MIO283QT-2 TFT LCD that can be
+configured and used. This is a 320x240 resolution display with color
+capability to 262K colors, though the mio283qt-2 driver in NuttX only
+supports 16-bit color depth, or 65K colors. Changes to both the
+mio283qt-2 driver and the driver interface layer would need to be made
+to support 24 BPP mode.
+
CFLAGS
------
@@ -738,6 +748,54 @@ instead of configure.sh:
Where <subdir> is one of the following:
+ fulldemo
+ --------
+ This is an example that includes an NSH shell over USB that also
+ enables all features of the Mikroe-STM32F4 board including the LCD,
+ on-board 1M Flash with SMART filesystem, Aux RS-232 serial port on the
+ expansion header, etc. A couple of the NX graphics commands are made
+ available via the NSH prompt for performing LCD demonstrations, and the
+ nximage example is used as a splash-screen at startup.
+
+
+ nsh
+ ---
+ This is an NSH example that uses USART2 as the console. Note that
+ the Mikroe-STM32F4 board doesn't actually have onboard line drivers
+ or a connector for USART2, but it does route the USART2 signals to
+ the expansion header. To use this demo, you would need to connect
+ an external 3.3V RS-232 line driver to the USART's I/O lines on the
+ expansion header.
+
+ NOTE: This demo doesn't quite work yet. I can get output to the
+ USART, but so far, I have not gotten nsh to actually come up.
+
+
+ nx
+ --
+ An example using the NuttX graphics system (NX). This example
+ focuses on general window controls, movement, mouse and keyboard
+ input.
+
+ CONFIG_LCD_LANDSCAPE=y : 320x240 landscape orientation
+ CONFIG_LCD_MIO283QT2
+
+ nxlines:
+ ------
+ An example using the NuttX graphics system (NX). This example focuses on
+ placing lines on the background in various orientations using the
+ on-board TFT LCD.
+
+ CONFIG_LCD_LANDSCAPE=y : 320x240 landscape orientation
+ CONFIG_LCD_MIO283QT2
+
+ nxtext:
+ ------
+ Another example using the NuttX graphics system (NX). This
+ example focuses on placing text on the background while pop-up
+ windows occur. Text should continue to update normally with
+ or without the popup windows present.
+
usbnsh:
-------
@@ -810,40 +868,3 @@ Where <subdir> is one of the following:
CONFIG_PL2303=y : The Prolifics PL2303 emulation is enabled
CONFIG_PL2303_CONSOLE=y : The PL2303 serial device is the console
- winbuild:
- --------
-
- This is a version of the apps/example/ostest, but configure to build natively
- in the Windows CMD shell.
-
- NOTES:
-
- 1. The beginnings of a Windows native build are in place but still not full
- usable as of this writing. The windows native build logic is currently
- separate and must be started by:
-
- make -f Makefile.win
-
- This build:
-
- - Uses all Windows style paths
- - Uses primarily Windows batch commands from cmd.exe, with
- - A few extensions from GNUWin32 (or MSYS is you prefer)
-
- In this build, you cannot use a Cygwin or MSYS shell. Rather the build must
- be performed in a Windows console. Here is a better shell than than the
- standard issue, CMD.exe shell: ConEmu which can be downloaded from:
- http://code.google.com/p/conemu-maximus5/
-
- CONFIG_HOST_WINDOWS=y : Windows
- CONFIG_WINDOWS_NATIVE=y : Native Windows environment
- CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
-
- Build Tools. The build still relies on some Unix-like commands. I use
- the GNUWin32 tools that can be downloaded from http://gnuwin32.sourceforge.net/.
- The MSYS tools are probably also a option but are likely lower performance
- since they are based on Cygwin 1.3.
-
- Host Compiler: I use the MingGW compiler which can be downloaded from
- http://www.mingw.org/. If you are using GNUWin32, then it is recommended
- the you not install the optional MSYS components as there may be conflicts.
diff --git a/nuttx/configs/mikroe-stm32f4/fulldemo/Make.defs b/nuttx/configs/mikroe-stm32f4/fulldemo/Make.defs
new file mode 100644
index 000000000..b04c5126d
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/fulldemo/Make.defs
@@ -0,0 +1,111 @@
+############################################################################
+# configs/mikroe-stm32f4/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
+
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+ 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 = $(ARCROSSDEV)ar rcs
+NM = $(ARCROSSDEV)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
+else
+ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
+endif
+
+ARCHCFLAGS = -fno-builtin
+ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
+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/mikroe-stm32f4/fulldemo/defconfig b/nuttx/configs/mikroe-stm32f4/fulldemo/defconfig
new file mode 100644
index 000000000..86aaf26bd
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/fulldemo/defconfig
@@ -0,0 +1,916 @@
+#
+# 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=y
+# 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=y
+
+#
+# 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_SAM3U is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+CONFIG_ARCH_CORTEXM4=y
+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_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_EABI=y
+# CONFIG_SERIAL_TERMIOS is not set
+
+#
+# STM32 Configuration Options
+#
+# 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_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=y
+# 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_STM32F40XX=y
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKPSRAM is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CAN2 is not set
+# CONFIG_STM32_CCMDATARAM is not set
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_CRYP 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_DCMI is not set
+# CONFIG_STM32_ETHMAC is not set
+# CONFIG_STM32_FSMC is not set
+# CONFIG_STM32_HASH is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+# CONFIG_STM32_I2C3 is not set
+# CONFIG_STM32_IWDG is not set
+CONFIG_STM32_OTGFS=y
+# CONFIG_STM32_OTGHS is not set
+CONFIG_STM32_PWR=y
+CONFIG_STM32_RNG=y
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+CONFIG_STM32_SPI2=y
+CONFIG_STM32_SPI3=y
+CONFIG_STM32_SYSCFG=y
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+# CONFIG_STM32_TIM4 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_TIM9 is not set
+# CONFIG_STM32_TIM10 is not set
+# CONFIG_STM32_TIM11 is not set
+# CONFIG_STM32_TIM12 is not set
+# CONFIG_STM32_TIM13 is not set
+# CONFIG_STM32_TIM14 is not set
+# CONFIG_STM32_USART1 is not set
+CONFIG_STM32_USART2=y
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+# CONFIG_STM32_USART6 is not set
+# CONFIG_STM32_WWDG is not set
+CONFIG_STM32_SPI=y
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_FLASH_PREFETCH is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
+# CONFIG_STM32_CCMEXCLUDE is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART2_RS485 is not set
+# CONFIG_STM32_USART_SINGLEWIRE is not set
+
+#
+# SPI Configuration
+#
+# CONFIG_STM32_SPI_INTERRUPTS is not set
+# CONFIG_STM32_SPI_DMA is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# External Memory 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=16717
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_SIZE=114688
+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
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set
+CONFIG_ARCH_BOARD_MIKROE_STM32F4=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="mikroe-stm32f4"
+
+#
+# Common Board Options
+#
+CONFIG_NSH_MMCSDMINOR=0
+CONFIG_NSH_MMCSDSLOTNO=0
+CONFIG_NSH_MMCSDSPIPORTNO=0
+
+#
+# Board-Specific Options
+#
+CONFIG_MIKROE_FLASH=y
+CONFIG_MIKROE_FLASH_MINOR=0
+CONFIG_MIKROE_FLASH_PART=y
+CONFIG_MIKROE_FLASH_PART_LIST="256,768"
+# CONFIG_MIKROE_RAMMTD 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=2013
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=27
+# 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=y
+# 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=y
+# CONFIG_DISABLE_CLOCK is not set
+# CONFIG_DISABLE_POSIX_TIMERS is not set
+# CONFIG_DISABLE_PTHREAD is not set
+# CONFIG_DISABLE_SIGNALS is not set
+# CONFIG_DISABLE_MQUEUE is not set
+# CONFIG_DISABLE_ENVIRON is not set
+
+#
+# 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=2048
+CONFIG_USERMAIN_STACKSIZE=2048
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+
+#
+# Device Drivers
+#
+CONFIG_DISABLE_POLL=y
+CONFIG_DEV_NULL=y
+CONFIG_DEV_ZERO=y
+CONFIG_ARCH_HAVE_RNG=y
+CONFIG_DEV_RANDOM=y
+CONFIG_LOOP=y
+CONFIG_RAMDISK=y
+# CONFIG_CAN is not set
+# CONFIG_PWM is not set
+# CONFIG_I2C is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+CONFIG_SPI=y
+# CONFIG_SPI_OWNBUS is not set
+CONFIG_SPI_EXCHANGE=y
+# CONFIG_SPI_CMDDATA is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+CONFIG_LCD=y
+# CONFIG_LCD_NOGETRUN is not set
+CONFIG_LCD_MAXCONTRAST=63
+CONFIG_LCD_MAXPOWER=1
+# CONFIG_LCD_P14201 is not set
+# CONFIG_LCD_NOKIA6100 is not set
+CONFIG_LCD_MIO283QT2=y
+# CONFIG_LCD_UG9664HSWAG01 is not set
+# CONFIG_LCD_ST7567 is not set
+# CONFIG_LCD_UG2864AMBAG01 is not set
+# CONFIG_LCD_SSD1289 is not set
+CONFIG_LCD_LANDSCAPE=y
+# CONFIG_LCD_PORTRAIT is not set
+# CONFIG_LCD_RPORTRAIT is not set
+# CONFIG_LCD_RLANDSCAPE is not set
+CONFIG_MMCSD=y
+CONFIG_MMCSD_NSLOTS=1
+# CONFIG_MMCSD_READONLY is not set
+# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
+CONFIG_MMCSD_MMCSUPPORT=y
+CONFIG_MMCSD_HAVECARDDETECT=y
+CONFIG_MMCSD_SPI=y
+CONFIG_MMCSD_SPICLOCK=20000000
+# CONFIG_MMCSD_SDIO is not set
+CONFIG_MTD=y
+
+#
+# MTD Configuration
+#
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_BYTE_WRITE=y
+
+#
+# MTD Device Drivers
+#
+CONFIG_RAMMTD=y
+CONFIG_RAMMTD_BLOCKSIZE=512
+CONFIG_RAMMTD_ERASESIZE=4096
+CONFIG_RAMMTD_ERASESTATE=0xff
+# CONFIG_RAMMTD_FLASHSIM is not set
+# CONFIG_MTD_AT24XX is not set
+# CONFIG_MTD_AT45DB is not set
+CONFIG_MTD_M25P=y
+CONFIG_M25P_SPIMODE=0
+CONFIG_M25P_MANUFACTURER=0x1C
+CONFIG_M25P_MEMORY_TYPE=0x31
+CONFIG_M25P_SUBSECTOR_ERASE=y
+CONFIG_MTD_SMART=y
+CONFIG_MTD_SMART_SECTOR_SIZE=512
+# CONFIG_MTD_RAMTRON is not set
+# CONFIG_MTD_SST25 is not set
+# CONFIG_MTD_SST39FV is not set
+# CONFIG_MTD_W25 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_SERIAL_REMOVABLE=y
+# CONFIG_16550_UART is not set
+CONFIG_ARCH_HAVE_USART2=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+# CONFIG_USART2_SERIAL_CONSOLE is not set
+CONFIG_NO_SERIAL_CONSOLE=y
+
+#
+# USART2 Configuration
+#
+CONFIG_USART2_RXBUFSIZE=256
+CONFIG_USART2_TXBUFSIZE=256
+CONFIG_USART2_BAUD=115200
+CONFIG_USART2_BITS=8
+CONFIG_USART2_PARITY=0
+CONFIG_USART2_2STOP=0
+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 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_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=y
+# CONFIG_FAT_LCNAMES is not set
+# CONFIG_FAT_LFN is not set
+# CONFIG_FS_FATTIME is not set
+# CONFIG_FAT_DMAMEMORY is not set
+# CONFIG_FS_NXFFS is not set
+CONFIG_FS_ROMFS=y
+CONFIG_FS_SMARTFS=y
+CONFIG_SMARTFS_ERASEDSTATE=0xff
+CONFIG_SMARTFS_MAXNAMLEN=16
+# CONFIG_SMARTFS_MULTI_ROOT_DIRS is not set
+# CONFIG_FS_BINFS is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG_ENABLE is not set
+CONFIG_SYSLOG=y
+CONFIG_SYSLOG_CHAR=y
+CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
+
+#
+# Graphics Support
+#
+CONFIG_NX=y
+CONFIG_NX_LCDDRIVER=y
+CONFIG_NX_NPLANES=1
+# CONFIG_NX_WRITEONLY is not set
+
+#
+# Supported Pixel Depths
+#
+CONFIG_NX_DISABLE_1BPP=y
+CONFIG_NX_DISABLE_2BPP=y
+CONFIG_NX_DISABLE_4BPP=y
+CONFIG_NX_DISABLE_8BPP=y
+# CONFIG_NX_DISABLE_16BPP is not set
+CONFIG_NX_DISABLE_24BPP=y
+CONFIG_NX_DISABLE_32BPP=y
+CONFIG_NX_PACKEDMSFIRST=y
+
+#
+# Input Devices
+#
+# CONFIG_NX_MOUSE is not set
+# CONFIG_NX_KBD is not set
+
+#
+# Framed Window Borders
+#
+CONFIG_NXTK_BORDERWIDTH=3
+CONFIG_NXTK_BORDERCOLOR1=0x8410
+CONFIG_NXTK_BORDERCOLOR2=0x4208
+CONFIG_NXTK_BORDERCOLOR3=0xc618
+# CONFIG_NXTK_AUTORAISE is not set
+
+#
+# Font Selections
+#
+CONFIG_NXFONTS_CHARBITS=7
+# CONFIG_NXFONT_MONO5X8 is not set
+# CONFIG_NXFONT_SANS17X22 is not set
+# CONFIG_NXFONT_SANS20X26 is not set
+# CONFIG_NXFONT_SANS23X27 is not set
+# CONFIG_NXFONT_SANS22X29 is not set
+# CONFIG_NXFONT_SANS28X37 is not set
+# CONFIG_NXFONT_SANS39X48 is not set
+# CONFIG_NXFONT_SANS17X23B is not set
+# CONFIG_NXFONT_SANS20X27B is not set
+# CONFIG_NXFONT_SANS22X29B is not set
+# CONFIG_NXFONT_SANS28X37B is not set
+# CONFIG_NXFONT_SANS40X49B is not set
+# CONFIG_NXFONT_SERIF22X29 is not set
+# CONFIG_NXFONT_SERIF29X37 is not set
+# CONFIG_NXFONT_SERIF38X48 is not set
+CONFIG_NXFONT_SERIF22X28B=y
+# CONFIG_NXFONT_SERIF27X38B is not set
+# CONFIG_NXFONT_SERIF38X49B is not set
+# CONFIG_NXCONSOLE is not set
+
+#
+# NX Multi-user only options
+#
+# CONFIG_NX_MULTIUSER is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=2
+# CONFIG_GRAN 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 is not set
+
+#
+# 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=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
+CONFIG_LIBC_STRERROR=y
+# CONFIG_LIBC_STRERROR_SHORT is not set
+CONFIG_LIBC_PERROR_STDOUT=y
+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
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CDCACM is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST 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_MTDPART is not set
+CONFIG_EXAMPLES_NSH=y
+# CONFIG_EXAMPLES_NULL is not set
+CONFIG_EXAMPLES_NX=y
+CONFIG_EXAMPLES_NX_BUILTIN=y
+CONFIG_EXAMPLES_NX_VPLANE=0
+CONFIG_EXAMPLES_NX_DEVNO=0
+CONFIG_EXAMPLES_NX_DEFAULT_COLORS=y
+CONFIG_EXAMPLES_NX_DEFAULT_FONT=y
+CONFIG_EXAMPLES_NX_BPP=16
+# CONFIG_EXAMPLES_NX_RAWWINDOWS is not set
+# CONFIG_EXAMPLES_NX_EXTERNINIT 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=y
+# 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_FLASH_TEST is not set
+# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART 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_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=y
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_LINELEN=64
+CONFIG_NSH_NESTDEPTH=3
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+# CONFIG_NSH_ROMFSETC is not set
+CONFIG_NSH_CONSOLE=y
+# CONFIG_NSH_USBCONSOLE is not set
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+# CONFIG_NXWIDGETS is not set
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+CONFIG_SYSTEM_FLASH_ERASEALL=y
+
+#
+# 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
+#
diff --git a/nuttx/configs/mikroe-stm32f4/fulldemo/setenv.sh b/nuttx/configs/mikroe-stm32f4/fulldemo/setenv.sh
new file mode 100755
index 000000000..1dc5b1806
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/fulldemo/setenv.sh
@@ -0,0 +1,77 @@
+#!/bin/bash
+# configs/stm32f4discovery/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 under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+export TOOLCHAIN_BIN="/home/ken/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/mikroe-stm32f4/nsh/defconfig b/nuttx/configs/mikroe-stm32f4/nsh/defconfig
index 7a82a8974..8fb6a4148 100644
--- a/nuttx/configs/mikroe-stm32f4/nsh/defconfig
+++ b/nuttx/configs/mikroe-stm32f4/nsh/defconfig
@@ -8,14 +8,10 @@ CONFIG_NUTTX_NEWCONFIG=y
# Build Setup
#
# CONFIG_EXPERIMENTAL is not set
-# CONFIG_HOST_LINUX is not set
+CONFIG_HOST_LINUX=y
# CONFIG_HOST_OSX is not set
-CONFIG_HOST_WINDOWS=y
+# CONFIG_HOST_WINDOWS is not set
# CONFIG_HOST_OTHER is not set
-# CONFIG_WINDOWS_NATIVE is not set
-CONFIG_WINDOWS_CYGWIN=y
-# CONFIG_WINDOWS_MSYS is not set
-# CONFIG_WINDOWS_OTHER is not set
#
# Build Configuration
@@ -93,13 +89,10 @@ CONFIG_ARCH_HAVE_MPU=y
#
# ARMV7M Configuration Options
#
-# CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC is not set
# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
-# CONFIG_ARMV7M_TOOLCHAIN_CODEREDW is not set
-CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y
-# CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM is not set
-# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI is not set
-# CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set
+CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
# CONFIG_SERIAL_TERMIOS is not set
#
@@ -178,11 +171,11 @@ CONFIG_STM32_STM32F40XX=y
# CONFIG_STM32_OTGFS is not set
# CONFIG_STM32_OTGHS is not set
CONFIG_STM32_PWR=y
-# CONFIG_STM32_RNG is not set
+CONFIG_STM32_RNG=y
# CONFIG_STM32_SDIO is not set
-CONFIG_STM32_SPI1=y
-# CONFIG_STM32_SPI2 is not set
-# CONFIG_STM32_SPI3 is not set
+# CONFIG_STM32_SPI1 is not set
+CONFIG_STM32_SPI2=y
+CONFIG_STM32_SPI3=y
CONFIG_STM32_SYSCFG=y
# CONFIG_STM32_TIM1 is not set
# CONFIG_STM32_TIM2 is not set
@@ -215,8 +208,9 @@ CONFIG_STM32_SPI=y
# CONFIG_STM32_JTAG_FULL_ENABLE is not set
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
# CONFIG_STM32_FORCEPOWER is not set
-# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
# CONFIG_STM32_CCMEXCLUDE is not set
CONFIG_STM32_USART=y
@@ -282,25 +276,26 @@ CONFIG_BOOT_RUNFROMFLASH=y
#
# Board Selection
#
-CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y
-# CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set
+# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set
+CONFIG_ARCH_BOARD_MIKROE_STM32F4=y
# CONFIG_ARCH_BOARD_CUSTOM is not set
-CONFIG_ARCH_BOARD="stm32f4discovery"
+CONFIG_ARCH_BOARD="mikroe-stm32f4"
#
# Common Board Options
#
-CONFIG_ARCH_HAVE_LEDS=y
-CONFIG_ARCH_LEDS=y
-CONFIG_ARCH_HAVE_BUTTONS=y
-CONFIG_ARCH_BUTTONS=y
-CONFIG_ARCH_HAVE_IRQBUTTONS=y
-# CONFIG_ARCH_IRQBUTTONS is not set
CONFIG_NSH_MMCSDMINOR=0
+CONFIG_NSH_MMCSDSLOTNO=0
+CONFIG_NSH_MMCSDSPIPORTNO=0
#
# Board-Specific Options
#
+CONFIG_MIKROE_FLASH=y
+CONFIG_MIKROE_FLASH_MINOR=0
+CONFIG_MIKROE_FLASH_PART=y
+CONFIG_MIKROE_FLASH_PART_LIST="256,768"
+# CONFIG_MIKROE_RAMMTD is not set
#
# RTOS Features
@@ -312,10 +307,10 @@ CONFIG_RR_INTERVAL=200
CONFIG_TASK_NAME_SIZE=0
# CONFIG_SCHED_HAVE_PARENT is not set
# CONFIG_JULIAN_TIME is not set
-CONFIG_START_YEAR=2011
-CONFIG_START_MONTH=12
-CONFIG_START_DAY=6
-CONFIG_DEV_CONSOLE=y
+CONFIG_START_YEAR=2013
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=27
+# CONFIG_DEV_CONSOLE is not set
# CONFIG_MUTEX_TYPES is not set
# CONFIG_PRIORITY_INHERITANCE is not set
# CONFIG_FDCLONE_DISABLE is not set
@@ -326,13 +321,7 @@ CONFIG_SCHED_WAITPID=y
# CONFIG_SCHED_ATEXIT is not set
# CONFIG_SCHED_ONEXIT is not set
CONFIG_USER_ENTRYPOINT="nsh_main"
-CONFIG_DISABLE_OS_API=y
-# CONFIG_DISABLE_CLOCK is not set
-# CONFIG_DISABLE_POSIX_TIMERS is not set
-# CONFIG_DISABLE_PTHREAD is not set
-# CONFIG_DISABLE_SIGNALS is not set
-# CONFIG_DISABLE_MQUEUE is not set
-# CONFIG_DISABLE_ENVIRON is not set
+# CONFIG_DISABLE_OS_API is not set
#
# Signal Numbers
@@ -360,7 +349,7 @@ CONFIG_PREALLOC_TIMERS=4
#
# Stack and heap information
#
-CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_IDLETHREAD_STACKSIZE=2048
CONFIG_USERMAIN_STACKSIZE=2048
CONFIG_PTHREAD_STACK_MIN=256
CONFIG_PTHREAD_STACK_DEFAULT=2048
@@ -370,9 +359,11 @@ CONFIG_PTHREAD_STACK_DEFAULT=2048
#
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_DEV_ZERO=y
+CONFIG_ARCH_HAVE_RNG=y
+CONFIG_DEV_RANDOM=y
+CONFIG_LOOP=y
+CONFIG_RAMDISK=y
# CONFIG_CAN is not set
# CONFIG_PWM is not set
# CONFIG_I2C is not set
@@ -387,13 +378,48 @@ CONFIG_SPI_EXCHANGE=y
# 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_MMCSD=y
+CONFIG_MMCSD_NSLOTS=1
+# CONFIG_MMCSD_READONLY is not set
+# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
+CONFIG_MMCSD_MMCSUPPORT=y
+CONFIG_MMCSD_HAVECARDDETECT=y
+CONFIG_MMCSD_SPI=y
+CONFIG_MMCSD_SPICLOCK=20000000
+# CONFIG_MMCSD_SDIO is not set
+CONFIG_MTD=y
+
+#
+# MTD Configuration
+#
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_BYTE_WRITE=y
+
+#
+# MTD Device Drivers
+#
+CONFIG_RAMMTD=y
+CONFIG_RAMMTD_BLOCKSIZE=512
+CONFIG_RAMMTD_ERASESIZE=4096
+CONFIG_RAMMTD_ERASESTATE=0xff
+# CONFIG_RAMMTD_FLASHSIM is not set
+# CONFIG_MTD_AT24XX is not set
+# CONFIG_MTD_AT45DB is not set
+CONFIG_MTD_M25P=y
+CONFIG_M25P_SPIMODE=0
+CONFIG_M25P_MANUFACTURER=0x1C
+CONFIG_M25P_MEMORY_TYPE=0x31
+CONFIG_M25P_SUBSECTOR_ERASE=y
+CONFIG_MTD_SMART=y
+CONFIG_MTD_SMART_SECTOR_SIZE=512
+# CONFIG_MTD_RAMTRON is not set
+# CONFIG_MTD_SST25 is not set
+# CONFIG_MTD_SST39FV is not set
+# CONFIG_MTD_W25 is not set
# CONFIG_PIPES is not set
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
@@ -406,8 +432,8 @@ CONFIG_USART2_SERIAL_CONSOLE=y
#
# USART2 Configuration
#
-CONFIG_USART2_RXBUFSIZE=128
-CONFIG_USART2_TXBUFSIZE=128
+CONFIG_USART2_RXBUFSIZE=256
+CONFIG_USART2_TXBUFSIZE=256
CONFIG_USART2_BAUD=115200
CONFIG_USART2_BITS=8
CONFIG_USART2_PARITY=0
@@ -439,17 +465,26 @@ CONFIG_USART2_2STOP=0
#
# CONFIG_DISABLE_MOUNTPOINT is not set
# CONFIG_FS_RAMMAP is not set
-# CONFIG_FS_FAT is not set
+CONFIG_FS_FAT=y
+# CONFIG_FAT_LCNAMES is not set
+# CONFIG_FAT_LFN is not set
+# CONFIG_FS_FATTIME is not set
+# CONFIG_FAT_DMAMEMORY is not set
# CONFIG_FS_NXFFS is not set
-# CONFIG_FS_ROMFS is not set
-# CONFIG_FS_SMARTFS is not set
+CONFIG_FS_ROMFS=y
+CONFIG_FS_SMARTFS=y
+CONFIG_SMARTFS_ERASEDSTATE=0xff
+CONFIG_SMARTFS_MAXNAMLEN=16
+# CONFIG_SMARTFS_MULTI_ROOT_DIRS is not set
# CONFIG_FS_BINFS is not set
#
# System Logging
#
# CONFIG_SYSLOG_ENABLE is not set
-# CONFIG_SYSLOG is not set
+CONFIG_SYSLOG=y
+CONFIG_SYSLOG_CHAR=y
+CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
#
# Graphics Support
@@ -497,8 +532,9 @@ 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_LIBC_STRERROR=y
+# CONFIG_LIBC_STRERROR_SHORT is not set
+CONFIG_LIBC_PERROR_STDOUT=y
CONFIG_ARCH_LOWPUTC=y
CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_ARCH_ROMGETC is not set
@@ -573,7 +609,9 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_ROMFS is not set
# CONFIG_EXAMPLES_SENDMAIL is not set
# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_FLASH_TEST is not set
# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART is not set
# CONFIG_EXAMPLES_TELNETD is not set
# CONFIG_EXAMPLES_THTTPD is not set
# CONFIG_EXAMPLES_TIFF is not set
@@ -674,20 +712,22 @@ CONFIG_NSH_BUILTIN_APPS=y
#
# Configure Command Options
#
-# CONFIG_NSH_CMDOPT_DF_H is not set
+CONFIG_NSH_CMDOPT_DF_H=y
CONFIG_NSH_CODECS_BUFSIZE=128
CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_STRERROR=y
CONFIG_NSH_LINELEN=64
CONFIG_NSH_NESTDEPTH=3
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLEBG is not set
+# CONFIG_NSH_ROMFSETC is not set
CONFIG_NSH_CONSOLE=y
#
# USB Trace Support
#
# CONFIG_NSH_CONDEV is not set
-# CONFIG_NSH_ARCHINIT is not set
+CONFIG_NSH_ARCHINIT=y
#
# NxWidgets/NxWM
@@ -714,6 +754,7 @@ CONFIG_NSH_CONSOLE=y
#
# FLASH Erase-all Command
#
+CONFIG_SYSTEM_FLASH_ERASEALL=y
#
# readline()
@@ -739,7 +780,7 @@ CONFIG_READLINE_ECHO=y
#
# Sysinfo
#
-# CONFIG_SYSTEM_SYSINFO is not set
+CONFIG_SYSTEM_SYSINFO=y
#
# USB Monitor
diff --git a/nuttx/configs/mikroe-stm32f4/nx/Make.defs b/nuttx/configs/mikroe-stm32f4/nx/Make.defs
new file mode 100644
index 000000000..b04c5126d
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nx/Make.defs
@@ -0,0 +1,111 @@
+############################################################################
+# configs/mikroe-stm32f4/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
+
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+ 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 = $(ARCROSSDEV)ar rcs
+NM = $(ARCROSSDEV)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
+else
+ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
+endif
+
+ARCHCFLAGS = -fno-builtin
+ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
+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/mikroe-stm32f4/nx/defconfig b/nuttx/configs/mikroe-stm32f4/nx/defconfig
new file mode 100644
index 000000000..cda392981
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nx/defconfig
@@ -0,0 +1,786 @@
+#
+# 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=y
+# 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_SAM3U is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+CONFIG_ARCH_CORTEXM4=y
+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_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_EABI=y
+
+#
+# STM32 Configuration Options
+#
+# 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_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=y
+# 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_STM32F40XX=y
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKPSRAM is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CAN2 is not set
+# CONFIG_STM32_CCMDATARAM is not set
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_CRYP 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_DCMI is not set
+# CONFIG_STM32_ETHMAC is not set
+# CONFIG_STM32_FSMC is not set
+# CONFIG_STM32_HASH is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+# CONFIG_STM32_I2C3 is not set
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_OTGFS is not set
+# CONFIG_STM32_OTGHS is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_RNG is not set
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_SPI3 is not set
+CONFIG_STM32_SYSCFG=y
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+# CONFIG_STM32_TIM4 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_TIM9 is not set
+# CONFIG_STM32_TIM10 is not set
+# CONFIG_STM32_TIM11 is not set
+# CONFIG_STM32_TIM12 is not set
+# CONFIG_STM32_TIM13 is not set
+# CONFIG_STM32_TIM14 is not set
+# CONFIG_STM32_USART1 is not set
+# 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_USART6 is not set
+# CONFIG_STM32_WWDG is not set
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_FLASH_PREFETCH is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
+# CONFIG_STM32_CCMEXCLUDE is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# External Memory 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=16717
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_SIZE=114688
+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
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set
+CONFIG_ARCH_BOARD_MIKROE_STM32F4=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="mikroe-stm32f4"
+
+#
+# Common Board Options
+#
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+# CONFIG_MIKROE_FLASH is not set
+# CONFIG_MIKROE_RAMMTD 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=2013
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=27
+# 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=y
+# CONFIG_SCHED_STARTHOOK is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nx_main"
+CONFIG_DISABLE_OS_API=y
+# CONFIG_DISABLE_CLOCK is not set
+# CONFIG_DISABLE_POSIX_TIMERS is not set
+# CONFIG_DISABLE_PTHREAD is not set
+# CONFIG_DISABLE_SIGNALS is not set
+# CONFIG_DISABLE_MQUEUE is not set
+# CONFIG_DISABLE_ENVIRON is not set
+
+#
+# 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=2048
+CONFIG_USERMAIN_STACKSIZE=2048
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+
+#
+# Device Drivers
+#
+CONFIG_DISABLE_POLL=y
+# CONFIG_DEV_NULL is not set
+# 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 is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_SPI is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+CONFIG_LCD=y
+# CONFIG_LCD_NOGETRUN is not set
+CONFIG_LCD_MAXCONTRAST=63
+CONFIG_LCD_MAXPOWER=1
+# CONFIG_LCD_P14201 is not set
+# CONFIG_LCD_NOKIA6100 is not set
+CONFIG_LCD_MIO283QT2=y
+# CONFIG_LCD_UG9664HSWAG01 is not set
+# CONFIG_LCD_ST7567 is not set
+# CONFIG_LCD_UG2864AMBAG01 is not set
+# CONFIG_LCD_SSD1289 is not set
+CONFIG_LCD_LANDSCAPE=y
+# CONFIG_LCD_PORTRAIT is not set
+# CONFIG_LCD_RPORTRAIT is not set
+# CONFIG_LCD_RLANDSCAPE 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 is not set
+# CONFIG_USBDEV 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=y
+CONFIG_SYSLOG_CHAR=y
+CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
+
+#
+# Graphics Support
+#
+CONFIG_NX=y
+CONFIG_NX_LCDDRIVER=y
+CONFIG_NX_NPLANES=1
+# CONFIG_NX_WRITEONLY is not set
+
+#
+# Supported Pixel Depths
+#
+CONFIG_NX_DISABLE_1BPP=y
+CONFIG_NX_DISABLE_2BPP=y
+CONFIG_NX_DISABLE_4BPP=y
+CONFIG_NX_DISABLE_8BPP=y
+# CONFIG_NX_DISABLE_16BPP is not set
+CONFIG_NX_DISABLE_24BPP=y
+CONFIG_NX_DISABLE_32BPP=y
+CONFIG_NX_PACKEDMSFIRST=y
+
+#
+# Input Devices
+#
+# CONFIG_NX_MOUSE is not set
+# CONFIG_NX_KBD is not set
+
+#
+# Framed Window Borders
+#
+CONFIG_NXTK_BORDERWIDTH=3
+CONFIG_NXTK_BORDERCOLOR1=0x8410
+CONFIG_NXTK_BORDERCOLOR2=0x4208
+CONFIG_NXTK_BORDERCOLOR3=0xc618
+# CONFIG_NXTK_AUTORAISE is not set
+
+#
+# Font Selections
+#
+CONFIG_NXFONTS_CHARBITS=7
+# CONFIG_NXFONT_MONO5X8 is not set
+# CONFIG_NXFONT_SANS17X22 is not set
+# CONFIG_NXFONT_SANS20X26 is not set
+# CONFIG_NXFONT_SANS23X27 is not set
+# CONFIG_NXFONT_SANS22X29 is not set
+# CONFIG_NXFONT_SANS28X37 is not set
+# CONFIG_NXFONT_SANS39X48 is not set
+# CONFIG_NXFONT_SANS17X23B is not set
+# CONFIG_NXFONT_SANS20X27B is not set
+# CONFIG_NXFONT_SANS22X29B is not set
+# CONFIG_NXFONT_SANS28X37B is not set
+# CONFIG_NXFONT_SANS40X49B is not set
+# CONFIG_NXFONT_SERIF22X29 is not set
+# CONFIG_NXFONT_SERIF29X37 is not set
+# CONFIG_NXFONT_SERIF38X48 is not set
+CONFIG_NXFONT_SERIF22X28B=y
+# CONFIG_NXFONT_SERIF27X38B is not set
+# CONFIG_NXFONT_SERIF38X49B is not set
+# CONFIG_NXCONSOLE is not set
+
+#
+# NX Multi-user only options
+#
+# CONFIG_NX_MULTIUSER is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=2
+# CONFIG_GRAN 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 is not set
+
+#
+# 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=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
+CONFIG_LIBC_STRERROR=y
+# CONFIG_LIBC_STRERROR_SHORT is not set
+CONFIG_LIBC_PERROR_STDOUT=y
+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
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST 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_NSH is not set
+# CONFIG_EXAMPLES_NULL is not set
+CONFIG_EXAMPLES_NX=y
+# CONFIG_EXAMPLES_NX_BUILTIN is not set
+CONFIG_EXAMPLES_NX_VPLANE=0
+CONFIG_EXAMPLES_NX_DEVNO=0
+CONFIG_EXAMPLES_NX_DEFAULT_COLORS=y
+CONFIG_EXAMPLES_NX_DEFAULT_FONT=y
+CONFIG_EXAMPLES_NX_BPP=16
+# CONFIG_EXAMPLES_NX_RAWWINDOWS is not set
+# CONFIG_EXAMPLES_NX_EXTERNINIT 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_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART 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_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=y
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_LINELEN=64
+CONFIG_NSH_NESTDEPTH=3
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_CONSOLE=y
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+# CONFIG_NXWIDGETS is not set
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# 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
+#
diff --git a/nuttx/configs/mikroe-stm32f4/nx/setenv.sh b/nuttx/configs/mikroe-stm32f4/nx/setenv.sh
new file mode 100755
index 000000000..1dc5b1806
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nx/setenv.sh
@@ -0,0 +1,77 @@
+#!/bin/bash
+# configs/stm32f4discovery/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 under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+export TOOLCHAIN_BIN="/home/ken/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/mikroe-stm32f4/nxlines/Make.defs b/nuttx/configs/mikroe-stm32f4/nxlines/Make.defs
new file mode 100644
index 000000000..b04c5126d
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nxlines/Make.defs
@@ -0,0 +1,111 @@
+############################################################################
+# configs/mikroe-stm32f4/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
+
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+ 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 = $(ARCROSSDEV)ar rcs
+NM = $(ARCROSSDEV)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
+else
+ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
+endif
+
+ARCHCFLAGS = -fno-builtin
+ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
+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/mikroe-stm32f4/nxlines/defconfig b/nuttx/configs/mikroe-stm32f4/nxlines/defconfig
new file mode 100644
index 000000000..59ff32fb5
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nxlines/defconfig
@@ -0,0 +1,786 @@
+#
+# 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=y
+# 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_SAM3U is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+CONFIG_ARCH_CORTEXM4=y
+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_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_EABI=y
+
+#
+# STM32 Configuration Options
+#
+# 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_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=y
+# 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_STM32F40XX=y
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKPSRAM is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CAN2 is not set
+# CONFIG_STM32_CCMDATARAM is not set
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_CRYP 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_DCMI is not set
+# CONFIG_STM32_ETHMAC is not set
+# CONFIG_STM32_FSMC is not set
+# CONFIG_STM32_HASH is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+# CONFIG_STM32_I2C3 is not set
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_OTGFS is not set
+# CONFIG_STM32_OTGHS is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_RNG is not set
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_SPI3 is not set
+CONFIG_STM32_SYSCFG=y
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+# CONFIG_STM32_TIM4 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_TIM9 is not set
+# CONFIG_STM32_TIM10 is not set
+# CONFIG_STM32_TIM11 is not set
+# CONFIG_STM32_TIM12 is not set
+# CONFIG_STM32_TIM13 is not set
+# CONFIG_STM32_TIM14 is not set
+# CONFIG_STM32_USART1 is not set
+# 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_USART6 is not set
+# CONFIG_STM32_WWDG is not set
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_FLASH_PREFETCH is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
+# CONFIG_STM32_CCMEXCLUDE is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# External Memory 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=16717
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_SIZE=114688
+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
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set
+CONFIG_ARCH_BOARD_MIKROE_STM32F4=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="mikroe-stm32f4"
+
+#
+# Common Board Options
+#
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+# CONFIG_MIKROE_FLASH is not set
+# CONFIG_MIKROE_RAMMTD 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=2013
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=27
+# 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=y
+# CONFIG_SCHED_STARTHOOK is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nxlines_main"
+CONFIG_DISABLE_OS_API=y
+# CONFIG_DISABLE_CLOCK is not set
+# CONFIG_DISABLE_POSIX_TIMERS is not set
+# CONFIG_DISABLE_PTHREAD is not set
+# CONFIG_DISABLE_SIGNALS is not set
+# CONFIG_DISABLE_MQUEUE is not set
+# CONFIG_DISABLE_ENVIRON is not set
+
+#
+# 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=2048
+CONFIG_USERMAIN_STACKSIZE=2048
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+
+#
+# Device Drivers
+#
+CONFIG_DISABLE_POLL=y
+# CONFIG_DEV_NULL is not set
+# 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 is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_SPI is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+CONFIG_LCD=y
+CONFIG_LCD_NOGETRUN=y
+CONFIG_LCD_MAXCONTRAST=63
+CONFIG_LCD_MAXPOWER=1
+# CONFIG_LCD_P14201 is not set
+# CONFIG_LCD_NOKIA6100 is not set
+CONFIG_LCD_MIO283QT2=y
+# CONFIG_LCD_UG9664HSWAG01 is not set
+# CONFIG_LCD_ST7567 is not set
+# CONFIG_LCD_UG2864AMBAG01 is not set
+# CONFIG_LCD_SSD1289 is not set
+CONFIG_LCD_LANDSCAPE=y
+# CONFIG_LCD_PORTRAIT is not set
+# CONFIG_LCD_RPORTRAIT is not set
+# CONFIG_LCD_RLANDSCAPE 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 is not set
+# CONFIG_USBDEV 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=y
+CONFIG_SYSLOG_CHAR=y
+CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
+
+#
+# Graphics Support
+#
+CONFIG_NX=y
+CONFIG_NX_LCDDRIVER=y
+CONFIG_NX_NPLANES=1
+# CONFIG_NX_WRITEONLY is not set
+
+#
+# Supported Pixel Depths
+#
+CONFIG_NX_DISABLE_1BPP=y
+CONFIG_NX_DISABLE_2BPP=y
+CONFIG_NX_DISABLE_4BPP=y
+CONFIG_NX_DISABLE_8BPP=y
+# CONFIG_NX_DISABLE_16BPP is not set
+CONFIG_NX_DISABLE_24BPP=y
+CONFIG_NX_DISABLE_32BPP=y
+CONFIG_NX_PACKEDMSFIRST=y
+
+#
+# Input Devices
+#
+# CONFIG_NX_MOUSE is not set
+# CONFIG_NX_KBD is not set
+
+#
+# Framed Window Borders
+#
+CONFIG_NXTK_BORDERWIDTH=3
+CONFIG_NXTK_BORDERCOLOR1=0x8410
+CONFIG_NXTK_BORDERCOLOR2=0x4208
+CONFIG_NXTK_BORDERCOLOR3=0xc618
+# CONFIG_NXTK_AUTORAISE is not set
+
+#
+# Font Selections
+#
+CONFIG_NXFONTS_CHARBITS=7
+# CONFIG_NXFONT_MONO5X8 is not set
+# CONFIG_NXFONT_SANS17X22 is not set
+# CONFIG_NXFONT_SANS20X26 is not set
+# CONFIG_NXFONT_SANS23X27 is not set
+# CONFIG_NXFONT_SANS22X29 is not set
+# CONFIG_NXFONT_SANS28X37 is not set
+# CONFIG_NXFONT_SANS39X48 is not set
+# CONFIG_NXFONT_SANS17X23B is not set
+# CONFIG_NXFONT_SANS20X27B is not set
+# CONFIG_NXFONT_SANS22X29B is not set
+# CONFIG_NXFONT_SANS28X37B is not set
+# CONFIG_NXFONT_SANS40X49B is not set
+# CONFIG_NXFONT_SERIF22X29 is not set
+# CONFIG_NXFONT_SERIF29X37 is not set
+# CONFIG_NXFONT_SERIF38X48 is not set
+CONFIG_NXFONT_SERIF22X28B=y
+# CONFIG_NXFONT_SERIF27X38B is not set
+# CONFIG_NXFONT_SERIF38X49B is not set
+# CONFIG_NXCONSOLE is not set
+
+#
+# NX Multi-user only options
+#
+# CONFIG_NX_MULTIUSER is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=2
+# CONFIG_GRAN 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 is not set
+
+#
+# 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=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
+# CONFIG_LIBC_STRERROR 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
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST 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_NSH is not set
+# 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=y
+CONFIG_EXAMPLES_NXLINES_VPLANE=0
+CONFIG_EXAMPLES_NXLINES_DEVNO=0
+CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0
+CONFIG_EXAMPLES_NXLINES_LINEWIDTH=16
+CONFIG_EXAMPLES_NXLINES_LINECOLOR=0x861F
+CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=16
+CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0xFFE0
+CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0x87F0
+CONFIG_EXAMPLES_NXLINES_BPP=16
+# CONFIG_EXAMPLES_NXLINES_EXTERNINIT 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_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART 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_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=y
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_LINELEN=64
+CONFIG_NSH_NESTDEPTH=3
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_CONSOLE=y
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+# CONFIG_NXWIDGETS is not set
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# 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
+#
diff --git a/nuttx/configs/mikroe-stm32f4/nxlines/setenv.sh b/nuttx/configs/mikroe-stm32f4/nxlines/setenv.sh
new file mode 100755
index 000000000..1dc5b1806
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nxlines/setenv.sh
@@ -0,0 +1,77 @@
+#!/bin/bash
+# configs/stm32f4discovery/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 under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+export TOOLCHAIN_BIN="/home/ken/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/mikroe-stm32f4/nxtext/Make.defs b/nuttx/configs/mikroe-stm32f4/nxtext/Make.defs
new file mode 100644
index 000000000..b04c5126d
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nxtext/Make.defs
@@ -0,0 +1,111 @@
+############################################################################
+# configs/mikroe-stm32f4/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
+
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+ 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 = $(ARCROSSDEV)ar rcs
+NM = $(ARCROSSDEV)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
+else
+ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
+endif
+
+ARCHCFLAGS = -fno-builtin
+ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
+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/mikroe-stm32f4/nxtext/defconfig b/nuttx/configs/mikroe-stm32f4/nxtext/defconfig
new file mode 100644
index 000000000..6f7f569b3
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nxtext/defconfig
@@ -0,0 +1,797 @@
+#
+# 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=y
+# 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=y
+
+#
+# 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_SAM3U is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+CONFIG_ARCH_CORTEXM4=y
+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_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_EABI=y
+
+#
+# STM32 Configuration Options
+#
+# 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_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=y
+# 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_STM32F40XX=y
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKPSRAM is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CAN2 is not set
+# CONFIG_STM32_CCMDATARAM is not set
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_CRYP 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_DCMI is not set
+# CONFIG_STM32_ETHMAC is not set
+# CONFIG_STM32_FSMC is not set
+# CONFIG_STM32_HASH is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+# CONFIG_STM32_I2C3 is not set
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_OTGFS is not set
+# CONFIG_STM32_OTGHS is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_RNG is not set
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_SPI3 is not set
+CONFIG_STM32_SYSCFG=y
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+# CONFIG_STM32_TIM4 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_TIM9 is not set
+# CONFIG_STM32_TIM10 is not set
+# CONFIG_STM32_TIM11 is not set
+# CONFIG_STM32_TIM12 is not set
+# CONFIG_STM32_TIM13 is not set
+# CONFIG_STM32_TIM14 is not set
+# CONFIG_STM32_USART1 is not set
+# 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_USART6 is not set
+# CONFIG_STM32_WWDG is not set
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_FLASH_PREFETCH is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
+# CONFIG_STM32_CCMEXCLUDE is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# External Memory 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=16717
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_SIZE=114688
+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
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set
+CONFIG_ARCH_BOARD_MIKROE_STM32F4=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="mikroe-stm32f4"
+
+#
+# Common Board Options
+#
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+# CONFIG_MIKROE_FLASH is not set
+# CONFIG_MIKROE_RAMMTD 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=2013
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=27
+# 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=y
+# CONFIG_SCHED_STARTHOOK is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nxtext_main"
+CONFIG_DISABLE_OS_API=y
+# CONFIG_DISABLE_CLOCK is not set
+# CONFIG_DISABLE_POSIX_TIMERS is not set
+# CONFIG_DISABLE_PTHREAD is not set
+# CONFIG_DISABLE_SIGNALS is not set
+# CONFIG_DISABLE_MQUEUE is not set
+# CONFIG_DISABLE_ENVIRON is not set
+
+#
+# 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=2048
+CONFIG_USERMAIN_STACKSIZE=2048
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+
+#
+# Device Drivers
+#
+CONFIG_DISABLE_POLL=y
+# CONFIG_DEV_NULL is not set
+# 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 is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_SPI is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+CONFIG_LCD=y
+# CONFIG_LCD_NOGETRUN is not set
+CONFIG_LCD_MAXCONTRAST=63
+CONFIG_LCD_MAXPOWER=1
+# CONFIG_LCD_P14201 is not set
+# CONFIG_LCD_NOKIA6100 is not set
+CONFIG_LCD_MIO283QT2=y
+# CONFIG_LCD_UG9664HSWAG01 is not set
+# CONFIG_LCD_ST7567 is not set
+# CONFIG_LCD_UG2864AMBAG01 is not set
+# CONFIG_LCD_SSD1289 is not set
+CONFIG_LCD_LANDSCAPE=y
+# CONFIG_LCD_PORTRAIT is not set
+# CONFIG_LCD_RPORTRAIT is not set
+# CONFIG_LCD_RLANDSCAPE 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 is not set
+# CONFIG_USBDEV 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=y
+CONFIG_SYSLOG_CHAR=y
+CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
+
+#
+# Graphics Support
+#
+CONFIG_NX=y
+CONFIG_NX_LCDDRIVER=y
+CONFIG_NX_NPLANES=1
+# CONFIG_NX_WRITEONLY is not set
+
+#
+# Supported Pixel Depths
+#
+CONFIG_NX_DISABLE_1BPP=y
+CONFIG_NX_DISABLE_2BPP=y
+CONFIG_NX_DISABLE_4BPP=y
+CONFIG_NX_DISABLE_8BPP=y
+# CONFIG_NX_DISABLE_16BPP is not set
+CONFIG_NX_DISABLE_24BPP=y
+CONFIG_NX_DISABLE_32BPP=y
+CONFIG_NX_PACKEDMSFIRST=y
+
+#
+# Input Devices
+#
+# CONFIG_NX_MOUSE is not set
+# CONFIG_NX_KBD is not set
+
+#
+# Framed Window Borders
+#
+CONFIG_NXTK_BORDERWIDTH=3
+CONFIG_NXTK_BORDERCOLOR1=0x8410
+CONFIG_NXTK_BORDERCOLOR2=0x4208
+CONFIG_NXTK_BORDERCOLOR3=0xc618
+# CONFIG_NXTK_AUTORAISE is not set
+
+#
+# Font Selections
+#
+CONFIG_NXFONTS_CHARBITS=7
+# CONFIG_NXFONT_MONO5X8 is not set
+# CONFIG_NXFONT_SANS17X22 is not set
+# CONFIG_NXFONT_SANS20X26 is not set
+# CONFIG_NXFONT_SANS23X27 is not set
+# CONFIG_NXFONT_SANS22X29 is not set
+# CONFIG_NXFONT_SANS28X37 is not set
+# CONFIG_NXFONT_SANS39X48 is not set
+# CONFIG_NXFONT_SANS17X23B is not set
+# CONFIG_NXFONT_SANS20X27B is not set
+# CONFIG_NXFONT_SANS22X29B is not set
+# CONFIG_NXFONT_SANS28X37B is not set
+# CONFIG_NXFONT_SANS40X49B is not set
+# CONFIG_NXFONT_SERIF22X29 is not set
+# CONFIG_NXFONT_SERIF29X37 is not set
+# CONFIG_NXFONT_SERIF38X48 is not set
+CONFIG_NXFONT_SERIF22X28B=y
+# CONFIG_NXFONT_SERIF27X38B is not set
+# CONFIG_NXFONT_SERIF38X49B is not set
+# CONFIG_NXCONSOLE is not set
+
+#
+# NX Multi-user only options
+#
+# CONFIG_NX_MULTIUSER is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=2
+# CONFIG_GRAN 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 is not set
+
+#
+# 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=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
+# CONFIG_LIBC_STRERROR 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
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST 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_NSH is not set
+# 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=y
+
+#
+# Basic Configuration of the example
+#
+# CONFIG_EXAMPLES_NXTEXT_BUILTIN is not set
+CONFIG_EXAMPLES_NXTEXT_VPLANE=0
+CONFIG_EXAMPLES_NXTEXT_DEVNO=0
+CONFIG_EXAMPLES_NXTEXT_BPP=16
+CONFIG_EXAMPLES_NXTEXT_BMCACHE=128
+CONFIG_EXAMPLES_NXTEXT_GLCACHE=16
+
+#
+# Example Color Configuration
+#
+CONFIG_EXAMPLES_NXTEXT_DEFAULT_COLORS=y
+
+#
+# Example Font Configuration
+#
+CONFIG_EXAMPLES_NXTEXT_DEFAULT_FONT=y
+# CONFIG_EXAMPLES_NXTEXT_EXTERNINIT 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_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART 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_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=y
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_LINELEN=64
+CONFIG_NSH_NESTDEPTH=3
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_CONSOLE=y
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+# CONFIG_NXWIDGETS is not set
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# 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
+#
diff --git a/nuttx/configs/mikroe-stm32f4/nxtext/setenv.sh b/nuttx/configs/mikroe-stm32f4/nxtext/setenv.sh
new file mode 100755
index 000000000..1dc5b1806
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/nxtext/setenv.sh
@@ -0,0 +1,77 @@
+#!/bin/bash
+# configs/stm32f4discovery/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 under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+export TOOLCHAIN_BIN="/home/ken/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/mikroe-stm32f4/src/Makefile b/nuttx/configs/mikroe-stm32f4/src/Makefile
index bf88711ef..c166e1926 100644
--- a/nuttx/configs/mikroe-stm32f4/src/Makefile
+++ b/nuttx/configs/mikroe-stm32f4/src/Makefile
@@ -90,7 +90,7 @@ ifeq ($(CONFIG_INPUT),y)
CSRCS += up_touchscreen.c
endif
-ifeq ($(ARCH_CONFIG_LCD_MIO283QT2),y)
+ifeq ($(CONFIG_LCD_MIO283QT2),y)
CSRCS += up_mio283qt2.c
endif
diff --git a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
index ab9602b87..f21229e42 100644
--- a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
+++ b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
@@ -115,6 +115,70 @@
# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5)
#endif
+/* TFT LCD Controller GPIOs
+ *
+ * PE8, LCD_RST -- Low value holds in reset
+ * PE15, LCD_CS -- Low value selects LCD
+ * PE9, LCD_BLED -- Backlight -- Low value turns off
+ * PE12, RS -- High values selects data
+ *
+ * PE10, PMPRD -- Low to read from the LCD
+ * PE11, PMPWR -- Low to write to the LCD
+ *
+ */
+
+#define GPIO_LCD_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN8)
+
+#define GPIO_LCD_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15)
+#define LCD_CS_PIN GPIO_PIN15
+
+#define GPIO_LCD_BLED (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN9)
+
+#define GPIO_LCD_RS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN12)
+#define LCD_RS_PIN GPIO_PIN12
+
+#define GPIO_LCD_PMPRD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN10)
+#define LCD_PMPRD_PIN GPIO_PIN10
+
+#define GPIO_LCD_PMPWR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN11)
+#define LCD_PMPWR_PIN GPIO_PIN11
+
+#define GPIO_LCD_T_D0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN0)
+
+#define GPIO_LCD_T_D1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN1)
+
+#define GPIO_LCD_T_D2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN2)
+
+#define GPIO_LCD_T_D3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN3)
+
+#define GPIO_LCD_T_D4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN4)
+
+#define GPIO_LCD_T_D5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN5)
+
+#define GPIO_LCD_T_D6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN6)
+
+#define GPIO_LCD_T_D7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_PORTE|GPIO_PIN7)
+
+#define GPIO_TP_DRIVEA (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
+
+#define GPIO_TP_DRIVEB (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
+
/****************************************************************************************************
* Public Types
****************************************************************************************************/
@@ -165,6 +229,31 @@ void weak_function stm32_usbinitialize(void);
#error "The Mikroe-STM32F4 board does not support HOST OTG, only device!"
#endif
+/****************************************************************************************************
+ * Name: stm32_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD. This function should be called early in the boot sequendce -- Even if the
+ * LCD is not enabled. In that case we should at a minimum at least disable the LCD backlight.
+ *
+ ****************************************************************************************************/
+
+#ifdef CONFIG_LCD_MIO283QT2
+void stm32_lcdinitialize(void);
+#endif
+
+/****************************************************************************************************
+ * Name: up_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD video hardware. The initial state of the LCD is fully initialized, display
+ * memory cleared, and the LCD ready to use, but with the power setting at 0 (full off).
+ *
+ ****************************************************************************************************/
+
+#ifdef CONFIG_LCD_MIO283QT2
+int up_lcdinitialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_MIKROE_STM32F4_SRC_MIKROE_STM32F4_INTERNAL_H */
-
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_boot.c b/nuttx/configs/mikroe-stm32f4/src/up_boot.c
index 4fd18f729..bbdd435c7 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_boot.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_boot.c
@@ -71,6 +71,12 @@
void stm32_boardinitialize(void)
{
+ /* Configure GPIOs for controlling the LCD */
+
+#ifdef CONFIG_LCD_MIO283QT2
+ stm32_lcdinitialize();
+#endif
+
/* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
* stm32_spiinitialize() has been brought into the link.
*/
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c b/nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c
index f06fd9861..c37c16b91 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_mio283qt2.c
@@ -8,6 +8,8 @@
* Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
*
+ * Modified: 2013 by Ken Pettit to support Mikroe-STM32F4 board.
+ *
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@@ -57,6 +59,7 @@
#include "up_arch.h"
#include "stm32.h"
+#include "stm32_gpio.h"
#include "mikroe-stm32f4-internal.h"
#ifdef CONFIG_LCD_MIO283QT2
@@ -66,10 +69,6 @@
**************************************************************************************/
/* Configuration **********************************************************************/
-#ifndef CONFIG_PIC32MX_PMP
-# error "CONFIG_PIC32MX_PMP is required to use the LCD"
-#endif
-
/* Define CONFIG_DEBUG_LCD to enable detailed LCD debug output. Verbose debug must
* also be enabled.
*/
@@ -84,59 +83,40 @@
# undef CONFIG_DEBUG_LCD
#endif
-/* PIC32MX7MMB LCD Hardware Definitions ***********************************************/
+/* Mikroe-STM32F4 Hardware Definitions ************************************************/
/* --- ---------------------------------- -------------------- ------------------------
* PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS
* (Family Data Sheet Table 1-1) (PIC32MX7 Schematic)
* --- ---------------------------------- -------------------- ------------------------
- * 6 RC1/T2CK LCD_RST TFT display
- * 43 PMA1/AETXD3/AN14/ERXD2/PMALH/RB14 LCD-CS# TFT display, HDR2 pin 3
- * 77 OC3/RD2 LCD_BLED LCD backlight LED
- * 44 PMA0/AETXD2/AN15/CN12/ERXD3/OCFB/ LCD-RS TFT display
- * PMALL/RB15
- *
- * 34 PMA13/AN10/RB10/CVREFOUT LCD-YD TFT display
- * 35 PMA12/AETXERR/AN11/ERXERR/RB11 LCD-XR TFT display
- * 41 PMA11/AECRS/AN12/ERXD0/RB12 LCD-YU TFT display
- * 42 PMA10/AECOL/AN13/ERXD1/RB13 LCD-XL TFT display
- *
- * 93 PMD0/RE0 PMPD0 TFT display, HDR1 pin 18
- * 94 PMD1/RE1 PMPD1 TFT display, HDR1 pin 17
- * 98 PMD2/RE2 PMPD2 TFT display, HDR1 pin 16
- * 99 PMD3/RE3 PMPD3 TFT display, HDR1 pin 15
- * 100 PMD4/RE4 PMPD4 TFT display, HDR1 pin 14
- * 3 PMD5/RE5 PMPD5 TFT display, HDR1 pin 13
- * 4 PMD6/RE6 PMPD6 TFT display, HDR1 pin 12
- * 5 PMD7/RE7 PMPD7 TFT display, HDR1 pin 11
- * 90 PMD8/C2RX/RG0 PMPD8 TFT display, HDR1 pin 10
- * 89 PMD9/C2TX/ETXERR/RG1 PMPD9 TFT display, HDR1 pin 9
- * 88 PMD10/C1TX/ETXD0/RF1 PMPD10 TFT display, HDR1 pin 8
- * 87 PMD11/C1RX/ETXD1/RF0 PMPD11 TFT display, HDR1 pin 7
- * 79 PMD12/ETXD2/IC5/RD12 PMPD12 TFT display, HDR1 pin 6
- * 80 PMD13/CN19/ETXD3/RD13 PMPD13 TFT display, HDR1 pin 5
- * 83 PMD14/CN15/ETXEN/RD6 PMPD14 TFT display, HDR1 pin 4
- * 84 PMD15/CN16/ETXCLK/RD7 PMPD15 TFT display, HDR1 pin 3
- *
- * 82 CN14/PMRD/RD5 PMPRD
- * 81 CN13/OC5/PMWR/RD4 PMPWR
+ * 39 PE8 LCD_RST TFT display
+ * 46 PE15 LCD-CS# TFT display
+ * 40 PE9 LCD_BLED LCD backlight LED
+ * 43 PE12 LCD-RS TFT display
+ *
+ *
+ * 97 RE0 T_D0 TFT display
+ * 98 RE1 T_D1 TFT display
+ * 1 RE2 T_D2 TFT display
+ * 2 RE3 T_D3 TFT display
+ * 3 RE4 T_D4 TFT display
+ * 4 RE5 T_D5 TFT display
+ * 5 RE6 T_D6 TFT display
+ * 38 RE7 T_D7 TFT display
+ *
+ * 41 PE10 PMPRD
+ * 42 RE11 PMPWR
+ *
+ * TOUCHSCREEN PIN CONFIGURATIONS
+ * PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS
+ * --- ---------------------------------- -------------------- ------------------------
+ * 35 PB0 LCD-YD TFT display
+ * ? LCD-XR TFT display
+ * ? LCD-YU TFT display
+ * 36 PB1 LCD-XL TFT display
+ * 95 PB8 DRIVEA TFT display
+ * 96 PB9 DRIVEB TFT display
*/
-/* RC1, Reset -- Low value holds in reset */
-
-#define GPIO_LCD_RST (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTC|GPIO_PIN1)
-
-/* RB14, LCD select -- Low value selects LCD */
-
-#define GPIO_LCD_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN14)
-
-/* RD2, Backlight -- Low value turns off */
-
-#define GPIO_LCD_BLED (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN2)
-
-/* RB15, RS -- High values selects data */
-
-#define GPIO_LCD_RS (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTB|GPIO_PIN15)
-
/* Debug ******************************************************************************/
#ifdef CONFIG_DEBUG_LCD
@@ -151,12 +131,11 @@
* Private Type Definition
**************************************************************************************/
-struct pic32mx7mmb_dev_s
+struct stm32f4_dev_s
{
struct mio283qt2_lcd_s dev; /* The externally visible part of the driver */
- bool data; /* true=data selected */
- bool selected; /* true=LCD selected */
- bool reading; /* true=We are in a read sequence */
+ bool grammode; /* true=Writing to GRAM (16-bit write vs 8-bit) */
+ bool firstread;/* First GRAM read? */
FAR struct lcd_dev_s *drvr; /* The saved instance of the LCD driver */
};
@@ -165,14 +144,14 @@ struct pic32mx7mmb_dev_s
**************************************************************************************/
/* Low Level LCD access */
-static void pic32mx_select(FAR struct mio283qt2_lcd_s *dev);
-static void pic32mx_deselect(FAR struct mio283qt2_lcd_s *dev);
-static void pic32mx_index(FAR struct mio283qt2_lcd_s *dev, uint8_t index);
-#ifndef CONFIG_MIO283QT2_WRONLY
-static uint16_t pic32mx_read(FAR struct mio283qt2_lcd_s *dev);
+static void stm32_select(FAR struct mio283qt2_lcd_s *dev);
+static void stm32_deselect(FAR struct mio283qt2_lcd_s *dev);
+static void stm32_index(FAR struct mio283qt2_lcd_s *dev, uint8_t index);
+#if !defined(CONFIG_MIO283QT2_WRONLY) && CONFIG_LCD_NOGETRUN != 1
+static uint16_t stm32_read(FAR struct mio283qt2_lcd_s *dev);
#endif
-static void pic32mx_write(FAR struct mio283qt2_lcd_s *dev, uint16_t data);
-static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power);
+static void stm32_write(FAR struct mio283qt2_lcd_s *dev, uint16_t data);
+static void stm32_backlight(FAR struct mio283qt2_lcd_s *dev, int power);
/**************************************************************************************
* Private Data
@@ -180,229 +159,277 @@ static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power);
/* This is the driver state structure (there is no retained state information) */
-static struct pic32mx7mmb_dev_s g_pic32mx7mmb_lcd =
+static struct stm32f4_dev_s g_stm32f4_lcd =
{
{
- .select = pic32mx_select,
- .deselect = pic32mx_deselect,
- .index = pic32mx_index,
-#ifndef CONFIG_MIO283QT2_WRONLY
- .read = pic32mx_read,
+ .select = stm32_select,
+ .deselect = stm32_deselect,
+ .index = stm32_index,
+#if !defined(CONFIG_MIO283QT2_WRONLY) && CONFIG_LCD_NOGETRUN != 1
+ .read = stm32_read,
#endif
- .write = pic32mx_write,
- .backlight = pic32mx_backlight
+ .write = stm32_write,
+ .backlight = stm32_backlight
}
};
+static uint32_t * volatile g_portsetreset = (uint32_t *) STM32_GPIOE_BSRR;
+
/**************************************************************************************
* Private Functions
**************************************************************************************/
/**************************************************************************************
- * Name: pic32mx_command
+ * Name: stm32_tinydelay
*
* Description:
- * Configure to write an LCD command
+ * Delay for a few hundered NS.
*
**************************************************************************************/
-static void pic32mx_command(FAR struct pic32mx7mmb_dev_s *priv)
+static void stm32_tinydelay(void)
{
- /* Low selects command */
+ volatile uint8_t x = 0;
- if (priv->data)
- {
- pic32mx_gpiowrite(GPIO_LCD_RS, false);
-
- priv->data = false; /* Command, not data */
- priv->reading = false; /* No read sequence in progress */
- }
+ for (x = 1; x > 0; x--)
+ ;
}
/**************************************************************************************
- * Name: pic32mx_data
+ * Name: stm32_command
*
* Description:
- * Configure to read or write LCD data
+ * Configure to write an LCD command
*
**************************************************************************************/
-static void pic32mx_data(FAR struct pic32mx7mmb_dev_s *priv)
+static inline void stm32_command(void)
{
- /* Hi selects data */
+ uint32_t * volatile portsetreset = (uint32_t *) STM32_GPIOE_BSRR;
- if (!priv->data)
- {
- pic32mx_gpiowrite(GPIO_LCD_RS, true);
+ /* Low selects command */
- priv->data = true; /* Data, not command */
- priv->reading = false; /* No read sequence in progress */
- }
+ *portsetreset = (1 << LCD_RS_PIN) << 16;
}
/**************************************************************************************
- * Name: pic32mx_data
+ * Name: stm32_data
*
* Description:
- * Wait until the PMP is no longer busy
+ * Configure to read or write LCD data
*
**************************************************************************************/
-static void pic32mx_busywait(void)
+static inline void stm32_data(void)
{
- while ((getreg32(PIC32MX_PMP_MODE) & PMP_MODE_BUSY) != 0);
+ /* Hi selects data */
+
+ *g_portsetreset = 1 << LCD_RS_PIN;
}
/**************************************************************************************
- * Name: pic32mx_select
+ * Name: stm32_select
*
* Description:
* Select the LCD device
*
**************************************************************************************/
-static void pic32mx_select(FAR struct mio283qt2_lcd_s *dev)
+static void stm32_select(FAR struct mio283qt2_lcd_s *dev)
{
- FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev;
-
/* CS low selects */
- if (!priv->selected)
- {
- pic32mx_gpiowrite(GPIO_LCD_CS, false);
-
- priv->selected = true; /* LCD selected */
- priv->reading = false; /* No read sequence in progress */
- }
+ *g_portsetreset = (1 << LCD_CS_PIN) << 16;
}
/**************************************************************************************
- * Name: pic32mx_deselect
+ * Name: stm32_deselect
*
* Description:
* De-select the LCD device
*
**************************************************************************************/
-static void pic32mx_deselect(FAR struct mio283qt2_lcd_s *dev)
+static void stm32_deselect(FAR struct mio283qt2_lcd_s *dev)
{
- FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev;
-
/* CS high de-selects */
- if (priv->selected)
- {
- pic32mx_gpiowrite(GPIO_LCD_CS, true);
-
- priv->selected = false; /* LCD not selected */
- priv->reading = false; /* No read sequence in progress */
- }
+ *g_portsetreset = 1 << LCD_CS_PIN;
}
/**************************************************************************************
- * Name: pic32mx_index
+ * Name: stm32_index
*
* Description:
* Set the index register
*
**************************************************************************************/
-static void pic32mx_index(FAR struct mio283qt2_lcd_s *dev, uint8_t index)
+static void stm32_index(FAR struct mio283qt2_lcd_s *dev, uint8_t index)
{
- FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev;
+ FAR struct stm32f4_dev_s *priv = (FAR struct stm32f4_dev_s *)dev;
- /* Make sure that the PMP is not busy from the last transaction. Read data is not
- * available until the busy bit becomes zero.
+ /* Setup to write in command mode (vs data mode) */
+
+ stm32_command();
+
+ /* Write the index register to the 8-bit GPIO pin bus. We are violating the
+ * datasheet here a little by driving the WR pin low at the same time as
+ * the data, but the fact is that all ASIC logic will latch on the rising
+ * edge of WR anyway, not the falling edge. We are just shaving off a few
+ * cycles every time this routine is called, which will be farirly often.
+ */
+
+ *g_portsetreset = index | ((uint8_t) (~index) << 16) |
+ ((1 << LCD_PMPWR_PIN) << 16);
+
+ /* Record if we are accessing GRAM or not (16 vs 8 bit accesses)
+ * NOTE. This also serves as a delay between WR low to WR high
+ * transition.
*/
- pic32mx_busywait();
+ priv->grammode = index == 0x22;
+ priv->firstread = true;
+
+ /* Now raise the WR line */
- /* Write the 8-bit command (on the 16-bit data bus) */
+ *g_portsetreset = (1 << LCD_PMPWR_PIN);
- pic32mx_command(priv);
- putreg16((uint16_t)index, PIC32MX_PMP_DIN);
+ /* Back to data mode to read/write the data */
+
+ stm32_data();
}
/**************************************************************************************
- * Name: pic32mx_read
+ * Name: stm32_read
*
* Description:
* Read LCD data (GRAM data or register contents)
*
**************************************************************************************/
-#ifndef CONFIG_MIO283QT2_WRONLY
-static uint16_t pic32mx_read(FAR struct mio283qt2_lcd_s *dev)
+#if !defined(CONFIG_MIO283QT2_WRONLY) && CONFIG_LCD_NOGETRUN != 1
+static uint16_t stm32_read(FAR struct mio283qt2_lcd_s *dev)
{
- FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev;
+ FAR struct stm32f4_dev_s *priv = (FAR struct stm32f4_dev_s *)dev;
+ uint32_t * volatile portsetreset = (uint32_t *) STM32_GPIOE_BSRR;
+ uint32_t * volatile portmode = (uint32_t *) STM32_GPIOE_MODER;
+ uint32_t * volatile portinput = (uint32_t *) STM32_GPIOE_IDR;
uint16_t data;
- /* Make sure that the PMP is not busy from the last transaction. Read data is not
- * available until the busy bit becomes zero.
- */
+ /* Set the I/O Port to input mode. Ugly, but fast. */
- pic32mx_busywait();
+ *portmode &= 0xFFFF0000;
- /* Read 16-bits of data */
+ /* Read the data */
- pic32mx_data(priv);
- data = getreg16(PIC32MX_PMP_DIN);
+ *portsetreset = (1 << LCD_PMPRD_PIN) << 16;
+ stm32_tinydelay();
+ data = *portinput & 0x00FF;
+ *portsetreset = (1 << LCD_PMPRD_PIN);
- /* We need to discard the first 16-bits of data that we read and re-read inorder
- * to get valid data (that is just the way that the PMP works).
- */
+ /* Test if a 16-bit read is needed (GRAM mode) */
- if (!priv->reading)
+ if (priv->grammode)
{
- data = getreg16(PIC32MX_PMP_DIN);
+ /* If this is the 1st GRAM read, then discard the dummy byte */
+
+ if (priv->firstread)
+ {
+ priv->firstread = false;
+ *portsetreset = (1 << LCD_PMPRD_PIN) << 16;
+ stm32_tinydelay();
+ data = *portinput;
+ *portsetreset = (1 << LCD_PMPRD_PIN);
+ }
+
+ /* Okay, a 16-bit read is actually a 24-bit read from the LCD.
+ * this is because the read color format of the MIO283QT-2 is a bit
+ * different than the 16-bit write color format. During a read,
+ * the R,G and B samples are read on subsequent bytes, and the
+ * data is MSB aligned. We must re-construct the 16-bit 565 data.
+ */
+
+ /* Clip RED sample to 5-bits and shit to MSB */
+
+ data = (data & 0xF8) << 8;
+
+ /* Now read Green sample */
+
+ *portsetreset = (1 << LCD_PMPRD_PIN) << 16;
+ stm32_tinydelay();
+ data |= (*portinput & 0x00FC) << 3;
+ *portsetreset = (1 << LCD_PMPRD_PIN);
+
+ /* Now read Blue sample */
+
+ *portsetreset = (1 << LCD_PMPRD_PIN) << 16;
+ stm32_tinydelay();
+ data |= (*portinput & 0x00F8) >> 3;
+ *portsetreset = (1 << LCD_PMPRD_PIN);
}
+ /* Put the port back in output mode. Ugly, but fast. */
+
+ *portmode |= 0x00005555;
+
return data;
}
#endif
/**************************************************************************************
- * Name: pic32mx_write
+ * Name: stm32_write
*
* Description:
* Write LCD data (GRAM data or register contents)
*
**************************************************************************************/
-static void pic32mx_write(FAR struct mio283qt2_lcd_s *dev, uint16_t data)
+static void stm32_write(FAR struct mio283qt2_lcd_s *dev, uint16_t data)
{
- FAR struct pic32mx7mmb_dev_s *priv = (FAR struct pic32mx7mmb_dev_s *)dev;
+ FAR struct stm32f4_dev_s *priv = (FAR struct stm32f4_dev_s *)dev;
- /* Make sure that the PMP is not busy from the last transaction */
-
- pic32mx_busywait();
+ /* Write the data register to the 8-bit GPIO pin bus. We are violating the
+ * datasheet here a little by driving the WR pin low at the same time as
+ * the data, but the fact is that all ASIC logic will latch on the rising
+ * edge of WR anyway, not the falling edge. We are just shaving off a few
+ * cycles every time this routine is called, which will be farirly often.
+ */
- /* Write 16-bits of data */
+ if (priv->grammode)
+ {
+ /* Need to write 16-bit pixel data (16 BPP). Write the upper pixel data first */
- pic32mx_data(priv);
- putreg16(data, PIC32MX_PMP_DIN);
+ *g_portsetreset = ((data>>8) & 0xFF) | (((~data>>8) & 0xFF) << 16) |
+ ((1 << LCD_PMPWR_PIN) << 16);
+ stm32_tinydelay();
+ *g_portsetreset = (1 << LCD_PMPWR_PIN);
+ }
- /* We are not in a write sequence */
+ /* Now write the lower 8-bit of data */
- priv->reading = false;
+ *g_portsetreset = (data & 0xFF) | ((~data & 0xFF) << 16) |
+ ((1 << LCD_PMPWR_PIN) << 16);
+ stm32_tinydelay();
+ *g_portsetreset = (1 << LCD_PMPWR_PIN);
}
/**************************************************************************************
- * Name: pic32mx_write
+ * Name: stm32_backlight
*
* Description:
- * Write LCD data (GRAM data or register contents)
+ * Set the backlight power level.
*
**************************************************************************************/
-static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power)
+static void stm32_backlight(FAR struct mio283qt2_lcd_s *dev, int power)
{
/* For now, we just control the backlight as a discrete. Pulse width modulation
* would be required to vary the backlight level. A low value turns the backlight
* off.
*/
- pic32mx_gpiowrite(GPIO_LCD_BLED, power > 0);
+ stm32_gpiowrite(GPIO_LCD_BLED, power > 0);
}
/**************************************************************************************
@@ -410,6 +437,54 @@ static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power)
**************************************************************************************/
/**************************************************************************************
+ * Name: stm32_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD. This function should be called early in the boot
+ * sequendce -- Even if the LCD is not enabled. In that case we should
+ * at a minimum at least disable the LCD backlight.
+ *
+ **************************************************************************************/
+
+void stm32_lcdinitialize(void)
+{
+ /* Configure all LCD discrete controls. LCD will be left in this state:
+ * 1. Held in reset,
+ * 2. Not selected,
+ * 3. Backlight off,
+ * 4. Command selected.
+ */
+
+#ifdef CONFIG_LCD_MIO283QT2
+ stm32_configgpio(GPIO_LCD_RST);
+ stm32_configgpio(GPIO_LCD_CS);
+ stm32_configgpio(GPIO_LCD_BLED);
+ stm32_gpiowrite(GPIO_LCD_BLED, false);
+ stm32_configgpio(GPIO_LCD_RS);
+ stm32_configgpio(GPIO_LCD_PMPWR);
+ stm32_configgpio(GPIO_LCD_PMPRD);
+
+ /* Configure PE0-7 for output */
+
+ stm32_configgpio(GPIO_LCD_T_D0);
+ stm32_configgpio(GPIO_LCD_T_D1);
+ stm32_configgpio(GPIO_LCD_T_D2);
+ stm32_configgpio(GPIO_LCD_T_D3);
+ stm32_configgpio(GPIO_LCD_T_D4);
+ stm32_configgpio(GPIO_LCD_T_D5);
+ stm32_configgpio(GPIO_LCD_T_D6);
+ stm32_configgpio(GPIO_LCD_T_D7);
+
+#else
+ /* Just configure the backlight control as an output and turn off the
+ * backlight for now.
+ */
+
+ stm32_configgpio(GPIO_LCD_BLED);
+#endif
+}
+
+/**************************************************************************************
* Name: up_lcdinitialize
*
* Description:
@@ -421,66 +496,37 @@ static void pic32mx_backlight(FAR struct mio283qt2_lcd_s *dev, int power)
int up_lcdinitialize(void)
{
- uint32_t regval;
-
/* Only initialize the driver once. NOTE: The LCD GPIOs were already configured
- * by pic32mx_lcdinitialize.
+ * by stm32_lcdinitialize.
*/
- if (!g_pic32mx7mmb_lcd.drvr)
+ if (!g_stm32f4_lcd.drvr)
{
lcdvdbg("Initializing\n");
/* Hold the LCD in reset (active low) */
- pic32mx_gpiowrite(GPIO_LCD_RST, false);
-
- /* Configure PMP to support the LCD */
-
- putreg32(0, PIC32MX_PMP_MODE);
- putreg32(0, PIC32MX_PMP_AEN);
- putreg32(0, PIC32MX_PMP_CON);
-
- /* Set LCD timing values, PMP master mode 2, 16-bit mode, no address
- * increment, and no interrupts.
- */
-
- regval = (PMP_MODE_WAITE_RD(0) | PMP_MODE_WAITM(3) | PMP_MODE_WAITB_1TPB |
- PMP_MODE_MODE_MODE2 | PMP_MODE_MODE16 | PMP_MODE_INCM_NONE |
- PMP_MODE_IRQM_NONE);
- putreg32(regval, PIC32MX_PMP_MODE);
-
- /* Enable the PMP for reading and writing */
-
- regval = (PMP_CON_CSF_ADDR1415 | PMP_CON_PTRDEN | PMP_CON_PTWREN |
- PMP_CON_ADRMUX_NONE | PMP_CON_ON);
- putreg32(regval, PIC32MX_PMP_CON);
+ stm32_gpiowrite(GPIO_LCD_RST, false);
/* Bring the LCD out of reset */
up_mdelay(5);
- pic32mx_gpiowrite(GPIO_LCD_RST, true);
+ stm32_gpiowrite(GPIO_LCD_RST, true);
/* Configure and enable the LCD */
up_mdelay(50);
- g_pic32mx7mmb_lcd.drvr = mio283qt2_lcdinitialize(&g_pic32mx7mmb_lcd.dev);
- if (!g_pic32mx7mmb_lcd.drvr)
+ g_stm32f4_lcd.drvr = mio283qt2_lcdinitialize(&g_stm32f4_lcd.dev);
+ if (!g_stm32f4_lcd.drvr)
{
lcddbg("ERROR: mio283qt2_lcdinitialize failed\n");
return -ENODEV;
}
}
- /* Clear the display (setting it to the color 0=black) */
-
-#if 0 /* Already done in the driver */
- mio283qt2_clear(g_pic32mx7mmb_lcd.drvr, 0);
-#endif
-
/* Turn the display off */
- g_pic32mx7mmb_lcd.drvr->setpower(g_pic32mx7mmb_lcd.drvr, 0);
+ g_stm32f4_lcd.drvr->setpower(g_stm32f4_lcd.drvr, 0);
return OK;
}
@@ -496,7 +542,7 @@ int up_lcdinitialize(void)
FAR struct lcd_dev_s *up_lcdgetdev(int lcddev)
{
DEBUGASSERT(lcddev == 0);
- return g_pic32mx7mmb_lcd.drvr;
+ return g_stm32f4_lcd.drvr;
}
/**************************************************************************************
@@ -511,41 +557,7 @@ void up_lcduninitialize(void)
{
/* Turn the display off */
- g_pic32mx7mmb_lcd.drvr->setpower(g_pic32mx7mmb_lcd.drvr, 0);
+ g_stm32f4_lcd.drvr->setpower(g_stm32f4_lcd.drvr, 0);
}
#endif /* CONFIG_LCD_MIO283QT2 */
-
-/****************************************************************************
- * Name: pic32mx_lcdinitialize
- *
- * Description:
- * Initialize the LCD. This function should be called early in the boot
- * sequendce -- Even if the LCD is not enabled. In that case we should
- * at a minimum at least disable the LCD backlight.
- *
- ****************************************************************************/
-
-void pic32mx_lcdinitialize(void)
-{
- /* Configure all LCD discrete controls. LCD will be left in this state:
- * 1. Held in reset,
- * 2. Not selected,
- * 3. Backlight off,
- * 4. Command selected.
- */
-
-#ifdef CONFIG_LCD_MIO283QT2
- pic32mx_configgpio(GPIO_LCD_RST);
- pic32mx_configgpio(GPIO_LCD_CS);
- pic32mx_configgpio(GPIO_LCD_BLED);
- pic32mx_configgpio(GPIO_LCD_RS);
-
-#else
- /* Just configure the backlight control as an output and turn off the
- * backlight for now.
- */
-
- pic32mx_configgpio(GPIO_LCD_BLED);
-#endif
-}
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_nsh.c b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
index 226a715f6..9fcf160f9 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
@@ -331,5 +331,18 @@ int nsh_archinitialize(void)
}
#endif
+#ifdef CONFIG_LCD_MIO283QT2
+ /* Configure the TFT LCD module */
+
+ message("nsh_archinitialize: Initializing TFT LCD module\n");
+
+ ret = up_lcdinitialize();
+ if (ret != OK)
+ {
+ message("nsh_archinitialize: Failed to initialize TFT LCD module\n");
+ }
+
+#endif
+
return OK;
}
diff --git a/nuttx/configs/mikroe-stm32f4/usbnsh/defconfig b/nuttx/configs/mikroe-stm32f4/usbnsh/defconfig
index 02e12d903..525ba0038 100644
--- a/nuttx/configs/mikroe-stm32f4/usbnsh/defconfig
+++ b/nuttx/configs/mikroe-stm32f4/usbnsh/defconfig
@@ -208,6 +208,7 @@ CONFIG_STM32_SPI=y
# CONFIG_STM32_JTAG_FULL_ENABLE is not set
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
# CONFIG_STM32_FORCEPOWER is not set
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
# CONFIG_STM32_CCMEXCLUDE is not set
@@ -427,7 +428,6 @@ CONFIG_MTD_SMART_SECTOR_SIZE=512
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
@@ -643,7 +643,6 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_NX is not set
# CONFIG_EXAMPLES_NXCONSOLE is not set
# CONFIG_EXAMPLES_NXFFS is not set
-# CONFIG_EXAMPLES_SMART is not set
# CONFIG_EXAMPLES_NXFLAT is not set
# CONFIG_EXAMPLES_NXHELLO is not set
# CONFIG_EXAMPLES_NXIMAGE is not set
@@ -660,6 +659,7 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_SERLOOP is not set
# CONFIG_EXAMPLES_FLASH_TEST is not set
# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART is not set
# CONFIG_EXAMPLES_TELNETD is not set
# CONFIG_EXAMPLES_THTTPD is not set
# CONFIG_EXAMPLES_TIFF is not set
diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig
index 1dbee5113..16fc8bb8e 100644
--- a/nuttx/drivers/lcd/Kconfig
+++ b/nuttx/drivers/lcd/Kconfig
@@ -182,6 +182,13 @@ config NOKIA6100_RGBORD
Required LCD driver settings:
endif
+config LCD_MIO283QT2
+ bool "MIO283QT-2 TFT LCD Display Module"
+ default n
+ ---help---
+ OLED Display Module, MIO283QT-2, Multi-Inno Technology, Co.
+ based on the Himax HX8347-D LCD controller.
+
config LCD_UG9664HSWAG01
bool "UG-9664HSWAG01 OLED Display Module"
default n