summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-07 23:34:16 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-07 23:34:16 +0000
commit8e0a238d47834fc8a070ab19c73208db41049099 (patch)
treefb3aedc16092dcaa37ba67bbd6ee0bd24e7f60fd /nuttx
parentf1e1db08d53f02b5fd39d8ab4e33cd9e853a4d6c (diff)
downloadpx4-nuttx-8e0a238d47834fc8a070ab19c73208db41049099.tar.gz
px4-nuttx-8e0a238d47834fc8a070ab19c73208db41049099.tar.bz2
px4-nuttx-8e0a238d47834fc8a070ab19c73208db41049099.zip
More support for the Shenzhou board
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5110 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/configs/shenzhou/README.txt14
-rw-r--r--nuttx/configs/shenzhou/include/board.h16
-rw-r--r--nuttx/configs/shenzhou/scripts/ld.script106
-rw-r--r--nuttx/configs/shenzhou/scripts/ld.script.dfu106
-rw-r--r--nuttx/configs/shenzhou/src/Makefile122
-rw-r--r--nuttx/configs/shenzhou/src/shenzhou-internal.h8
-rw-r--r--nuttx/configs/shenzhou/src/up_autoleds.c401
-rw-r--r--nuttx/configs/shenzhou/src/up_boot.c102
-rw-r--r--nuttx/configs/shenzhou/src/up_buttons.c169
-rw-r--r--nuttx/configs/shenzhou/src/up_can.c133
-rw-r--r--nuttx/configs/shenzhou/src/up_composite.c163
-rw-r--r--nuttx/configs/shenzhou/src/up_cxxinitialize.c155
-rw-r--r--nuttx/configs/shenzhou/src/up_leds.c401
-rw-r--r--nuttx/configs/shenzhou/src/up_nsh.c218
-rw-r--r--nuttx/configs/shenzhou/src/up_spi.c204
-rw-r--r--nuttx/configs/shenzhou/src/up_usb.c294
-rw-r--r--nuttx/configs/shenzhou/src/up_usbmsc.c159
-rw-r--r--nuttx/configs/shenzhou/src/up_userleds.c131
-rw-r--r--nuttx/configs/shenzhou/src/up_watchdog.c136
-rw-r--r--nuttx/configs/stm3210e-eval/RIDE/appconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/RIDE/setenv.sh2
-rwxr-xr-xnuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld2
-rw-r--r--nuttx/configs/stm3210e-eval/buttons/appconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/buttons/setenv.sh2
-rwxr-xr-xnuttx/configs/stm3210e-eval/nsh/setenv.sh2
-rwxr-xr-xnuttx/configs/stm3210e-eval/nsh2/setenv.sh2
-rwxr-xr-xnuttx/configs/stm3210e-eval/nx/setenv.sh2
-rw-r--r--nuttx/configs/stm3210e-eval/nxlines/appconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/nxlines/setenv.sh2
-rw-r--r--nuttx/configs/stm3210e-eval/nxtext/appconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/nxtext/setenv.sh2
-rw-r--r--nuttx/configs/stm3210e-eval/ostest/appconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/setenv.sh2
-rwxr-xr-xnuttx/configs/stm3210e-eval/pm/setenv.sh2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_buttons.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_composite.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_deselectlcd.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_deselectnor.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_deselectsram.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_extcontext.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_extmem.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_lm75.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_nsh.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_selectlcd.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_selectnor.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_selectsram.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_spi.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_usbdev.c2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_usbmsc.c2
-rw-r--r--nuttx/configs/stm3210e-eval/usbserial/appconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbserial/setenv.sh2
-rw-r--r--nuttx/configs/stm3210e-eval/usbstorage/appconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbstorage/setenv.sh2
-rw-r--r--nuttx/configs/stm3220g-eval/dhcpd/appconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_selectlcd.c2
-rw-r--r--nuttx/configs/stm3240g-eval/dhcpd/appconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_deselectlcd.c2
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_selectlcd.c2
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_userleds.c4
59 files changed, 3064 insertions, 56 deletions
diff --git a/nuttx/configs/shenzhou/README.txt b/nuttx/configs/shenzhou/README.txt
index 72e4c8008..c87ccb1ca 100755
--- a/nuttx/configs/shenzhou/README.txt
+++ b/nuttx/configs/shenzhou/README.txt
@@ -662,19 +662,9 @@ Shenzhou-specific Configuration Options
For the Shenzhou board, the edge next to the row of buttons
is used as the top of the display in this orientation.
CONFIG_LCD_PORTRAIT - Define for 240x320 display "portrait"
- orientation support. In this orientation, the STM3210E-EVAL's
- LCD ribbon cable is at the bottom of the display. Default is
- 320x240 "landscape" orientation.
- In this orientation, the top of the display is to the left
- of the buttons (if the board is held so that the buttons are at the
- botton of the board).
+ orientation support.
CONFIG_LCD_RPORTRAIT - Define for 240x320 display "reverse
- portrait" orientation support. In this orientation, the
- STM3210E-EVAL's LCD ribbon cable is at the top of the display.
- Default is 320x240 "landscape" orientation.
- In this orientation, the top of the display is to the right
- of the buttons (if the board is held so that the buttons are at the
- botton of the board).
+ portrait" orientation support.
CONFIG_LCD_RDSHIFT - When reading 16-bit gram data, there appears
to be a shift in the returned data. This value fixes the offset.
Default 5.
diff --git a/nuttx/configs/shenzhou/include/board.h b/nuttx/configs/shenzhou/include/board.h
index 6a71bd89f..026a6adab 100644
--- a/nuttx/configs/shenzhou/include/board.h
+++ b/nuttx/configs/shenzhou/include/board.h
@@ -330,6 +330,22 @@ void stm32_board_clockconfig(void);
#endif
/************************************************************************************
+ * Name: stm32_ledinit, stm32_setled, and stm32_setleds
+ *
+ * Description:
+ * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
+ * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
+ * control the LEDs from user applications.
+ *
+ ************************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+EXTERN void stm32_ledinit(void);
+EXTERN void stm32_setled(int led, bool ledon);
+EXTERN void stm32_setleds(uint8_t ledset);
+#endif
+
+/************************************************************************************
* Name: stm32_selectrmii
*
* Description:
diff --git a/nuttx/configs/shenzhou/scripts/ld.script b/nuttx/configs/shenzhou/scripts/ld.script
new file mode 100644
index 000000000..5630b38df
--- /dev/null
+++ b/nuttx/configs/shenzhou/scripts/ld.script
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * configs/shenzhou/scripts/ld.script
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
+
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(_stext)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ _eronly = ABSOLUTE(.);
+
+ /* The STM32F107VC has 64Kb of SRAM beginning at the following address */
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } >sram
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } >sram
+ __exidx_end = ABSOLUTE(.);
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/shenzhou/scripts/ld.script.dfu b/nuttx/configs/shenzhou/scripts/ld.script.dfu
new file mode 100644
index 000000000..b1d41e0ab
--- /dev/null
+++ b/nuttx/configs/shenzhou/scripts/ld.script.dfu
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * configs/shenzhou/scripts/ld.script.dfu
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* Don't know if this is correct. Just 256K-48K (not testet) */
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08003000, LENGTH = 208K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(_stext)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ _eronly = ABSOLUTE(.);
+
+ /* The STM32F103Z has 64Kb of SRAM beginning at the following address */
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } >sram
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } >sram
+ __exidx_end = ABSOLUTE(.);
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile
new file mode 100644
index 000000000..e588cddde
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/Makefile
@@ -0,0 +1,122 @@
+############################################################################
+# configs/shenzhou/src/Makefile
+#
+# Copyright (C) 2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = up_boot.c up_spi.c
+
+ifeq ($(CONFIG_HAVE_CXX),y)
+CSRCS += up_cxxinitialize.c
+endif
+
+ifeq ($(CONFIG_ARCH_LEDS),y)
+CSRCS += up_autoleds.c
+else
+CSRCS += up_userleds.c
+
+ifeq ($(CONFIG_ARCH_BUTTONS),y)
+CSRCS += up_buttons.c
+endif
+
+ifeq ($(CONFIG_STM32_OTGFS),y)
+CSRCS += up_usb.c
+endif
+
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+CSRCS += up_nsh.c
+endif
+
+ifeq ($(CONFIG_USBMSC),y)
+CSRCS += up_usbmsc.c
+endif
+
+ifeq ($(CONFIG_USBDEV_COMPOSITE),y)
+CSRCS += up_composite.c
+endif
+
+ifeq ($(CONFIG_CAN),y)
+CSRCS += up_can.c
+endif
+
+ifeq ($(CONFIG_WATCHDOG),y)
+CSRCS += up_watchdog.c
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f libboard$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/configs/shenzhou/src/shenzhou-internal.h b/nuttx/configs/shenzhou/src/shenzhou-internal.h
index 1d63df0ae..2b490b187 100644
--- a/nuttx/configs/shenzhou/src/shenzhou-internal.h
+++ b/nuttx/configs/shenzhou/src/shenzhou-internal.h
@@ -76,7 +76,8 @@
* 59 PD12 WIRELESS_CS To the NRF24L01 2.4G wireless module
*/
-/* To be provided */
+#define GPIO_WIRELESS_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN12)
/* Buttons
*
@@ -151,7 +152,8 @@
* 46 PE15 DB15 To TFT LCD (CN13)
*/
-/* To be provided */
+#define GPIO_LCD_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
/* RS-485
*
@@ -171,7 +173,7 @@
* 95 PB8 USB_PWR Drives USB VBUS
*/
-#define GPIO_USB_PWR (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8)
/* Audio DAC
*
diff --git a/nuttx/configs/shenzhou/src/up_autoleds.c b/nuttx/configs/shenzhou/src/up_autoleds.c
new file mode 100644
index 000000000..996836c79
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_autoleds.c
@@ -0,0 +1,401 @@
+/****************************************************************************
+ * configs/shenzhou/src/up_autoleds.c
+ * arch/arm/src/board/up_autoleds.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+#include <nuttx/power/pm.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "shenzhou-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/* The following definitions map the encoded LED setting to GPIO settings */
+
+#define SHENZHOU_LED1 (1 << 0)
+#define SHENZHOU_LED2 (1 << 1)
+#define SHENZHOU_LED3 (1 << 2)
+#define SHENZHOU_LED4 (1 << 3)
+
+#define ON_SETBITS_SHIFT (0)
+#define ON_CLRBITS_SHIFT (4)
+#define OFF_SETBITS_SHIFT (8)
+#define OFF_CLRBITS_SHIFT (12)
+
+#define ON_BITS(v) ((v) & 0xff)
+#define OFF_BITS(v) (((v) >> 8) & 0x0ff)
+#define SETBITS(b) ((b) & 0x0f)
+#define CLRBITS(b) (((b) >> 4) & 0x0f)
+
+#define ON_SETBITS(v) (SETBITS(ON_BITS(v))
+#define ON_CLRBITS(v) (CLRBITS(ON_BITS(v))
+#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v))
+#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v))
+
+#define LED_STARTED_ON_SETBITS ((SHENZHOU_LED1) << ON_SETBITS_SHIFT)
+#define LED_STARTED_ON_CLRBITS ((SHENZHOU_LED2|SHENZHOU_LED3|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_STARTED_OFF_SETBITS (0 << OFF_SETBITS_SHIFT)
+#define LED_STARTED_OFF_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED2|SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_HEAPALLOCATE_ON_SETBITS ((SHENZHOU_LED2) << ON_SETBITS_SHIFT)
+#define LED_HEAPALLOCATE_ON_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED3|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_HEAPALLOCATE_OFF_SETBITS ((SHENZHOU_LED1) << OFF_SETBITS_SHIFT)
+#define LED_HEAPALLOCATE_OFF_CLRBITS ((SHENZHOU_LED2|SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_IRQSENABLED_ON_SETBITS ((SHENZHOU_LED1|SHENZHOU_LED2) << ON_SETBITS_SHIFT)
+#define LED_IRQSENABLED_ON_CLRBITS ((SHENZHOU_LED3|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_IRQSENABLED_OFF_SETBITS ((SHENZHOU_LED2) << OFF_SETBITS_SHIFT)
+#define LED_IRQSENABLED_OFF_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_STACKCREATED_ON_SETBITS ((SHENZHOU_LED3) << ON_SETBITS_SHIFT)
+#define LED_STACKCREATED_ON_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED2|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_STACKCREATED_OFF_SETBITS ((SHENZHOU_LED1|SHENZHOU_LED2) << OFF_SETBITS_SHIFT)
+#define LED_STACKCREATED_OFF_CLRBITS ((SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_INIRQ_ON_SETBITS ((SHENZHOU_LED1) << ON_SETBITS_SHIFT)
+#define LED_INIRQ_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_INIRQ_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_INIRQ_OFF_CLRBITS ((SHENZHOU_LED1) << OFF_CLRBITS_SHIFT)
+
+#define LED_SIGNAL_ON_SETBITS ((SHENZHOU_LED2) << ON_SETBITS_SHIFT)
+#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_SIGNAL_OFF_CLRBITS ((SHENZHOU_LED2) << OFF_CLRBITS_SHIFT)
+
+#define LED_ASSERTION_ON_SETBITS ((SHENZHOU_LED4) << ON_SETBITS_SHIFT)
+#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_ASSERTION_OFF_CLRBITS ((SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_PANIC_ON_SETBITS ((SHENZHOU_LED4) << ON_SETBITS_SHIFT)
+#define LED_PANIC_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_PANIC_OFF_CLRBITS ((SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+/**************************************************************************************
+ * Private Function Protototypes
+ **************************************************************************************/
+
+/* LED State Controls */
+
+static inline void led_clrbits(unsigned int clrbits);
+static inline void led_setbits(unsigned int setbits);
+static void led_setonoff(unsigned int bits);
+
+/* LED Power Management */
+
+#ifdef CONFIG_PM
+static void led_pm_notify(struct pm_callback_s *cb, enum pm_state_e pmstate);
+static int led_pm_prepare(struct pm_callback_s *cb, enum pm_state_e pmstate);
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const uint16_t g_ledbits[8] =
+{
+ (LED_STARTED_ON_SETBITS | LED_STARTED_ON_CLRBITS |
+ LED_STARTED_OFF_SETBITS | LED_STARTED_OFF_CLRBITS),
+
+ (LED_HEAPALLOCATE_ON_SETBITS | LED_HEAPALLOCATE_ON_CLRBITS |
+ LED_HEAPALLOCATE_OFF_SETBITS | LED_HEAPALLOCATE_OFF_CLRBITS),
+
+ (LED_IRQSENABLED_ON_SETBITS | LED_IRQSENABLED_ON_CLRBITS |
+ LED_IRQSENABLED_OFF_SETBITS | LED_IRQSENABLED_OFF_CLRBITS),
+
+ (LED_STACKCREATED_ON_SETBITS | LED_STACKCREATED_ON_CLRBITS |
+ LED_STACKCREATED_OFF_SETBITS | LED_STACKCREATED_OFF_CLRBITS),
+
+ (LED_INIRQ_ON_SETBITS | LED_INIRQ_ON_CLRBITS |
+ LED_INIRQ_OFF_SETBITS | LED_INIRQ_OFF_CLRBITS),
+
+ (LED_SIGNAL_ON_SETBITS | LED_SIGNAL_ON_CLRBITS |
+ LED_SIGNAL_OFF_SETBITS | LED_SIGNAL_OFF_CLRBITS),
+
+ (LED_ASSERTION_ON_SETBITS | LED_ASSERTION_ON_CLRBITS |
+ LED_ASSERTION_OFF_SETBITS | LED_ASSERTION_OFF_CLRBITS),
+
+ (LED_PANIC_ON_SETBITS | LED_PANIC_ON_CLRBITS |
+ LED_PANIC_OFF_SETBITS | LED_PANIC_OFF_CLRBITS)
+};
+
+#ifdef CONFIG_PM
+static struct pm_callback_s g_ledscb =
+{
+ .notify = led_pm_notify,
+ .prepare = led_pm_prepare,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: led_clrbits
+ *
+ * Description:
+ * Clear all LEDs to the bit encoded state
+ *
+ ****************************************************************************/
+
+static inline void led_clrbits(unsigned int clrbits)
+{
+ if ((clrbits & SHENZHOU_LED1) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+
+ if ((clrbits & SHENZHOU_LED2) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED2, false);
+ }
+
+ if ((clrbits & SHENZHOU_LED3) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED3, false);
+ }
+
+ if ((clrbits & SHENZHOU_LED4) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED4, false);
+ }
+}
+
+/****************************************************************************
+ * Name: led_setbits
+ *
+ * Description:
+ * Set all LEDs to the bit encoded state
+ *
+ ****************************************************************************/
+
+static inline void led_setbits(unsigned int setbits)
+{
+ if ((setbits & SHENZHOU_LED1) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+
+ if ((setbits & SHENZHOU_LED2) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+
+ if ((setbits & SHENZHOU_LED3) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED3, true);
+ }
+
+ if ((setbits & SHENZHOU_LED4) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED4, true);
+ }
+}
+
+/****************************************************************************
+ * Name: led_setonoff
+ *
+ * Description:
+ * Set/clear all LEDs to the bit encoded state
+ *
+ ****************************************************************************/
+
+static void led_setonoff(unsigned int bits)
+{
+ led_clrbits(CLRBITS(bits));
+ led_setbits(SETBITS(bits));
+}
+
+/****************************************************************************
+ * Name: led_pm_notify
+ *
+ * Description:
+ * Notify the driver of new power state. This callback is called after
+ * all drivers have had the opportunity to prepare for the new power state.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void led_pm_notify(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+ switch (pmstate)
+ {
+ case(PM_NORMAL):
+ {
+ /* Restore normal LEDs operation */
+
+ }
+ break;
+
+ case(PM_IDLE):
+ {
+ /* Entering IDLE mode - Turn leds off */
+
+ }
+ break;
+
+ case(PM_STANDBY):
+ {
+ /* Entering STANDBY mode - Logic for PM_STANDBY goes here */
+
+ }
+ break;
+
+ case(PM_SLEEP):
+ {
+ /* Entering SLEEP mode - Logic for PM_SLEEP goes here */
+
+ }
+ break;
+
+ default:
+ {
+ /* Should not get here */
+
+ }
+ break;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: led_pm_prepare
+ *
+ * Description:
+ * Request the driver to prepare for a new power state. This is a warning
+ * that the system is about to enter into a new power state. The driver
+ * should begin whatever operations that may be required to enter power
+ * state. The driver may abort the state change mode by returning a
+ * non-zero value from the callback function.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static int led_pm_prepare(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+ /* No preparation to change power modes is required by the LEDs driver.
+ * We always accept the state change by returning OK.
+ */
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+ /* Configure LED1-4 GPIOs for output */
+
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+ stm32_configgpio(GPIO_LED3);
+ stm32_configgpio(GPIO_LED4);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ led_setonoff(ON_BITS(g_ledbits[led]));
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ led_setonoff(OFF_BITS(g_ledbits[led]));
+}
+
+/****************************************************************************
+ * Name: up_ledpminitialize
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+void up_ledpminitialize(void)
+{
+ /* Register to receive power management callbacks */
+
+ int ret = pm_register(&g_ledscb);
+ if (ret != OK)
+ {
+ up_ledon(LED_ASSERTION);
+ }
+}
+#endif /* CONFIG_PM */
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/shenzhou/src/up_boot.c b/nuttx/configs/shenzhou/src/up_boot.c
new file mode 100644
index 000000000..efc4f26bd
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_boot.c
@@ -0,0 +1,102 @@
+/************************************************************************************
+ * configs/shenzhou/src/up_boot.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "shenzhou-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void)
+{
+ /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
+ * stm32_spiinitialize() has been brought into the link.
+ */
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI3)
+ if (stm32_spiinitialize)
+ {
+ stm32_spiinitialize();
+ }
+#endif
+
+ /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
+ * disabled, and 3) the weak function stm32_usbinitialize() has been brought
+ * into the build.
+ */
+
+#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB)
+ if (stm32_usbinitialize)
+ {
+ stm32_usbinitialize();
+ }
+#endif
+
+ /* Configure on-board LEDs if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
+}
diff --git a/nuttx/configs/shenzhou/src/up_buttons.c b/nuttx/configs/shenzhou/src/up_buttons.c
new file mode 100644
index 000000000..3bd0cd5c1
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_buttons.c
@@ -0,0 +1,169 @@
+/****************************************************************************
+ * configs/shenzhou/src/up_buttons.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+#include <arch/board/board.h>
+#include "shenzhou-internal.h"
+
+#ifdef CONFIG_ARCH_BUTTONS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Pin configuration for each Shenzhou button. This array is indexed by
+ * the BUTTON_* definitions in board.h
+ */
+
+static const uint16_t g_buttons[NUM_BUTTONS] =
+{
+ GPIO_BTN_USERKEY2, GPIO_BTN_USERKEY, GPIO_BTN_TAMPER, GPIO_BTN_WAKEUP
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_buttoninit
+ *
+ * Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons or up_irqbutton() may be called to register button interrupt
+ * handlers.
+ *
+ ****************************************************************************/
+
+void up_buttoninit(void)
+{
+ int i;
+
+ /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are
+ * configured for some pins but NOT used in this file
+ */
+
+ for (i = 0; i < NUM_BUTTONS; i++)
+ {
+ stm32_configgpio(g_buttons[i]);
+ }
+}
+
+/****************************************************************************
+ * Name: up_buttons
+ ****************************************************************************/
+
+uint8_t up_buttons(void)
+{
+ uint8_t ret = 0;
+ int i;
+
+ /* Check that state of each key */
+
+ for (i = 0; i < NUM_BUTTONS; i++)
+ {
+ /* A LOW value means that the key is pressed for most keys. The exception
+ * is the WAKEUP button.
+ */
+
+ bool released = stm32_gpioread(g_buttons[i]);
+ if (i == BUTTON_WAKEUP)
+ {
+ released = !released;
+ }
+
+ /* Accumulate the set of depressed (not released) keys */
+
+ if (!released)
+ {
+ ret |= (1 << i);
+ }
+ }
+
+ return ret;
+}
+
+/************************************************************************************
+ * Button support.
+ *
+ * Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons or up_irqbutton() may be called to register button interrupt
+ * handlers.
+ *
+ * After up_buttoninit() has been called, up_buttons() may be called to
+ * collect the state of all buttons. up_buttons() returns an 8-bit bit set
+ * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT
+ * definitions in board.h for the meaning of each bit.
+ *
+ * up_irqbutton() may be called to register an interrupt handler that will
+ * be called when a button is depressed or released. The ID value is a
+ * button enumeration value that uniquely identifies a button resource. See the
+ * BUTTON_* and JOYSTICK_* definitions in board.h for the meaning of enumeration
+ * value. The previous interrupt handler address is returned (so that it may
+ * restored, if so desired).
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQBUTTONS
+xcpt_t up_irqbutton(int id, xcpt_t irqhandler)
+{
+ xcpt_t oldhandler = NULL;
+
+ /* The following should be atomic */
+
+ if (id >= MIN_IRQBUTTON && id <= MAX_IRQBUTTON)
+ {
+ oldhandler = stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler);
+ }
+ return oldhandler;
+}
+#endif
+#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/shenzhou/src/up_can.c b/nuttx/configs/shenzhou/src/up_can.c
new file mode 100644
index 000000000..6b09be7ca
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_can.c
@@ -0,0 +1,133 @@
+/************************************************************************************
+ * configs/shenzhou/src/up_can.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/can.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "shenzhou-internal.h"
+
+#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+/* The STM32F107VC supports CAN1 and CAN2 */
+
+#define CAN_PORT 1
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+ if (can == NULL)
+ {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+ if (ret < 0)
+ {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_CAN && CONFIG_STM32_CAN1 */
diff --git a/nuttx/configs/shenzhou/src/up_composite.c b/nuttx/configs/shenzhou/src/up_composite.c
new file mode 100644
index 000000000..58f90797b
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_composite.c
@@ -0,0 +1,163 @@
+/****************************************************************************
+ * configs/shenzhou/src/up_composite.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Configure and register the STM32 MMC/SD SDIO block driver.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/sdio.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/usb/composite.h>
+
+#include "stm32_internal.h"
+
+/* There is nothing to do here if SDIO support is not selected. */
+
+#ifdef CONFIG_STM32_SDIO
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_EXAMPLES_COMPOSITE_DEVMINOR1
+# define CONFIG_EXAMPLES_COMPOSITE_DEVMINOR1 0
+#endif
+
+/* SLOT number(s) could depend on the board configuration */
+
+#ifdef CONFIG_ARCH_BOARD_STM3210E_EVAL
+# undef STM32_MMCSDSLOTNO
+# define STM32_MMCSDSLOTNO 0
+#else
+ /* Add configuration for new STM32 boards here */
+# error "Unrecognized STM32 board"
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# define msgflush()
+# else
+# define message(...) printf(__VA_ARGS__)
+# define msgflush() fflush(stdout)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# define msgflush()
+# else
+# define message printf
+# define msgflush() fflush(stdout)
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: composite_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int composite_archinitialize(void)
+{
+ /* If examples/composite is built as an NSH command, then SD slot should
+ * already have been initized in nsh_archinitialize() (see up_nsh.c). In
+ * this case, there is nothing further to be done here.
+ *
+ * NOTE: CONFIG_NSH_BUILTIN_APPS is not a fool-proof indication that NSH
+ * was built.
+ */
+
+#ifndef CONFIG_NSH_BUILTIN_APPS
+ FAR struct sdio_dev_s *sdio;
+ int ret;
+
+ /* First, get an instance of the SDIO interface */
+
+ message("composite_archinitialize: Initializing SDIO slot %d\n",
+ STM32_MMCSDSLOTNO);
+
+ sdio = sdio_initialize(STM32_MMCSDSLOTNO);
+ if (!sdio)
+ {
+ message("composite_archinitialize: Failed to initialize SDIO slot %d\n",
+ STM32_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+
+ message("composite_archinitialize: Bind SDIO to the MMC/SD driver, minor=%d\n",
+ CONFIG_EXAMPLES_COMPOSITE_DEVMINOR1);
+
+ ret = mmcsd_slotinitialize(CONFIG_EXAMPLES_COMPOSITE_DEVMINOR1, sdio);
+ if (ret != OK)
+ {
+ message("composite_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n",
+ ret);
+ return ret;
+ }
+ message("composite_archinitialize: Successfully bound SDIO to the MMC/SD driver\n");
+
+ /* Then let's guess and say that there is a card in the slot. I need to check to
+ * see if the STM3210E-EVAL board supports a GPIO to detect if there is a card in
+ * the slot.
+ */
+
+ sdio_mediachange(sdio, true);
+
+#endif /* CONFIG_NSH_BUILTIN_APPS */
+
+ return OK;
+}
+
+#endif /* CONFIG_STM32_SDIO */
diff --git a/nuttx/configs/shenzhou/src/up_cxxinitialize.c b/nuttx/configs/shenzhou/src/up_cxxinitialize.c
new file mode 100644
index 000000000..406827dbf
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_cxxinitialize.c
@@ -0,0 +1,155 @@
+/************************************************************************************
+ * configs/shenzhou/src/up_cxxinitialize.c
+ * arch/arm/src/board/up_cxxinitialize.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include <arch/stm32/chip.h>
+#include "chip.h"
+
+#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Debug ****************************************************************************/
+/* Non-standard debug that may be enabled just for testing the static constructors */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_CXX
+#endif
+
+#ifdef CONFIG_DEBUG_CXX
+# define cxxdbg dbg
+# define cxxlldbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define cxxvdbg vdbg
+# define cxxllvdbg llvdbg
+# else
+# define cxxvdbg(x...)
+# define cxxllvdbg(x...)
+# endif
+#else
+# define cxxdbg(x...)
+# define cxxlldbg(x...)
+# define cxxvdbg(x...)
+# define cxxllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+/* This type defines one entry in initialization array */
+
+typedef void (*initializer_t)(void);
+
+/************************************************************************************
+ * External references
+ ************************************************************************************/
+/* _sinit and _einit are symbols exported by the linker script that mark the
+ * beginning and the end of the C++ initialization section.
+ */
+
+extern initializer_t _sinit;
+extern initializer_t _einit;
+
+/* _stext and _etext are symbols exported by the linker script that mark the
+ * beginning and the end of text.
+ */
+
+extern uint32_t _stext;
+extern uint32_t _etext;
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: up_cxxinitialize
+ *
+ * Description:
+ * If C++ and C++ static constructors are supported, then this function
+ * must be provided by board-specific logic in order to perform
+ * initialization of the static C++ class instances.
+ *
+ * This function should then be called in the application-specific
+ * user_start logic in order to perform the C++ initialization. NOTE
+ * that no component of the core NuttX RTOS logic is involved; This
+ * function defintion only provides the 'contract' between application
+ * specific C++ code and platform-specific toolchain support
+ *
+ ***************************************************************************/
+
+void up_cxxinitialize(void)
+{
+ initializer_t *initp;
+
+ cxxdbg("_sinit: %p _einit: %p _stext: %p _etext: %p\n",
+ &_sinit, &_einit, &_stext, &_etext);
+
+ /* Visit each entry in the initialzation table */
+
+ for (initp = &_sinit; initp != &_einit; initp++)
+ {
+ initializer_t initializer = *initp;
+ cxxdbg("initp: %p initializer: %p\n", initp, initializer);
+
+ /* Make sure that the address is non-NULL and lies in the text region
+ * defined by the linker script. Some toolchains may put NULL values
+ * or counts in the initialization table
+ */
+
+ if ((void*)initializer > (void*)&_stext && (void*)initializer < (void*)&_etext)
+ {
+ cxxdbg("Calling %p\n", initializer);
+ initializer();
+ }
+ }
+}
+
+#endif /* CONFIG_HAVE_CXX && CONFIG_HAVE_CXXINITIALIZE */
+
diff --git a/nuttx/configs/shenzhou/src/up_leds.c b/nuttx/configs/shenzhou/src/up_leds.c
new file mode 100644
index 000000000..c7ce0b909
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_leds.c
@@ -0,0 +1,401 @@
+/****************************************************************************
+ * configs/shenzhou/src/up_leds.c
+ * arch/arm/src/board/up_leds.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+#include <nuttx/power/pm.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "shenzhou-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/* The following definitions map the encoded LED setting to GPIO settings */
+
+#define SHENZHOU_LED1 (1 << 0)
+#define SHENZHOU_LED2 (1 << 1)
+#define SHENZHOU_LED3 (1 << 2)
+#define SHENZHOU_LED4 (1 << 3)
+
+#define ON_SETBITS_SHIFT (0)
+#define ON_CLRBITS_SHIFT (4)
+#define OFF_SETBITS_SHIFT (8)
+#define OFF_CLRBITS_SHIFT (12)
+
+#define ON_BITS(v) ((v) & 0xff)
+#define OFF_BITS(v) (((v) >> 8) & 0x0ff)
+#define SETBITS(b) ((b) & 0x0f)
+#define CLRBITS(b) (((b) >> 4) & 0x0f)
+
+#define ON_SETBITS(v) (SETBITS(ON_BITS(v))
+#define ON_CLRBITS(v) (CLRBITS(ON_BITS(v))
+#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v))
+#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v))
+
+#define LED_STARTED_ON_SETBITS ((SHENZHOU_LED1) << ON_SETBITS_SHIFT)
+#define LED_STARTED_ON_CLRBITS ((SHENZHOU_LED2|SHENZHOU_LED3|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_STARTED_OFF_SETBITS (0 << OFF_SETBITS_SHIFT)
+#define LED_STARTED_OFF_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED2|SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_HEAPALLOCATE_ON_SETBITS ((SHENZHOU_LED2) << ON_SETBITS_SHIFT)
+#define LED_HEAPALLOCATE_ON_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED3|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_HEAPALLOCATE_OFF_SETBITS ((SHENZHOU_LED1) << OFF_SETBITS_SHIFT)
+#define LED_HEAPALLOCATE_OFF_CLRBITS ((SHENZHOU_LED2|SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_IRQSENABLED_ON_SETBITS ((SHENZHOU_LED1|SHENZHOU_LED2) << ON_SETBITS_SHIFT)
+#define LED_IRQSENABLED_ON_CLRBITS ((SHENZHOU_LED3|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_IRQSENABLED_OFF_SETBITS ((SHENZHOU_LED2) << OFF_SETBITS_SHIFT)
+#define LED_IRQSENABLED_OFF_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_STACKCREATED_ON_SETBITS ((SHENZHOU_LED3) << ON_SETBITS_SHIFT)
+#define LED_STACKCREATED_ON_CLRBITS ((SHENZHOU_LED1|SHENZHOU_LED2|SHENZHOU_LED4) << ON_CLRBITS_SHIFT)
+#define LED_STACKCREATED_OFF_SETBITS ((SHENZHOU_LED1|SHENZHOU_LED2) << OFF_SETBITS_SHIFT)
+#define LED_STACKCREATED_OFF_CLRBITS ((SHENZHOU_LED3|SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_INIRQ_ON_SETBITS ((SHENZHOU_LED1) << ON_SETBITS_SHIFT)
+#define LED_INIRQ_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_INIRQ_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_INIRQ_OFF_CLRBITS ((SHENZHOU_LED1) << OFF_CLRBITS_SHIFT)
+
+#define LED_SIGNAL_ON_SETBITS ((SHENZHOU_LED2) << ON_SETBITS_SHIFT)
+#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_SIGNAL_OFF_CLRBITS ((SHENZHOU_LED2) << OFF_CLRBITS_SHIFT)
+
+#define LED_ASSERTION_ON_SETBITS ((SHENZHOU_LED4) << ON_SETBITS_SHIFT)
+#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_ASSERTION_OFF_CLRBITS ((SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+#define LED_PANIC_ON_SETBITS ((SHENZHOU_LED4) << ON_SETBITS_SHIFT)
+#define LED_PANIC_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
+#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
+#define LED_PANIC_OFF_CLRBITS ((SHENZHOU_LED4) << OFF_CLRBITS_SHIFT)
+
+/**************************************************************************************
+ * Private Function Protototypes
+ **************************************************************************************/
+
+/* LED State Controls */
+
+static inline void led_clrbits(unsigned int clrbits);
+static inline void led_setbits(unsigned int setbits);
+static void led_setonoff(unsigned int bits);
+
+/* LED Power Management */
+
+#ifdef CONFIG_PM
+static void led_pm_notify(struct pm_callback_s *cb, enum pm_state_e pmstate);
+static int led_pm_prepare(struct pm_callback_s *cb, enum pm_state_e pmstate);
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const uint16_t g_ledbits[8] =
+{
+ (LED_STARTED_ON_SETBITS | LED_STARTED_ON_CLRBITS |
+ LED_STARTED_OFF_SETBITS | LED_STARTED_OFF_CLRBITS),
+
+ (LED_HEAPALLOCATE_ON_SETBITS | LED_HEAPALLOCATE_ON_CLRBITS |
+ LED_HEAPALLOCATE_OFF_SETBITS | LED_HEAPALLOCATE_OFF_CLRBITS),
+
+ (LED_IRQSENABLED_ON_SETBITS | LED_IRQSENABLED_ON_CLRBITS |
+ LED_IRQSENABLED_OFF_SETBITS | LED_IRQSENABLED_OFF_CLRBITS),
+
+ (LED_STACKCREATED_ON_SETBITS | LED_STACKCREATED_ON_CLRBITS |
+ LED_STACKCREATED_OFF_SETBITS | LED_STACKCREATED_OFF_CLRBITS),
+
+ (LED_INIRQ_ON_SETBITS | LED_INIRQ_ON_CLRBITS |
+ LED_INIRQ_OFF_SETBITS | LED_INIRQ_OFF_CLRBITS),
+
+ (LED_SIGNAL_ON_SETBITS | LED_SIGNAL_ON_CLRBITS |
+ LED_SIGNAL_OFF_SETBITS | LED_SIGNAL_OFF_CLRBITS),
+
+ (LED_ASSERTION_ON_SETBITS | LED_ASSERTION_ON_CLRBITS |
+ LED_ASSERTION_OFF_SETBITS | LED_ASSERTION_OFF_CLRBITS),
+
+ (LED_PANIC_ON_SETBITS | LED_PANIC_ON_CLRBITS |
+ LED_PANIC_OFF_SETBITS | LED_PANIC_OFF_CLRBITS)
+};
+
+#ifdef CONFIG_PM
+static struct pm_callback_s g_ledscb =
+{
+ .notify = led_pm_notify,
+ .prepare = led_pm_prepare,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: led_clrbits
+ *
+ * Description:
+ * Clear all LEDs to the bit encoded state
+ *
+ ****************************************************************************/
+
+static inline void led_clrbits(unsigned int clrbits)
+{
+ if ((clrbits & SHENZHOU_LED1) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+
+ if ((clrbits & SHENZHOU_LED2) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED2, false);
+ }
+
+ if ((clrbits & SHENZHOU_LED3) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED3, false);
+ }
+
+ if ((clrbits & SHENZHOU_LED4) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED4, false);
+ }
+}
+
+/****************************************************************************
+ * Name: led_setbits
+ *
+ * Description:
+ * Set all LEDs to the bit encoded state
+ *
+ ****************************************************************************/
+
+static inline void led_setbits(unsigned int setbits)
+{
+ if ((setbits & SHENZHOU_LED1) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+
+ if ((setbits & SHENZHOU_LED2) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+
+ if ((setbits & SHENZHOU_LED3) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED3, true);
+ }
+
+ if ((setbits & SHENZHOU_LED4) != 0)
+ {
+ stm32_gpiowrite(GPIO_LED4, true);
+ }
+}
+
+/****************************************************************************
+ * Name: led_setonoff
+ *
+ * Description:
+ * Set/clear all LEDs to the bit encoded state
+ *
+ ****************************************************************************/
+
+static void led_setonoff(unsigned int bits)
+{
+ led_clrbits(CLRBITS(bits));
+ led_setbits(SETBITS(bits));
+}
+
+/****************************************************************************
+ * Name: led_pm_notify
+ *
+ * Description:
+ * Notify the driver of new power state. This callback is called after
+ * all drivers have had the opportunity to prepare for the new power state.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void led_pm_notify(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+ switch (pmstate)
+ {
+ case(PM_NORMAL):
+ {
+ /* Restore normal LEDs operation */
+
+ }
+ break;
+
+ case(PM_IDLE):
+ {
+ /* Entering IDLE mode - Turn leds off */
+
+ }
+ break;
+
+ case(PM_STANDBY):
+ {
+ /* Entering STANDBY mode - Logic for PM_STANDBY goes here */
+
+ }
+ break;
+
+ case(PM_SLEEP):
+ {
+ /* Entering SLEEP mode - Logic for PM_SLEEP goes here */
+
+ }
+ break;
+
+ default:
+ {
+ /* Should not get here */
+
+ }
+ break;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: led_pm_prepare
+ *
+ * Description:
+ * Request the driver to prepare for a new power state. This is a warning
+ * that the system is about to enter into a new power state. The driver
+ * should begin whatever operations that may be required to enter power
+ * state. The driver may abort the state change mode by returning a
+ * non-zero value from the callback function.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static int led_pm_prepare(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+ /* No preparation to change power modes is required by the LEDs driver.
+ * We always accept the state change by returning OK.
+ */
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+ /* Configure LED1-4 GPIOs for output */
+
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+ stm32_configgpio(GPIO_LED3);
+ stm32_configgpio(GPIO_LED4);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ led_setonoff(ON_BITS(g_ledbits[led]));
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ led_setonoff(OFF_BITS(g_ledbits[led]));
+}
+
+/****************************************************************************
+ * Name: up_ledpminitialize
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+void up_ledpminitialize(void)
+{
+ /* Register to receive power management callbacks */
+
+ int ret = pm_register(&g_ledscb);
+ if (ret != OK)
+ {
+ up_ledon(LED_ASSERTION);
+ }
+}
+#endif /* CONFIG_PM */
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/shenzhou/src/up_nsh.c b/nuttx/configs/shenzhou/src/up_nsh.c
new file mode 100644
index 000000000..3d9ba407f
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_nsh.c
@@ -0,0 +1,218 @@
+/****************************************************************************
+ * config/shenzhou/src/up_nsh.c
+ * arch/arm/src/board/up_nsh.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#ifdef CONFIG_STM32_SPI1
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+#endif
+
+#ifdef CONFIG_STM32_SDIO
+# include <nuttx/sdio.h>
+# include <nuttx/mmcsd.h>
+#endif
+
+#ifdef CONFIG_STM32_OTGFS
+# include "stm32_usbhost.h"
+#endif
+
+#include "stm32_internal.h"
+#include "shenzhou-internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* For now, don't build in any SPI1 support -- NSH is not using it */
+
+#undef CONFIG_STM32_SPI1
+
+/* Assume that we support everything until convinced otherwise */
+
+#define HAVE_MMCSD 1
+#define HAVE_USBDEV 1
+#define HAVE_USBHOST 1
+
+/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support
+ * is not enabled.
+ */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO)
+# undef HAVE_MMCSD
+#endif
+
+/* Default MMC/SD minor number */
+
+#ifdef HAVE_MMCSD
+# ifndef CONFIG_NSH_MMCSDMINOR
+# define CONFIG_NSH_MMCSDMINOR 0
+# endif
+
+/* Default MMC/SD SLOT number */
+
+# if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != 0
+# error "Only one MMC/SD slot"
+# undef CONFIG_NSH_MMCSDSLOTNO
+# endif
+
+# ifndef CONFIG_NSH_MMCSDSLOTNO
+# define CONFIG_NSH_MMCSDSLOTNO 0
+# endif
+#endif
+
+/* Can't support USB host or device features if USB OTG FS is not enabled */
+
+#ifndef CONFIG_STM32_OTGFS
+# undef HAVE_USBDEV
+# undef HAVE_USBHOST
+#endif
+
+/* Can't support USB device is USB device is not enabled */
+
+#ifndef CONFIG_USBDEV
+# undef HAVE_USBDEV
+#endif
+
+/* Can't support USB host is USB host is not enabled */
+
+#ifndef CONFIG_USBHOST
+# undef HAVE_USBHOST
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+#ifdef CONFIG_STM32_SPI1
+ FAR struct spi_dev_s *spi;
+ FAR struct mtd_dev_s *mtd;
+#endif
+#ifdef HAVE_MMCSD
+ FAR struct sdio_dev_s *sdio;
+#endif
+#if defined(HAVE_MMCSD) || defined(HAVE_USBHOST)
+ int ret;
+#endif
+
+ /* Configure SPI-based devices */
+
+#ifdef CONFIG_STM32_SPI1
+# warning "Missing support for the SPI FLASH"
+#endif
+
+ /* Mount the SDIO-based MMC/SD block driver */
+
+#ifdef HAVE_MMCSD
+ /* First, get an instance of the SDIO interface */
+
+ sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
+ if (!sdio)
+ {
+ message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
+ CONFIG_NSH_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+
+ ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
+ if (ret != OK)
+ {
+ message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ return ret;
+ }
+
+ /* Then let's guess and say that there is a card in the slot. I need to check to
+ * see if the STM3240G-EVAL board supports a GPIO to detect if there is a card in
+ * the slot.
+ */
+
+ sdio_mediachange(sdio, true);
+#endif
+
+#ifdef HAVE_USBHOST
+ /* Initialize USB host operation. stm32_usbhost_initialize() starts a thread
+ * will monitor for USB connection and disconnection events.
+ */
+
+ ret = stm32_usbhost_initialize();
+ if (ret != OK)
+ {
+ message("nsh_archinitialize: Failed to initialize USB host: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ return OK;
+}
diff --git a/nuttx/configs/shenzhou/src/up_spi.c b/nuttx/configs/shenzhou/src/up_spi.c
new file mode 100644
index 000000000..5a3e69159
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_spi.c
@@ -0,0 +1,204 @@
+/************************************************************************************
+ * configs/shenzhou/src/up_spi.c
+ * arch/arm/src/board/up_spi.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "shenzhou-internal.h"
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI3)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG too) */
+
+#undef SPI_DEBUG /* Define to enable debug */
+#undef SPI_VERBOSE /* Define to enable verbose debug */
+
+#ifdef SPI_DEBUG
+# define spidbg lldbg
+# ifdef SPI_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# undef SPI_VERBOSE
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the Shenzhou board.
+ *
+ ************************************************************************************/
+
+void weak_function stm32_spiinitialize(void)
+{
+ /* NOTE: Clocking for SPI1 and/or SPI3 was already provided in stm32_rcc.c.
+ * Configurations of SPI pins is performed in stm32_spi.c.
+ * Here, we only initialize chip select pins unique to the board
+ * architecture.
+ */
+
+ /* SPI1 connects to the SD CARD and to the SPI FLASH */
+
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SD_CS);
+ stm32_configgpio(GPIO_FLASH_CS);
+#endif
+
+ /* SPI3 connects to TFT LCD and the RF24L01 2.4G wireless module */
+
+#ifdef CONFIG_STM32_SPI3
+ stm32_configgpio(GPIO_LCD_CS);
+ stm32_configgpio(GPIO_WIRELESS_CS);
+#endif
+}
+
+/****************************************************************************
+ * Name: stm32_spi1/2/3select and stm32_spi1/2/3status
+ *
+ * Description:
+ * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be
+ * provided by board-specific logic. They are implementations of the select
+ * and status methods of the SPI interface defined by struct spi_ops_s (see
+ * include/nuttx/spi.h). All other methods (including up_spiinitialize())
+ * are provided by common STM32 logic. To use this common SPI logic on your
+ * board:
+ *
+ * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select
+ * pins.
+ * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your
+ * board-specific logic. These functions will perform chip selection and
+ * status operations using GPIOs in the way your board is configured.
+ * 3. Add a calls to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_SPI1
+void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ /* SPI1 connects to the SD CARD and to the SPI FLASH */
+
+ if (devid == SPIDEV_MMCSD)
+ {
+ /* Set the GPIO low to select and high to de-select */
+
+ stm32_gpiowrite(GPIO_SD_CS, !selected);
+ }
+ elseif (devid == SPIDEV_FLASH)
+ {
+ /* Set the GPIO low to select and high to de-select */
+
+ stm32_gpiowrite(GPIO_FLASH_CS, !selected);
+ }
+}
+
+uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ if (stm32_gpioread(GPIO_SD_CD))
+ {
+ return 0;
+ }
+ else
+ {
+ return SPI_STATUS_PRESENT;
+ }
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ /* SPI3 connects to TFT LCD and the RF24L01 2.4G wireless module */
+
+ if (devid == SPIDEV_TOUCHSCREEN)
+ {
+ /* Set the GPIO low to select and high to de-select */
+
+ stm32_gpiowrite(GPIO_LCD_CS, !selected);
+ }
+ elseif (devid == SPIDEV_WIRELESS)
+ {
+ /* Set the GPIO low to select and high to de-select */
+
+ stm32_gpiowrite(GPIO_WIRELESS_CS, !selected);
+ }
+}
+
+uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return 0;
+}
+#endif
+
+#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI3 */
diff --git a/nuttx/configs/shenzhou/src/up_usb.c b/nuttx/configs/shenzhou/src/up_usb.c
new file mode 100644
index 000000000..1cf8a39a7
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_usb.c
@@ -0,0 +1,294 @@
+/************************************************************************************
+ * configs/shenzhou/src/up_usbdev.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbhost.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "up_arch.h"
+#include "stm32_internal.h"
+#include "shenshou-internal.h"
+
+#ifdef CONFIG_STM32_OTGFS
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST)
+# define HAVE_USB 1
+#else
+# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST"
+# undef HAVE_USB
+#endif
+
+#ifndef CONFIG_USBHOST_DEFPRIO
+# define CONFIG_USBHOST_DEFPRIO 50
+#endif
+
+#ifndef CONFIG_USBHOST_STACKSIZE
+# define CONFIG_USBHOST_STACKSIZE 1024
+#endif
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+#ifdef CONFIG_USBHOST
+static struct usbhost_driver_s *g_drvr;
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: usbhost_waiter
+ *
+ * Description:
+ * Wait for USB devices to be connected.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_USBHOST
+static int usbhost_waiter(int argc, char *argv[])
+{
+ bool connected = false;
+ int ret;
+
+ uvdbg("Running\n");
+ for (;;)
+ {
+ /* Wait for the device to change state */
+
+ ret = DRVR_WAIT(g_drvr, connected);
+ DEBUGASSERT(ret == OK);
+
+ connected = !connected;
+ uvdbg("%s\n", connected ? "connected" : "disconnected");
+
+ /* Did we just become connected? */
+
+ if (connected)
+ {
+ /* Yes.. enumerate the newly connected device */
+
+ (void)DRVR_ENUMERATE(g_drvr);
+ }
+ }
+
+ /* Keep the compiler from complaining */
+
+ return 0;
+}
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called from stm32_usbinitialize very early in inialization to setup USB-related
+ * GPIO pins for the STM3240G-EVAL board.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void)
+{
+ /* The OTG FS has an internal soft pull-up. No GPIO configuration is required */
+
+ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
+
+#ifdef CONFIG_STM32_OTGFS
+ stm32_configgpio(GPIO_OTGFS_VBUS);
+ stm32_configgpio(GPIO_OTGFS_PWRON);
+ stm32_configgpio(GPIO_OTGFS_OVER);
+#endif
+}
+
+/***********************************************************************************
+ * Name: stm32_usbhost_initialize
+ *
+ * Description:
+ * Called at application startup time to initialize the USB host functionality.
+ * This function will start a thread that will monitor for device
+ * connection/disconnection events.
+ *
+ ***********************************************************************************/
+
+#ifdef CONFIG_USBHOST
+int stm32_usbhost_initialize(void)
+{
+ int pid;
+ int ret;
+
+ /* First, register all of the class drivers needed to support the drivers
+ * that we care about:
+ */
+
+ uvdbg("Register class drivers\n");
+ ret = usbhost_storageinit();
+ if (ret != OK)
+ {
+ udbg("Failed to register the mass storage class\n");
+ }
+
+ /* Then get an instance of the USB host interface */
+
+ uvdbg("Initialize USB host\n");
+ g_drvr = usbhost_initialize(0);
+ if (g_drvr)
+ {
+ /* Start a thread to handle device connection. */
+
+ uvdbg("Start usbhost_waiter\n");
+
+ pid = TASK_CREATE("usbhost", CONFIG_USBHOST_DEFPRIO,
+ CONFIG_USBHOST_STACKSIZE,
+ (main_t)usbhost_waiter, (const char **)NULL);
+ return pid < 0 ? -ENOEXEC : OK;
+ }
+
+ return -ENODEV;
+}
+#endif
+
+/***********************************************************************************
+ * Name: stm32_usbhost_vbusdrive
+ *
+ * Description:
+ * Enable/disable driving of VBUS 5V output. This function must be provided be
+ * each platform that implements the STM32 OTG FS host interface
+ *
+ * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
+ * or, if 5 V are available on the application board, a basic power switch, must
+ * be added externally to drive the 5 V VBUS line. The external charge pump can
+ * be driven by any GPIO output. When the application decides to power on VBUS
+ * using the chosen GPIO, it must also set the port power bit in the host port
+ * control and status register (PPWR bit in OTG_FS_HPRT).
+ *
+ * "The application uses this field to control power to this port, and the core
+ * clears this bit on an overcurrent condition."
+ *
+ * Input Parameters:
+ * iface - For future growth to handle multiple USB host interface. Should be zero.
+ * enable - true: enable VBUS power; false: disable VBUS power
+ *
+ * Returned Value:
+ * None
+ *
+ ***********************************************************************************/
+
+#ifdef CONFIG_USBHOST
+void stm32_usbhost_vbusdrive(int iface, bool enable)
+{
+ DEBUGASSERT(iface == 0);
+
+ if (enable)
+ {
+ /* Enable the Power Switch by driving the enable pin low */
+
+ stm32_gpiowrite(GPIO_OTGFS_PWRON, false);
+ }
+ else
+ {
+ /* Disable the Power Switch by driving the enable pin high */
+
+ stm32_gpiowrite(GPIO_OTGFS_PWRON, true);
+ }
+}
+#endif
+
+/************************************************************************************
+ * Name: stm32_setup_overcurrent
+ *
+ * Description:
+ * Setup to receive an interrupt-level callback if an overcurrent condition is
+ * detected.
+ *
+ * Input paramter:
+ * handler - New overcurrent interrupt handler
+ *
+ * Returned value:
+ * Old overcurrent interrupt handler
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_USBHOST
+xcpt_t stm32_setup_overcurrent(xcpt_t handler)
+{
+ return NULL;
+}
+#endif
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_USBDEV
+void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+#endif
+
+#endif /* CONFIG_STM32_OTGFS */
+
+
+
diff --git a/nuttx/configs/shenzhou/src/up_usbmsc.c b/nuttx/configs/shenzhou/src/up_usbmsc.c
new file mode 100644
index 000000000..8d12f6324
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_usbmsc.c
@@ -0,0 +1,159 @@
+/****************************************************************************
+ * configs/shenzhou/src/up_usbmsc.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Configure and register the STM32 MMC/SD SDIO block driver.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/sdio.h>
+#include <nuttx/mmcsd.h>
+
+#include "stm32_internal.h"
+
+/* There is nothing to do here if SDIO support is not selected. */
+
+#ifdef CONFIG_STM32_SDIO
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_EXAMPLES_USBMSC_DEVMINOR1
+# define CONFIG_EXAMPLES_USBMSC_DEVMINOR1 0
+#endif
+
+/* SLOT number(s) could depend on the board configuration */
+
+#undef STM32_MMCSDSLOTNO
+#define STM32_MMCSDSLOTNO 0
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# define msgflush()
+# else
+# define message(...) printf(__VA_ARGS__)
+# define msgflush() fflush(stdout)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# define msgflush()
+# else
+# define message printf
+# define msgflush() fflush(stdout)
+# endif
+#endif
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbmsc_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int usbmsc_archinitialize(void)
+{
+ /* If examples/usbmsc is built as an NSH command, then SD slot should
+ * already have been initized in nsh_archinitialize() (see up_nsh.c). In
+ * this case, there is nothing further to be done here.
+ */
+
+#ifndef CONFIG_EXAMPLES_USBMSC_BUILTIN
+ FAR struct sdio_dev_s *sdio;
+ int ret;
+
+ /* First, get an instance of the SDIO interface */
+
+ message("usbmsc_archinitialize: "
+ "Initializing SDIO slot %d\n",
+ STM32_MMCSDSLOTNO);
+
+ sdio = sdio_initialize(STM32_MMCSDSLOTNO);
+ if (!sdio)
+ {
+ message("usbmsc_archinitialize: Failed to initialize SDIO slot %d\n",
+ STM32_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+
+ message("usbmsc_archinitialize: "
+ "Bind SDIO to the MMC/SD driver, minor=%d\n",
+ CONFIG_EXAMPLES_USBMSC_DEVMINOR1);
+
+ ret = mmcsd_slotinitialize(CONFIG_EXAMPLES_USBMSC_DEVMINOR1, sdio);
+ if (ret != OK)
+ {
+ message("usbmsc_archinitialize: "
+ "Failed to bind SDIO to the MMC/SD driver: %d\n",
+ ret);
+ return ret;
+ }
+ message("usbmsc_archinitialize: "
+ "Successfully bound SDIO to the MMC/SD driver\n");
+
+ /* Then let's guess and say that there is a card in the slot. I need to check to
+ * see if the Shenzhou board supports a GPIO to detect if there is a card in
+ * the slot.
+ */
+
+ sdio_mediachange(sdio, true);
+
+#endif /* CONFIG_EXAMPLES_USBMSC_BUILTIN */
+
+ return OK;
+}
+
+#endif /* CONFIG_STM32_SDIO */
diff --git a/nuttx/configs/shenzhou/src/up_userleds.c b/nuttx/configs/shenzhou/src/up_userleds.c
new file mode 100644
index 000000000..0ba029228
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_userleds.c
@@ -0,0 +1,131 @@
+/****************************************************************************
+ * configs/shenzhou/src/up_userleds.c
+ * arch/arm/src/board/up_userleds.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "shenzhou-internal.h"
+
+#ifndef CONFIG_ARCH_LEDS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* This array maps an LED number to GPIO pin configuration */
+
+static uint32_t g_ledcfg[BOARD_NLEDS] =
+{
+ GPIO_LED1, GPIO_LED2, GPIO_LED3, GPIO_LED4
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_ledinit
+ ****************************************************************************/
+
+void stm32_ledinit(void)
+{
+ /* Configure LED1-4 GPIOs for output */
+
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+ stm32_configgpio(GPIO_LED3);
+ stm32_configgpio(GPIO_LED4);
+}
+
+/****************************************************************************
+ * Name: stm32_setled
+ ****************************************************************************/
+
+void stm32_setled(int led, bool ledon)
+{
+ if ((unsigned)led < BOARD_NLEDS)
+ {
+ stm32_gpiowrite(g_ledcfg[led], ledon);
+ }
+}
+
+/****************************************************************************
+ * Name: stm32_setleds
+ ****************************************************************************/
+
+void stm32_setleds(uint8_t ledset)
+{
+ stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0);
+ stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0);
+ stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0);
+ stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0);
+}
+
+#endif /* !CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/shenzhou/src/up_watchdog.c b/nuttx/configs/shenzhou/src/up_watchdog.c
new file mode 100644
index 000000000..a4be02371
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_watchdog.c
@@ -0,0 +1,136 @@
+/************************************************************************************
+ * configs/shenzhou/src/up_watchdog.c
+ * arch/arm/src/board/up_watchdog.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/watchdog.h>
+#include <arch/board/board.h>
+
+#include "stm32_wdg.h"
+
+#ifdef CONFIG_WATCHDOG
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration *******************************************************************/
+/* Wathdog hardware should be enabled */
+
+#if !defined(CONFIG_STM32_WWDG) && !defined(CONFIG_STM32_IWDG)
+# warning "One of CONFIG_STM32_WWDG or CONFIG_STM32_IWDG must be defined"
+#endif
+
+/* Select the path to the registered watchdog timer device */
+
+#ifndef CONFIG_STM32_WDG_DEVPATH
+# ifdef CONFIG_EXAMPLES_WATCHDOG_DEVPATH
+# define CONFIG_STM32_WDG_DEVPATH CONFIG_EXAMPLES_WATCHDOG_DEVPATH
+# else
+# define CONFIG_STM32_WDG_DEVPATH "/dev/watchdog0"
+# endif
+#endif
+
+/* Use the un-calibrated LSI frequency if we have nothing better */
+
+#if defined(CONFIG_STM32_IWDG) && !defined(CONFIG_STM32_LSIFREQ)
+# define CONFIG_STM32_LSIFREQ STM32_LSI_FREQUENCY
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing the watchdog timer */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_WATCHDOG
+#endif
+
+#ifdef CONFIG_DEBUG_WATCHDOG
+# define wdgdbg dbg
+# define wdglldbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define wdgvdbg vdbg
+# define wdgllvdbg llvdbg
+# else
+# define wdgvdbg(x...)
+# define wdgllvdbg(x...)
+# endif
+#else
+# define wdgdbg(x...)
+# define wdglldbg(x...)
+# define wdgvdbg(x...)
+# define wdgllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: up_wdginitialize()
+ *
+ * Description:
+ * Perform architecuture-specific initialization of the Watchdog hardware.
+ * This interface must be provided by all configurations using
+ * apps/examples/watchdog
+ *
+ ****************************************************************************/
+
+int up_wdginitialize(void)
+{
+ /* Initialize tha register the watchdog timer device */
+
+#if defined(CONFIG_STM32_WWDG)
+ stm32_wwdginitialize(CONFIG_STM32_WDG_DEVPATH);
+ return OK;
+#elif defined(CONFIG_STM32_IWDG)
+ stm32_iwdginitialize(CONFIG_STM32_WDG_DEVPATH, CONFIG_STM32_LSIFREQ);
+ return OK;
+#else
+ return -ENODEV;
+#endif
+}
+
+#endif /* CONFIG_WATCHDOG */
diff --git a/nuttx/configs/stm3210e-eval/RIDE/appconfig b/nuttx/configs/stm3210e-eval/RIDE/appconfig
index b40f864aa..138b4e47a 100644
--- a/nuttx/configs/stm3210e-eval/RIDE/appconfig
+++ b/nuttx/configs/stm3210e-eval/RIDE/appconfig
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/RIDE/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/RIDE/setenv.sh b/nuttx/configs/stm3210e-eval/RIDE/setenv.sh
index 0c600814a..b73411136 100755
--- a/nuttx/configs/stm3210e-eval/RIDE/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/RIDE/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/RIDE/setenv.sh
#
# Copyright (C) 2009 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld b/nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld
index 93bd6bca4..704960ad9 100755
--- a/nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld
+++ b/nuttx/configs/stm3210e-eval/RIDE/stm32-nuttx.ld
@@ -2,7 +2,7 @@
* configs/stm3210e-eval/RIDE/stm32-nuttx.ld
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/buttons/appconfig b/nuttx/configs/stm3210e-eval/buttons/appconfig
index 5e847bd9e..a747036fe 100644
--- a/nuttx/configs/stm3210e-eval/buttons/appconfig
+++ b/nuttx/configs/stm3210e-eval/buttons/appconfig
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/buttons/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/buttons/setenv.sh b/nuttx/configs/stm3210e-eval/buttons/setenv.sh
index fba331e44..2bdf53674 100755
--- a/nuttx/configs/stm3210e-eval/buttons/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/buttons/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/buttons/setenv.sh
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/nsh/setenv.sh b/nuttx/configs/stm3210e-eval/nsh/setenv.sh
index d83685192..ee33a8d21 100755
--- a/nuttx/configs/stm3210e-eval/nsh/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/nsh/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/dfu/setenv.sh
#
# Copyright (C) 2009 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/nsh2/setenv.sh b/nuttx/configs/stm3210e-eval/nsh2/setenv.sh
index 09d1c5cea..425acf89e 100755
--- a/nuttx/configs/stm3210e-eval/nsh2/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/nsh2/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/nsh2/setenv.sh
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/nx/setenv.sh b/nuttx/configs/stm3210e-eval/nx/setenv.sh
index 40cbbf0ca..bf9fad443 100755
--- a/nuttx/configs/stm3210e-eval/nx/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/nx/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/nx/setenv.sh
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/nxlines/appconfig b/nuttx/configs/stm3210e-eval/nxlines/appconfig
index fb9c044c5..c2fc508fa 100644
--- a/nuttx/configs/stm3210e-eval/nxlines/appconfig
+++ b/nuttx/configs/stm3210e-eval/nxlines/appconfig
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/nxlines/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/nxlines/setenv.sh b/nuttx/configs/stm3210e-eval/nxlines/setenv.sh
index 2c4667fbd..a9dc78c74 100755
--- a/nuttx/configs/stm3210e-eval/nxlines/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/nxlines/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/nxlines/setenv.sh
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/nxtext/appconfig b/nuttx/configs/stm3210e-eval/nxtext/appconfig
index 73e9154ec..acb27582a 100644
--- a/nuttx/configs/stm3210e-eval/nxtext/appconfig
+++ b/nuttx/configs/stm3210e-eval/nxtext/appconfig
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/nxtext/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/nxtext/setenv.sh b/nuttx/configs/stm3210e-eval/nxtext/setenv.sh
index e10ac0096..a36540cf1 100755
--- a/nuttx/configs/stm3210e-eval/nxtext/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/nxtext/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/nxtext/setenv.sh
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/ostest/appconfig b/nuttx/configs/stm3210e-eval/ostest/appconfig
index 68c1f9c0d..3f36a5c7f 100644
--- a/nuttx/configs/stm3210e-eval/ostest/appconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/appconfig
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/ostest/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/ostest/setenv.sh b/nuttx/configs/stm3210e-eval/ostest/setenv.sh
index fcb428c2f..046a7f5ac 100755
--- a/nuttx/configs/stm3210e-eval/ostest/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/ostest/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/ostest/setenv.sh
#
# Copyright (C) 2009 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/pm/setenv.sh b/nuttx/configs/stm3210e-eval/pm/setenv.sh
index 9dc5094e6..5a02de258 100755
--- a/nuttx/configs/stm3210e-eval/pm/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/pm/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/pm/setenv.sh
#
# Copyright (C) 2012 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_buttons.c b/nuttx/configs/stm3210e-eval/src/up_buttons.c
index b9c9fb9d4..4f884649c 100644
--- a/nuttx/configs/stm3210e-eval/src/up_buttons.c
+++ b/nuttx/configs/stm3210e-eval/src/up_buttons.c
@@ -2,7 +2,7 @@
* configs/stm3210e-eval/src/up_buttons.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_composite.c b/nuttx/configs/stm3210e-eval/src/up_composite.c
index 7368c7898..e80e0fcb4 100644
--- a/nuttx/configs/stm3210e-eval/src/up_composite.c
+++ b/nuttx/configs/stm3210e-eval/src/up_composite.c
@@ -2,7 +2,7 @@
* configs/stm3210e-eval/src/up_composite.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Configure and register the STM32 MMC/SD SDIO block driver.
*
diff --git a/nuttx/configs/stm3210e-eval/src/up_deselectlcd.c b/nuttx/configs/stm3210e-eval/src/up_deselectlcd.c
index 93e438ed5..e8642c2e0 100644
--- a/nuttx/configs/stm3210e-eval/src/up_deselectlcd.c
+++ b/nuttx/configs/stm3210e-eval/src/up_deselectlcd.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_deselectlcd.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_deselectnor.c b/nuttx/configs/stm3210e-eval/src/up_deselectnor.c
index 7450b8c72..135977023 100644
--- a/nuttx/configs/stm3210e-eval/src/up_deselectnor.c
+++ b/nuttx/configs/stm3210e-eval/src/up_deselectnor.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_deselectnor.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_deselectsram.c b/nuttx/configs/stm3210e-eval/src/up_deselectsram.c
index 51329eb15..442524d80 100644
--- a/nuttx/configs/stm3210e-eval/src/up_deselectsram.c
+++ b/nuttx/configs/stm3210e-eval/src/up_deselectsram.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_deselectsram.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_extcontext.c b/nuttx/configs/stm3210e-eval/src/up_extcontext.c
index 64b1d7ea6..07a202f06 100644
--- a/nuttx/configs/stm3210e-eval/src/up_extcontext.c
+++ b/nuttx/configs/stm3210e-eval/src/up_extcontext.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_extcontext.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_extmem.c b/nuttx/configs/stm3210e-eval/src/up_extmem.c
index 848e8fa0d..a47d0fe12 100644
--- a/nuttx/configs/stm3210e-eval/src/up_extmem.c
+++ b/nuttx/configs/stm3210e-eval/src/up_extmem.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_extmem.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_lm75.c b/nuttx/configs/stm3210e-eval/src/up_lm75.c
index 18107d947..d1bb288ff 100644
--- a/nuttx/configs/stm3210e-eval/src/up_lm75.c
+++ b/nuttx/configs/stm3210e-eval/src/up_lm75.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_lm75.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_nsh.c b/nuttx/configs/stm3210e-eval/src/up_nsh.c
index 36430a52a..96e1e5e58 100644
--- a/nuttx/configs/stm3210e-eval/src/up_nsh.c
+++ b/nuttx/configs/stm3210e-eval/src/up_nsh.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_nsh.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_selectlcd.c b/nuttx/configs/stm3210e-eval/src/up_selectlcd.c
index 221834ff5..3afc79835 100644
--- a/nuttx/configs/stm3210e-eval/src/up_selectlcd.c
+++ b/nuttx/configs/stm3210e-eval/src/up_selectlcd.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_selectlcd.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_selectnor.c b/nuttx/configs/stm3210e-eval/src/up_selectnor.c
index 3448b5e95..9ee1ad34f 100644
--- a/nuttx/configs/stm3210e-eval/src/up_selectnor.c
+++ b/nuttx/configs/stm3210e-eval/src/up_selectnor.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_selectnor.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_selectsram.c b/nuttx/configs/stm3210e-eval/src/up_selectsram.c
index be10a05f5..3035110c8 100644
--- a/nuttx/configs/stm3210e-eval/src/up_selectsram.c
+++ b/nuttx/configs/stm3210e-eval/src/up_selectsram.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_selectsram.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_spi.c b/nuttx/configs/stm3210e-eval/src/up_spi.c
index 3fc6567de..dacc3adf8 100644
--- a/nuttx/configs/stm3210e-eval/src/up_spi.c
+++ b/nuttx/configs/stm3210e-eval/src/up_spi.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_spi.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_usbdev.c b/nuttx/configs/stm3210e-eval/src/up_usbdev.c
index d77c79887..2ac9e50f4 100644
--- a/nuttx/configs/stm3210e-eval/src/up_usbdev.c
+++ b/nuttx/configs/stm3210e-eval/src/up_usbdev.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_boot.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/stm3210e-eval/src/up_usbmsc.c b/nuttx/configs/stm3210e-eval/src/up_usbmsc.c
index 4f788579c..dce463abc 100644
--- a/nuttx/configs/stm3210e-eval/src/up_usbmsc.c
+++ b/nuttx/configs/stm3210e-eval/src/up_usbmsc.c
@@ -2,7 +2,7 @@
* configs/stm3210e-eval/src/up_usbmsc.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Configure and register the STM32 MMC/SD SDIO block driver.
*
diff --git a/nuttx/configs/stm3210e-eval/usbserial/appconfig b/nuttx/configs/stm3210e-eval/usbserial/appconfig
index 00a928b56..fecff045b 100644
--- a/nuttx/configs/stm3210e-eval/usbserial/appconfig
+++ b/nuttx/configs/stm3210e-eval/usbserial/appconfig
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/usbserial/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/usbserial/setenv.sh b/nuttx/configs/stm3210e-eval/usbserial/setenv.sh
index fcb428c2f..046a7f5ac 100755
--- a/nuttx/configs/stm3210e-eval/usbserial/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/usbserial/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/ostest/setenv.sh
#
# Copyright (C) 2009 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/usbstorage/appconfig b/nuttx/configs/stm3210e-eval/usbstorage/appconfig
index b487fdfdd..646e4f4ed 100644
--- a/nuttx/configs/stm3210e-eval/usbstorage/appconfig
+++ b/nuttx/configs/stm3210e-eval/usbstorage/appconfig
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/usbstorage/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh b/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh
index d83685192..ee33a8d21 100755
--- a/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh
+++ b/nuttx/configs/stm3210e-eval/usbstorage/setenv.sh
@@ -2,7 +2,7 @@
# configs/stm3210e-eval/dfu/setenv.sh
#
# Copyright (C) 2009 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3220g-eval/dhcpd/appconfig b/nuttx/configs/stm3220g-eval/dhcpd/appconfig
index 2211494bd..46c59e818 100644
--- a/nuttx/configs/stm3220g-eval/dhcpd/appconfig
+++ b/nuttx/configs/stm3220g-eval/dhcpd/appconfig
@@ -2,7 +2,7 @@
# configs/stm3220g-eval/dhcpd/appconfig
#
# Copyright (C) 2012 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3220g-eval/src/up_selectlcd.c b/nuttx/configs/stm3220g-eval/src/up_selectlcd.c
index e8ab375ce..f6c531270 100644
--- a/nuttx/configs/stm3220g-eval/src/up_selectlcd.c
+++ b/nuttx/configs/stm3220g-eval/src/up_selectlcd.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_selectlcd.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
* Diego Sanchez <dsanchez@nx-engineering.com>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/configs/stm3240g-eval/dhcpd/appconfig b/nuttx/configs/stm3240g-eval/dhcpd/appconfig
index c586eeb8e..d6f0fd920 100644
--- a/nuttx/configs/stm3240g-eval/dhcpd/appconfig
+++ b/nuttx/configs/stm3240g-eval/dhcpd/appconfig
@@ -2,7 +2,7 @@
# configs/stm3240g-eval/dhcpd/appconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/stm3240g-eval/src/up_deselectlcd.c b/nuttx/configs/stm3240g-eval/src/up_deselectlcd.c
index e0bab8c39..93fdd97c4 100644
--- a/nuttx/configs/stm3240g-eval/src/up_deselectlcd.c
+++ b/nuttx/configs/stm3240g-eval/src/up_deselectlcd.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_deselectlcd.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
* Diego Sanchez <dsanchez@nx-engineering.com>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/configs/stm3240g-eval/src/up_selectlcd.c b/nuttx/configs/stm3240g-eval/src/up_selectlcd.c
index 5e4900654..e5781a1ea 100644
--- a/nuttx/configs/stm3240g-eval/src/up_selectlcd.c
+++ b/nuttx/configs/stm3240g-eval/src/up_selectlcd.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_selectlcd.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
* Diego Sanchez <dsanchez@nx-engineering.com>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/configs/stm3240g-eval/src/up_userleds.c b/nuttx/configs/stm3240g-eval/src/up_userleds.c
index 45e0fdd85..59be38561 100644
--- a/nuttx/configs/stm3240g-eval/src/up_userleds.c
+++ b/nuttx/configs/stm3240g-eval/src/up_userleds.c
@@ -1,6 +1,6 @@
/****************************************************************************
- * configs/stm3240g_eval/src/up_leds.c
- * arch/arm/src/board/up_leds.c
+ * configs/stm3240g_eval/src/up_userleds.c
+ * arch/arm/src/board/up_userleds.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>