summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:35:37 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:35:37 +0000
commit24acf10752079d502696d57e20c2078b4e2ea801 (patch)
tree1701d3d2c3f6c456a04442336d5fa406bf553b55 /nuttx
parentb468f0fc17590b77076802afd66e23cb78373943 (diff)
downloadpx4-nuttx-24acf10752079d502696d57e20c2078b4e2ea801.tar.gz
px4-nuttx-24acf10752079d502696d57e20c2078b4e2ea801.tar.bz2
px4-nuttx-24acf10752079d502696d57e20c2078b4e2ea801.zip
Resync new repository with old repo r5166
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5154 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog22
-rw-r--r--nuttx/TODO18
-rw-r--r--nuttx/arch/8051/src/up_assert.c4
-rw-r--r--nuttx/arch/Kconfig9
-rw-r--r--nuttx/arch/arm/Kconfig1
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq.h21
-rw-r--r--nuttx/arch/arm/src/arm/up_assert.c4
-rw-r--r--nuttx/arch/arm/src/armv7-m/svcall.h2
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_assert.c4
-rwxr-xr-xnuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S2
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_svcall.c2
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h5
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig69
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c383
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_spi.c31
-rw-r--r--nuttx/arch/avr/src/avr/avr_internal.h7
-rw-r--r--nuttx/arch/avr/src/avr32/avr32_internal.h7
-rw-r--r--nuttx/arch/avr/src/common/up_assert.c2
-rw-r--r--nuttx/arch/hc/src/common/up_internal.h4
-rw-r--r--nuttx/arch/hc/src/m9s12/m9s12_assert.c4
-rw-r--r--nuttx/arch/mips/include/mips32/syscall.h4
-rw-r--r--nuttx/arch/mips/src/mips32/up_assert.c4
-rw-r--r--nuttx/arch/mips/src/mips32/up_swint0.c4
-rw-r--r--nuttx/arch/sh/src/common/up_assert.c4
-rw-r--r--nuttx/arch/sh/src/common/up_internal.h5
-rw-r--r--nuttx/arch/sim/src/up_internal.h3
-rw-r--r--nuttx/arch/x86/include/i486/arch.h10
-rw-r--r--nuttx/arch/x86/src/common/up_assert.c4
-rw-r--r--nuttx/arch/x86/src/common/up_internal.h5
-rw-r--r--nuttx/arch/x86/src/i486/up_irq.c3
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S4
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_handlers.c5
-rw-r--r--nuttx/arch/z16/src/common/up_assert.c4
-rw-r--r--nuttx/arch/z80/src/common/up_assert.c4
-rw-r--r--nuttx/configs/amber/hello/defconfig2
-rwxr-xr-xnuttx/configs/avr32dev1/nsh/defconfig2
-rwxr-xr-xnuttx/configs/avr32dev1/ostest/defconfig2
-rwxr-xr-xnuttx/configs/demo9s12ne64/ostest/defconfig2
-rw-r--r--nuttx/configs/ea3131/nsh/defconfig2
-rw-r--r--nuttx/configs/ea3131/ostest/defconfig2
-rw-r--r--nuttx/configs/ea3131/pgnsh/defconfig2
-rw-r--r--nuttx/configs/ea3131/usbserial/defconfig2
-rw-r--r--nuttx/configs/ea3131/usbstorage/defconfig2
-rw-r--r--nuttx/configs/ea3152/ostest/defconfig2
-rw-r--r--nuttx/configs/eagle100/httpd/defconfig2
-rw-r--r--nuttx/configs/eagle100/nettest/defconfig2
-rw-r--r--nuttx/configs/eagle100/nsh/defconfig2
-rw-r--r--nuttx/configs/eagle100/nxflat/defconfig2
-rw-r--r--nuttx/configs/eagle100/ostest/defconfig2
-rw-r--r--nuttx/configs/eagle100/thttpd/defconfig2
-rw-r--r--nuttx/configs/ekk-lm3s9b96/nsh/defconfig2
-rw-r--r--nuttx/configs/ekk-lm3s9b96/ostest/defconfig2
-rw-r--r--nuttx/configs/fire-stm32v2/README.txt10
-rw-r--r--nuttx/configs/fire-stm32v2/nsh/defconfig132
-rw-r--r--nuttx/configs/fire-stm32v2/src/Makefile12
-rw-r--r--nuttx/configs/fire-stm32v2/src/fire-internal.h19
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_autoleds.c16
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_enc28j60.c4
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_mmcsd.c1
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_w25.c153
-rw-r--r--nuttx/configs/hymini-stm32v/buttons/defconfig2
-rwxr-xr-xnuttx/configs/hymini-stm32v/nsh/defconfig2
-rw-r--r--nuttx/configs/hymini-stm32v/nsh2/defconfig2
-rw-r--r--nuttx/configs/hymini-stm32v/nx/defconfig2
-rw-r--r--nuttx/configs/hymini-stm32v/nxlines/defconfig2
-rwxr-xr-xnuttx/configs/hymini-stm32v/usbserial/defconfig2
-rwxr-xr-xnuttx/configs/hymini-stm32v/usbstorage/defconfig2
-rwxr-xr-xnuttx/configs/kwikstik-k40/ostest/defconfig2
-rw-r--r--nuttx/configs/lincoln60/nsh/defconfig2
-rw-r--r--nuttx/configs/lincoln60/ostest/defconfig2
-rw-r--r--nuttx/configs/lm3s6432-s2e/nsh/defconfig2
-rw-r--r--nuttx/configs/lm3s6432-s2e/ostest/defconfig2
-rwxr-xr-xnuttx/configs/lm3s6965-ek/nsh/defconfig2
-rwxr-xr-xnuttx/configs/lm3s6965-ek/nx/defconfig2
-rwxr-xr-xnuttx/configs/lm3s6965-ek/ostest/defconfig2
-rwxr-xr-xnuttx/configs/lm3s8962-ek/nsh/defconfig2
-rwxr-xr-xnuttx/configs/lm3s8962-ek/nx/defconfig2
-rwxr-xr-xnuttx/configs/lm3s8962-ek/ostest/defconfig2
-rw-r--r--nuttx/configs/lpc4330-xplorer/nsh/defconfig2
-rw-r--r--nuttx/configs/lpc4330-xplorer/ostest/defconfig2
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig2
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/nsh/defconfig2
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/nx/defconfig2
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/ostest/defconfig2
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig2
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig2
-rw-r--r--nuttx/configs/mbed/hidkbd/defconfig2
-rwxr-xr-xnuttx/configs/mbed/nsh/defconfig2
-rw-r--r--nuttx/configs/micropendous3/hello/defconfig2
-rw-r--r--nuttx/configs/mirtoo/nsh/defconfig2
-rw-r--r--nuttx/configs/mirtoo/nxffs/defconfig2
-rw-r--r--nuttx/configs/mirtoo/ostest/defconfig2
-rw-r--r--nuttx/configs/mx1ads/ostest/defconfig2
-rwxr-xr-xnuttx/configs/ne64badge/ostest/defconfig2
-rwxr-xr-xnuttx/configs/nucleus2g/nsh/defconfig2
-rwxr-xr-xnuttx/configs/nucleus2g/ostest/defconfig2
-rwxr-xr-xnuttx/configs/nucleus2g/usbserial/defconfig2
-rwxr-xr-xnuttx/configs/nucleus2g/usbstorage/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/ftpc/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/hidkbd/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nettest/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nsh/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nx/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/ostest/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/thttpd/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbserial/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbstorage/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/wlan/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc2378/nsh/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc2378/ostest/defconfig2
-rw-r--r--nuttx/configs/olimex-stm32-p107/nsh/defconfig2
-rw-r--r--nuttx/configs/olimex-stm32-p107/ostest/defconfig2
-rwxr-xr-xnuttx/configs/olimex-strp711/nettest/defconfig12
-rw-r--r--nuttx/configs/pcblogic-pic32mx/nsh/defconfig2
-rw-r--r--nuttx/configs/pcblogic-pic32mx/ostest/defconfig2
-rw-r--r--nuttx/configs/pic32-starterkit/nsh/defconfig2
-rw-r--r--nuttx/configs/pic32-starterkit/nsh2/defconfig2
-rw-r--r--nuttx/configs/pic32-starterkit/ostest/defconfig2
-rw-r--r--nuttx/configs/pic32mx7mmb/nsh/defconfig2
-rw-r--r--nuttx/configs/pic32mx7mmb/ostest/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/knsh/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/nsh/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/nx/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/ostest/defconfig2
-rwxr-xr-xnuttx/configs/sam3u-ek/touchscreen/defconfig2
-rw-r--r--nuttx/configs/shenzhou/src/Makefile4
-rw-r--r--nuttx/configs/shenzhou/src/shenzhou-internal.h12
-rw-r--r--nuttx/configs/shenzhou/src/up_w25.c153
-rwxr-xr-xnuttx/configs/stm3210e-eval/RIDE/defconfig2
-rw-r--r--nuttx/configs/stm3210e-eval/buttons/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/composite/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/nsh/defconfig2
-rw-r--r--nuttx/configs/stm3210e-eval/nsh2/defconfig2
-rw-r--r--nuttx/configs/stm3210e-eval/nx/defconfig2
-rw-r--r--nuttx/configs/stm3210e-eval/nxconsole/defconfig2
-rw-r--r--nuttx/configs/stm3210e-eval/nxlines/defconfig2
-rw-r--r--nuttx/configs/stm3210e-eval/nxtext/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/defconfig2
-rw-r--r--nuttx/configs/stm3210e-eval/pm/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbserial/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbstorage/defconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/dhcpd/defconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/nettest/defconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/nsh/defconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/nsh2/defconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/nxwm/defconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/ostest/defconfig2
-rw-r--r--nuttx/configs/stm3220g-eval/telnetd/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/dhcpd/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/nettest/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/nsh/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/nsh2/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/nxconsole/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/nxwm/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/ostest/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/telnetd/defconfig2
-rw-r--r--nuttx/configs/stm3240g-eval/webserver/defconfig2
-rw-r--r--nuttx/configs/stm32f4discovery/nsh/defconfig2
-rw-r--r--nuttx/configs/stm32f4discovery/nxlines/defconfig2
-rw-r--r--nuttx/configs/stm32f4discovery/ostest/defconfig2
-rw-r--r--nuttx/configs/stm32f4discovery/pm/defconfig2
-rw-r--r--nuttx/configs/sure-pic32mx/nsh/defconfig2
-rw-r--r--nuttx/configs/sure-pic32mx/ostest/defconfig2
-rw-r--r--nuttx/configs/sure-pic32mx/usbnsh/defconfig2
-rw-r--r--nuttx/configs/teensy/hello/defconfig2
-rwxr-xr-xnuttx/configs/teensy/nsh/defconfig2
-rwxr-xr-xnuttx/configs/teensy/usbstorage/defconfig2
-rw-r--r--nuttx/configs/twr-k60n512/nsh/defconfig2
-rw-r--r--nuttx/configs/twr-k60n512/ostest/defconfig2
-rw-r--r--nuttx/configs/ubw32/nsh/defconfig2
-rw-r--r--nuttx/configs/ubw32/ostest/defconfig2
-rwxr-xr-xnuttx/configs/vsn/nsh/defconfig2
-rw-r--r--nuttx/drivers/Kconfig8
-rw-r--r--nuttx/drivers/mtd/Kconfig73
-rw-r--r--nuttx/drivers/mtd/Make.defs4
-rw-r--r--nuttx/drivers/mtd/sst25.c2
-rw-r--r--nuttx/drivers/mtd/w25.c1188
-rw-r--r--nuttx/drivers/net/Kconfig9
-rw-r--r--nuttx/drivers/net/enc28j60.c244
-rw-r--r--nuttx/drivers/net/enc28j60.h8
-rw-r--r--nuttx/include/nuttx/analog/adc.h3
-rw-r--r--nuttx/include/nuttx/compiler.h24
-rw-r--r--nuttx/include/nuttx/gran.h9
-rw-r--r--nuttx/include/nuttx/i2c.h26
-rw-r--r--nuttx/include/nuttx/mtd.h13
-rw-r--r--nuttx/include/nuttx/net/enc28j60.h16
-rw-r--r--nuttx/mm/README.txt35
-rw-r--r--nuttx/mm/mm_graninit.c9
-rw-r--r--nuttx/net/Kconfig2
-rw-r--r--nuttx/net/uip/uip_lock.c1
191 files changed, 2581 insertions, 539 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index b6817eab2..69379a290 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3349,3 +3349,25 @@
* configs/*/nxwm/defconfig and sched/task_exithook.c: Fixes for
bugs that crept in during recent changes. (Submitted by Max
Holtzberg).
+ * arch/arm/include/armv7-m/irq.h: Fix a critical bug in irqsave().
+ It looks like sometimes the compile will re-order some instructions
+ inapproapriately. This end result is that interrupts will get
+ stuff off.
+ * drivers/mtd/w25.c: Beginning of a driver for the Windbond SPI
+ FLASH family (W25x16, W25x32, and W25x64). The initial check-in
+ is basically just the SST25 driver with some name changes.
+ * arch/arm/include/armv7-m/irq.h and arch/arm/src/stm32/stm32_spi.c:
+ Back out the last change in irq.h. It is (most likely) fine the
+ way it was. The really interrupt related problem was in stm32_spi.c:
+ When SPI3 is not enabled, then the irqrestore() falls in the
+ else clause.
+ * include/nuttx/compiler.h and other files: Moved always_inline
+ and noinline __attributes__ here. Also replaced all occurrences
+ of explicit __atributes__ in other files with definitions from
+ this header file.
+ * drivers/mtd/w25.c: The Windbond SPI FLASH W25 FLASH driver is
+ code complete (but still untested).
+ * arch/arm/src/stm32/stm32_i2c.c: I2C improvements from Mike Smith.
+ Unified configuration logic; dynamic timeout calculations;
+ I2C reset logic to recover from locked devices on the bus.
+
diff --git a/nuttx/TODO b/nuttx/TODO
index 543d15f70..72a94290b 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -1,4 +1,4 @@
-NuttX TODO List (Last updated August 12, 2012)
+NuttX TODO List (Last updated September 16, 2012)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This file summarizes known NuttX bugs, limitations, inconsistencies with
@@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements.
nuttx/
- (5) Task/Scheduler (sched/)
+ (6) Task/Scheduler (sched/)
(1) On-demand paging (sched/)
(1) Memory Managment (mm/)
(2) Signals (sched/, arch/)
@@ -110,6 +110,13 @@ o Task/Scheduler (sched/)
Status: Open
Priority: Low
+ Title: posix_spawn()
+ Description: This would be a good interface to add to NuttX. It is really
+ just a re-packaging of the existing, non-standard NuttX exec()
+ function.
+ Status: Open
+ Priority: Medium low.
+
o On-demand paging (sched/)
^^^^^^^^^^^^^^^^^^^^^^^^^
@@ -541,13 +548,6 @@ o Network (net/, drivers/net)
Status: Open
Priority: Low... fix defconfig files as necessary.
- Title: UNFINISHED ENC28J60 DRIVER
- Description: So far, I have not come up with a usable hardware platform to
- verify the ENC28J60 Ethernet driver (drivers/net/enc28j60.c).
- So it is untested.
- Status: Open
- Priority: Low unless you need it.
-
o USB (drivers/usbdev, drivers/usbhost)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/arch/8051/src/up_assert.c b/nuttx/arch/8051/src/up_assert.c
index 10a5daf35..46d731041 100644
--- a/nuttx/arch/8051/src/up_assert.c
+++ b/nuttx/arch/8051/src/up_assert.c
@@ -1,7 +1,7 @@
/************************************************************************
* up_assert.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -65,7 +65,7 @@
* Name: _up_assert
************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/Kconfig b/nuttx/arch/Kconfig
index b445e5620..bbe99c17c 100644
--- a/nuttx/arch/Kconfig
+++ b/nuttx/arch/Kconfig
@@ -153,13 +153,14 @@ config ARCH_HAVE_INTERRUPTSTACK
bool
config ARCH_INTERRUPTSTACK
- bool "Use interrupt stack"
+ int "Interrupt Stack Size"
depends on ARCH_HAVE_INTERRUPTSTACK
- default y
+ default 0
---help---
This architecture supports an interrupt stack. If defined, this symbol
- is the size of the interrupt stack in bytes. If not defined, the user
- task stacks will be used during interrupt handling.
+ will be the size of the interrupt stack in bytes. If not defined (or
+ defined to be zero), the user task stacks will be used during interrupt
+ handling.
comment "Boot options"
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 3bd531232..2a7ea10b5 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -103,6 +103,7 @@ config ARCH_CHIP_STM32
bool "STMicro STM32"
select ARCH_HAVE_CMNVECTOR
select ARCH_HAVE_MPU
+ select ARCH_HAVE_I2CRESET
---help---
STMicro STM32 architectures (ARM Cortex-M3/4).
diff --git a/nuttx/arch/arm/include/armv7-m/irq.h b/nuttx/arch/arm/include/armv7-m/irq.h
index 6cef85c02..606b3988f 100644
--- a/nuttx/arch/arm/include/armv7-m/irq.h
+++ b/nuttx/arch/arm/include/armv7-m/irq.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/include/armv7-m/irq.h
*
- * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,6 +48,7 @@
#include <nuttx/irq.h>
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@@ -131,6 +132,7 @@ struct xcptcontext
/* Disable IRQs */
+static inline void irqdisable(void) inline_function;
static inline void irqdisable(void)
{
__asm__ __volatile__ ("\tcpsid i\n");
@@ -138,6 +140,7 @@ static inline void irqdisable(void)
/* Save the current primask state & disable IRQs */
+static inline irqstate_t irqsave(void) inline_function;
static inline irqstate_t irqsave(void)
{
unsigned short primask;
@@ -153,11 +156,13 @@ static inline irqstate_t irqsave(void)
: "=r" (primask)
:
: "memory");
+
return primask;
}
/* Enable IRQs */
+static inline void irqenable(void) inline_function;
static inline void irqenable(void)
{
__asm__ __volatile__ ("\tcpsie i\n");
@@ -165,6 +170,7 @@ static inline void irqenable(void)
/* Restore saved primask state */
+static inline void irqrestore(irqstate_t primask) inline_function;
static inline void irqrestore(irqstate_t primask)
{
/* If bit 0 of the primask is 0, then we need to restore
@@ -184,6 +190,7 @@ static inline void irqrestore(irqstate_t primask)
/* Get/set the primask register */
+static inline uint8_t getprimask(void) inline_function;
static inline uint8_t getprimask(void)
{
uint32_t primask;
@@ -193,9 +200,11 @@ static inline uint8_t getprimask(void)
: "=r" (primask)
:
: "memory");
+
return (uint8_t)primask;
}
+static inline void setprimask(uint32_t primask) inline_function;
static inline void setprimask(uint32_t primask)
{
__asm__ __volatile__
@@ -208,18 +217,22 @@ static inline void setprimask(uint32_t primask)
/* Get/set the basepri register */
+static inline uint8_t getbasepri(void) inline_function;
static inline uint8_t getbasepri(void)
{
uint32_t basepri;
+
__asm__ __volatile__
(
"\tmrs %0, basepri\n"
: "=r" (basepri)
:
: "memory");
+
return (uint8_t)basepri;
}
+static inline void setbasepri(uint32_t basepri) inline_function;
static inline void setbasepri(uint32_t basepri)
{
__asm__ __volatile__
@@ -232,6 +245,7 @@ static inline void setbasepri(uint32_t basepri)
/* Get/set IPSR */
+static inline uint32_t getipsr(void) inline_function;
static inline uint32_t getipsr(void)
{
uint32_t ipsr;
@@ -241,9 +255,11 @@ static inline uint32_t getipsr(void)
: "=r" (ipsr)
:
: "memory");
+
return ipsr;
}
+static inline void setipsr(uint32_t ipsr) inline_function;
static inline void setipsr(uint32_t ipsr)
{
__asm__ __volatile__
@@ -256,6 +272,7 @@ static inline void setipsr(uint32_t ipsr)
/* Get/set CONTROL */
+static inline uint32_t getcontrol(void) inline_function;
static inline uint32_t getcontrol(void)
{
uint32_t control;
@@ -265,9 +282,11 @@ static inline uint32_t getcontrol(void)
: "=r" (control)
:
: "memory");
+
return control;
}
+static inline void setcontrol(uint32_t control) inline_function;
static inline void setcontrol(uint32_t control)
{
__asm__ __volatile__
diff --git a/nuttx/arch/arm/src/arm/up_assert.c b/nuttx/arch/arm/src/arm/up_assert.c
index 023e6e22d..3d75a4655 100644
--- a/nuttx/arch/arm/src/arm/up_assert.c
+++ b/nuttx/arch/arm/src/arm/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/arm/up_assert.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -252,7 +252,7 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/arm/src/armv7-m/svcall.h b/nuttx/arch/arm/src/armv7-m/svcall.h
index 9a4db89b1..675829799 100644
--- a/nuttx/arch/arm/src/armv7-m/svcall.h
+++ b/nuttx/arch/arm/src/armv7-m/svcall.h
@@ -74,7 +74,7 @@
/* SYS call 1:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*/
#define SYS_restore_context (1)
diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c
index 2662cbe37..282ff6a57 100644
--- a/nuttx/arch/arm/src/armv7-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv7-m/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_assert.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -262,7 +262,7 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S b/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S
index 3ce51c9cd..4c77b66b8 100755
--- a/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S
+++ b/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S
@@ -69,7 +69,7 @@
* Description:
* Restore the current thread context. Full prototype is:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
* Return:
* None
diff --git a/nuttx/arch/arm/src/armv7-m/up_svcall.c b/nuttx/arch/arm/src/armv7-m/up_svcall.c
index 5a4d64fe2..d32f0afc2 100644
--- a/nuttx/arch/arm/src/armv7-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv7-m/up_svcall.c
@@ -280,7 +280,7 @@ int up_svcall(int irq, FAR void *context)
/* R0=SYS_restore_context: This a restore context command:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
* At this point, the following values are saved in context:
*
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 45cb1dcc0..9f20775c0 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -40,7 +40,10 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <sys/types.h>
# include <stdint.h>
#endif
@@ -223,7 +226,7 @@ extern void up_boot(void);
extern void up_copystate(uint32_t *dest, uint32_t *src);
extern void up_decodeirq(uint32_t *regs);
extern int up_saveusercontext(uint32_t *saveregs);
-extern void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+extern void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
extern void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
/* Signal handling **********************************************************/
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index b5d0306da..8b0cea32e 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -191,14 +191,17 @@ menu "STM32 Peripheral Support"
config STM32_ADC1
bool "ADC1"
default n
+ select STM32_ADC
config STM32_ADC2
bool "ADC2"
default n
+ select STM32_ADC
config STM32_ADC3
bool "ADC3"
default n
+ select STM32_ADC
config STM32_CRC
bool "CRC"
@@ -228,12 +231,14 @@ config STM32_CAN1
bool "CAN1"
default n
select CAN
+ select STM32_CAN
config STM32_CAN2
bool "CAN2"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
select CAN
+ select STM32_CAN
config STM32_CCMDATARAM
bool "CMD/DATA RAM"
@@ -248,10 +253,12 @@ config STM32_CRYP
config STM32_DAC1
bool "DAC1"
default n
+ select STM32_DAC
config STM32_DAC2
bool "DAC2"
default n
+ select STM32_DAC
config STM32_DCMI
bool "DCMI"
@@ -276,15 +283,18 @@ config STM32_HASH
config STM32_I2C1
bool "I2C1"
default n
+ select STM32_I2C
config STM32_I2C2
bool "I2C2"
default n
+ select STM32_I2C
config STM32_I2C3
bool "I2C3"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
+ select STM32_I2C
config STM32_IWDG
bool "IWDG"
@@ -319,23 +329,27 @@ config STM32_SPI1
bool "SPI1"
default n
select SPI
+ select STM32_SPI
config STM32_SPI2
bool "SPI2"
default n
select SPI
+ select STM32_SPI
config STM32_SPI3
bool "SPI3"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
select SPI
+ select STM32_SPI
config STM32_SPI4
bool "SPI4"
default n
depends on STM32_STM32F10XX
select SPI
+ select STM32_SPI
config STM32_SYSCFG
bool "SYSCFG"
@@ -450,19 +464,18 @@ endmenu
config STM32_ADC
bool
- default y if STM32_ADC1 || STM32_ADC2 || STM32_ADC3
config STM32_DAC
bool
- default y if STM32_DAC1 || STM32_ADC2
config STM32_SPI
bool
- default y if STM32_SPI1 || STM32_SPI2 || STM32_SPI3 || STM32_SPI4
+
+config STM32_I2C
+ bool
config STM32_CAN
bool
- default y if STM32_CAN1 || STM32_CAN2
menu "Alternate Pin Mapping"
@@ -571,10 +584,10 @@ choice
config STM32_CAN1_NO_REMAP
bool "No pin remapping"
-config CONFIG_STM32_CAN1_REMAP1
+config STM32_CAN1_REMAP1
bool "CAN1 alternate pin remapping #1"
-config CONFIG_STM32_CAN1_REMAP2
+config STM32_CAN1_REMAP2
bool "CAN1 alternate pin remapping #2"
endchoice
@@ -1600,6 +1613,46 @@ config STM32_SPI_DMA
endmenu
+menu "I2C Configuration"
+ depends on STM32_I2C
+
+config STM32_I2C_DYNTIMEO
+ bool "Use dynamic timeouts"
+ default n
+ depends on STM32_I2C
+
+config STM32_I2C_DYNTIMEO_USECPERBYTE
+ int "Timeout Microseconds per Byte"
+ default 0
+ depends on STM32_I2C_DYNTIMEO
+
+config STM32_I2C_DYNTIMEO_STARTSTOP
+ int "Timeout for Start/Stop (Milliseconds)"
+ default 5000
+ depends on STM32_I2C_DYNTIMEO
+
+config STM32_I2CTIMEOSEC
+ int "Timeout seconds"
+ default 0
+ depends on STM32_I2C
+
+config STM32_I2CTIMEOMS
+ int "Timeout Milliseconds"
+ default 500
+ depends on STM32_I2C && !STM32_I2C_DYNTIMEO
+
+config STM32_I2CTIMEOTICKS
+ int "Timeout for Done and Stop (ticks)"
+ default 500
+ depends on STM32_I2C && !STM32_I2C_DYNTIMEO
+
+config STM32_I2C_DUTY16_9
+ bool "Frequency with Tlow/Thigh = 16/9 "
+ default n
+ depends on STM32_I2C
+
+endmenu
+
menu "SDIO Configuration"
depends on STM32_SDIO
@@ -1826,13 +1879,13 @@ config STM32_USBHOST_REGDEBUG
default n
depends on USBHOST && STM32_OTGFS
---help---
- Enable very low-level register access debug. Depends on CONFIG_DEBUG.
+ Enable very low-level register access debug. Depends on DEBUG.
config STM32_USBHOST_PKTDUMP
bool "Packet Dump Debug"
default n
depends on USBHOST && STM32_OTGFS
---help---
- Dump all incoming and outgoing USB packets. Depends on CONFIG_DEBUG.
+ Dump all incoming and outgoing USB packets. Depends on DEBUG.
endmenu
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index cbd6f6b14..bd3031b2d 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -107,11 +107,11 @@
#if !defined(CONFIG_STM32_I2CTIMEOSEC) && !defined(CONFIG_STM32_I2CTIMEOMS)
# define CONFIG_STM32_I2CTIMEOSEC 0
-# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
+# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOSEC)
# define CONFIG_STM32_I2CTIMEOSEC 0 /* User provided milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOMS)
-# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
+# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
#endif
/* Interrupt wait time timeout in system timer ticks */
@@ -119,6 +119,10 @@
#define CONFIG_STM32_I2CTIMEOTICKS \
(SEC2TICK(CONFIG_STM32_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32_I2CTIMEOMS))
+#ifndef CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP
+# define CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP TICK2USEC(CONFIG_STM32_I2CTIMEOTICKS)
+#endif
+
/* On the STM32F103ZE, there is an internal conflict between I2C1 and FSMC. In that
* case, it is necessary to disable FSMC before each I2C1 access and re-enable FSMC
* when the I2C access completes.
@@ -129,6 +133,18 @@
# define I2C1_FSMC_CONFLICT
#endif
+/* Macros to convert a I2C pin to a GPIO output */
+
+#if defined(CONFIG_STM32_STM32F10XX)
+# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_OUTPUT_SET | GPIO_CNF_OUTOD | \
+ GPIO_MODE_50MHz)
+#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_FLOAT | GPIO_OPENDRAIN |\
+ GPIO_SPEED_50MHz | GPIO_OUTPUT_SET)
+#endif
+
+#define MKI2C_OUTPUT(p) (((p) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | I2C_OUTPUT)
+
/* Debug ****************************************************************************/
/* CONFIG_DEBUG_I2C + CONFIG_DEBUG enables general I2C debug output. */
@@ -196,36 +212,52 @@ struct stm32_trace_s
uint32_t time; /* First of event or first status */
};
+/* I2C Device hardware configuration */
+
+struct stm32_i2c_config_s
+{
+ uint32_t base; /* I2C base address */
+ uint32_t clk_bit; /* Clock enable bit */
+ uint32_t reset_bit; /* Reset bit */
+ uint32_t scl_pin; /* GPIO configuration for SCL as SCL */
+ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */
+#ifndef CONFIG_I2C_POLLED
+ int (*isr)(int, void *); /* Interrupt handler */
+ uint32_t ev_irq; /* Event IRQ */
+ uint32_t er_irq; /* Error IRQ */
+#endif
+};
+
/* I2C Device Private Data */
struct stm32_i2c_priv_s
{
- uint32_t base; /* I2C base address */
- int refs; /* Referernce count */
- sem_t sem_excl; /* Mutual exclusion semaphore */
+ const struct stm32_i2c_config_s *config; /* Port configuration */
+ int refs; /* Referernce count */
+ sem_t sem_excl; /* Mutual exclusion semaphore */
#ifndef CONFIG_I2C_POLLED
- sem_t sem_isr; /* Interrupt wait semaphore */
+ sem_t sem_isr; /* Interrupt wait semaphore */
#endif
- volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
+ volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
- uint8_t msgc; /* Message count */
- struct i2c_msg_s *msgv; /* Message list */
- uint8_t *ptr; /* Current message buffer */
- int dcnt; /* Current message length */
- uint16_t flags; /* Current message flags */
+ uint8_t msgc; /* Message count */
+ struct i2c_msg_s *msgv; /* Message list */
+ uint8_t *ptr; /* Current message buffer */
+ int dcnt; /* Current message length */
+ uint16_t flags; /* Current message flags */
/* I2C trace support */
#ifdef CONFIG_I2C_TRACE
- int tndx; /* Trace array index */
- uint32_t start_time; /* Time when the trace was started */
+ int tndx; /* Trace array index */
+ uint32_t start_time; /* Time when the trace was started */
/* The actual trace data */
struct stm32_trace_s trace[CONFIG_I2C_NTRACE];
#endif
- uint32_t status; /* End of transfer SR2|SR1 status */
+ uint32_t status; /* End of transfer SR2|SR1 status */
};
/* I2C Device, Instance */
@@ -252,6 +284,9 @@ static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset, uint16_t clearbits,
uint16_t setbits);
static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev);
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs);
+#endif /* CONFIG_STM32_I2C_DYNTIMEO */
static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_sem_post(FAR struct i2c_dev_s *dev);
@@ -263,7 +298,7 @@ static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t statu
static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
enum stm32_trace_e event, uint32_t parm);
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv);
-#endif
+#endif /* CONFIG_I2C_TRACE */
static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv,
uint32_t frequency);
static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv);
@@ -273,7 +308,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv);
#ifdef I2C1_FSMC_CONFLICT
static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_enablefsmc(uint32_t ahbenr);
-#endif
+#endif /* I2C1_FSMC_CONFLICT */
static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv);
#ifndef CONFIG_I2C_POLLED
#ifdef CONFIG_STM32_I2C1
@@ -311,9 +346,23 @@ static int stm32_i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *m
************************************************************************************/
#ifdef CONFIG_STM32_I2C1
-struct stm32_i2c_priv_s stm32_i2c1_priv =
+static const struct stm32_i2c_config_s stm32_i2c1_config =
{
.base = STM32_I2C1_BASE,
+ .clk_bit = RCC_APB1ENR_I2C1EN,
+ .reset_bit = RCC_APB1RSTR_I2C1RST,
+ .scl_pin = GPIO_I2C1_SCL,
+ .sda_pin = GPIO_I2C1_SDA,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c1_isr,
+ .ev_irq = STM32_IRQ_I2C1EV,
+ .er_irq = STM32_IRQ_I2C1ER
+#endif
+};
+
+struct stm32_i2c_priv_s stm32_i2c1_priv =
+{
+ .config = &stm32_i2c1_config,
.refs = 0,
.intstate = INTSTATE_IDLE,
.msgc = 0,
@@ -326,9 +375,23 @@ struct stm32_i2c_priv_s stm32_i2c1_priv =
#endif
#ifdef CONFIG_STM32_I2C2
-struct stm32_i2c_priv_s stm32_i2c2_priv =
+static const struct stm32_i2c_config_s stm32_i2c2_config =
{
.base = STM32_I2C2_BASE,
+ .clk_bit = RCC_APB1ENR_I2C2EN,
+ .reset_bit = RCC_APB1RSTR_I2C2RST,
+ .scl_pin = GPIO_I2C2_SCL,
+ .sda_pin = GPIO_I2C2_SDA,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c2_isr,
+ .ev_irq = STM32_IRQ_I2C2EV,
+ .er_irq = STM32_IRQ_I2C2ER
+#endif
+};
+
+struct stm32_i2c_priv_s stm32_i2c2_priv =
+{
+ .config = &stm32_i2c2_config,
.refs = 0,
.intstate = INTSTATE_IDLE,
.msgc = 0,
@@ -341,9 +404,23 @@ struct stm32_i2c_priv_s stm32_i2c2_priv =
#endif
#ifdef CONFIG_STM32_I2C3
-struct stm32_i2c_priv_s stm32_i2c3_priv =
+static const struct stm32_i2c_config_s stm32_i2c3_config =
{
.base = STM32_I2C3_BASE,
+ .clk_bit = RCC_APB1ENR_I2C3EN,
+ .reset_bit = RCC_APB1RSTR_I2C3RST,
+ .scl_pin = GPIO_I2C3_SCL,
+ .sda_pin = GPIO_I2C3_SDA,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c3_isr,
+ .ev_irq = STM32_IRQ_I2C3EV,
+ .er_irq = STM32_IRQ_I2C3ER
+#endif
+};
+
+struct stm32_i2c_priv_s stm32_i2c3_priv =
+{
+ .config = &stm32_i2c3_config,
.refs = 0,
.intstate = INTSTATE_IDLE,
.msgc = 0,
@@ -355,7 +432,6 @@ struct stm32_i2c_priv_s stm32_i2c3_priv =
};
#endif
-
/* Device Structures, Instantiation */
struct i2c_ops_s stm32_i2c_ops =
@@ -391,7 +467,7 @@ struct i2c_ops_s stm32_i2c_ops =
static inline uint16_t stm32_i2c_getreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset)
{
- return getreg16(priv->base + offset);
+ return getreg16(priv->config->base + offset);
}
/************************************************************************************
@@ -405,7 +481,7 @@ static inline uint16_t stm32_i2c_getreg(FAR struct stm32_i2c_priv_s *priv,
static inline void stm32_i2c_putreg(FAR struct stm32_i2c_priv_s *priv, uint8_t offset,
uint16_t value)
{
- putreg16(value, priv->base + offset);
+ putreg16(value, priv->config->base + offset);
}
/************************************************************************************
@@ -420,7 +496,7 @@ static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset, uint16_t clearbits,
uint16_t setbits)
{
- modifyreg16(priv->base + offset, clearbits, setbits);
+ modifyreg16(priv->config->base + offset, clearbits, setbits);
}
/************************************************************************************
@@ -440,6 +516,35 @@ static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
}
/************************************************************************************
+ * Name: stm32_i2c_tousecs
+ *
+ * Description:
+ * Return a micro-second delay based on the number of bytes left to be processed.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs)
+{
+ size_t bytecount = 0;
+ int i;
+
+ /* Count the number of bytes left to process */
+
+ for (i = 0; i < msgc; i++)
+ {
+ bytecount += msgs[i].length;
+ }
+
+ /* Then return a number of microseconds based on a user provided scaling
+ * factor.
+ */
+
+ return (useconds_t)(CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE * bytecount);
+}
+#endif
+
+/************************************************************************************
* Name: stm32_i2c_sem_waitdone
*
* Description:
@@ -480,7 +585,18 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
#if CONFIG_STM32_I2CTIMEOSEC > 0
abstime.tv_sec += CONFIG_STM32_I2CTIMEOSEC;
#endif
-#if CONFIG_STM32_I2CTIMEOMS > 0
+
+ /* Add a value proportional to the number of bytes in the transfer */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ abstime.tv_nsec += 1000 * stm32_i2c_tousecs(priv->msgc, priv->msgv);
+ if (abstime.tv_nsec > 1000 * 1000 * 1000)
+ {
+ abstime.tv_sec++;
+ abstime.tv_nsec -= 1000 * 1000 * 1000;
+ }
+
+#elif CONFIG_STM32_I2CTIMEOMS > 0
abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
if (abstime.tv_nsec > 1000 * 1000 * 1000)
{
@@ -520,12 +636,21 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
return ret;
}
#else
-static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv )
+static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
{
+ uint32_t timeout;
uint32_t start;
uint32_t elapsed;
int ret;
+ /* Get the timeout value */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ timeout = USEC2TICK(stm32_i2c_tousecs(priv->msgc, priv->msgv));
+#else
+ timeout = CONFIG_STM32_I2CTIMEOTICKS;
+#endif
+
/* Signal the interrupt handler that we are waiting. NOTE: Interrupts
* are currently disabled but will be temporarily re-enabled below when
* sem_timedwait() sleeps.
@@ -533,6 +658,7 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv )
priv->intstate = INTSTATE_WAITING;
start = clock_systimer();
+
do
{
/* Poll by simply calling the timer interrupt handler until it
@@ -548,10 +674,10 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv )
/* Loop until the transfer is complete. */
- while (priv->intstate != INTSTATE_DONE && elapsed < CONFIG_STM32_I2CTIMEOTICKS);
+ while (priv->intstate != INTSTATE_DONE && elapsed < timeout);
i2cvdbg("intstate: %d elapsed: %d threshold: %d status: %08x\n",
- priv->intstate, elapsed, CONFIG_STM32_I2CTIMEOTICKS, priv->status);
+ priv->intstate, elapsed, timeout, priv->status);
/* Set the interrupt state back to IDLE */
@@ -573,9 +699,18 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
{
uint32_t start;
uint32_t elapsed;
+ uint32_t timeout;
uint32_t cr1;
uint32_t sr1;
+ /* Select a timeout */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ timeout = USEC2TICK(CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP);
+#else
+ timeout = CONFIG_STM32_I2CTIMEOTICKS;
+#endif
+
/* Wait as stop might still be in progress; but stop might also
* be set because of a timeout error: "The [STOP] bit is set and
* cleared by software, cleared by hardware when a Stop condition is
@@ -608,7 +743,7 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
/* Loop until the stop is complete or a timeout occurs. */
- while (elapsed < CONFIG_STM32_I2CTIMEOTICKS);
+ while (elapsed < timeout);
/* If we get here then a timeout occurred with the STOP condition
* still pending.
@@ -828,7 +963,7 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ
{
/* Fast mode speed calculation with Tlow/Thigh = 16/9 */
-#ifdef CONFIG_I2C_DUTY16_9
+#ifdef CONFIG_STM32_I2C_DUTY16_9
speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25));
/* Set DUTY and fast speed bits */
@@ -967,8 +1102,8 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv)
/* Is this I2C1 */
-#ifdef CONFIG_STM32_I2C2
- if (priv->base == STM32_I2C1_BASE)
+#if defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3)
+ if (priv->config->base == STM32_I2C1_BASE)
#endif
{
/* Disable FSMC unconditionally */
@@ -1094,6 +1229,14 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
{
stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt);
+ /* No interrupts or context switches may occur in the following
+ * sequence. Otherwise, additional bytes may be sent by the
+ * device.
+ */
+
+#ifdef CONFIG_I2C_POLLED
+ irqstate_t state = irqsave();
+#endif
/* Receive a byte */
*priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET);
@@ -1105,6 +1248,10 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0);
}
priv->dcnt--;
+
+#ifdef CONFIG_I2C_POLLED
+ irqrestore(state);
+#endif
}
}
@@ -1292,113 +1439,33 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
{
/* Power-up and configure GPIOs */
- switch (priv->base)
- {
-#ifdef CONFIG_STM32_I2C1
- case STM32_I2C1_BASE:
-
- /* Enable power and reset the peripheral */
-
- modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C1EN);
-
- modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C1RST);
- modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C1RST, 0);
-
- /* Configure pins */
-
- if (stm32_configgpio(GPIO_I2C1_SCL) < 0)
- {
- return ERROR;
- }
+ /* Enable power and reset the peripheral */
- if (stm32_configgpio(GPIO_I2C1_SDA) < 0)
- {
- stm32_unconfiggpio(GPIO_I2C1_SCL);
- return ERROR;
- }
+ modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit);
+ modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit);
+ modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0);
- /* Attach ISRs */
-
-#ifndef CONFIG_I2C_POLLED
- irq_attach(STM32_IRQ_I2C1EV, stm32_i2c1_isr);
- irq_attach(STM32_IRQ_I2C1ER, stm32_i2c1_isr);
- up_enable_irq(STM32_IRQ_I2C1EV);
- up_enable_irq(STM32_IRQ_I2C1ER);
-#endif
- break;
-#endif
+ /* Configure pins */
-#ifdef CONFIG_STM32_I2C2
- case STM32_I2C2_BASE:
-
- /* Enable power and reset the peripheral */
-
- modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C2EN);
-
- modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C2RST);
- modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C2RST, 0);
-
- /* Configure pins */
-
- if (stm32_configgpio(GPIO_I2C2_SCL) < 0)
- {
- return ERROR;
- }
-
- if (stm32_configgpio(GPIO_I2C2_SDA) < 0)
- {
- stm32_unconfiggpio(GPIO_I2C2_SCL);
- return ERROR;
- }
-
- /* Attach ISRs */
-
-#ifndef CONFIG_I2C_POLLED
- irq_attach(STM32_IRQ_I2C2EV, stm32_i2c2_isr);
- irq_attach(STM32_IRQ_I2C2ER, stm32_i2c2_isr);
- up_enable_irq(STM32_IRQ_I2C2EV);
- up_enable_irq(STM32_IRQ_I2C2ER);
-#endif
- break;
-#endif
-
-#ifdef CONFIG_STM32_I2C3
- case STM32_I2C3_BASE:
-
- /* Enable power and reset the peripheral */
-
- modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C3EN);
-
- modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C3RST);
- modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C3RST, 0);
-
- /* Configure pins */
-
- if (stm32_configgpio(GPIO_I2C3_SCL) < 0)
- {
- return ERROR;
- }
-
- if (stm32_configgpio(GPIO_I2C3_SDA) < 0)
- {
- stm32_unconfiggpio(GPIO_I2C3_SCL);
- return ERROR;
- }
+ if (stm32_configgpio(priv->config->scl_pin) < 0)
+ {
+ return ERROR;
+ }
- /* Attach ISRs */
+ if (stm32_configgpio(priv->config->sda_pin) < 0)
+ {
+ stm32_unconfiggpio(priv->config->scl_pin);
+ return ERROR;
+ }
+ /* Attach ISRs */
+
#ifndef CONFIG_I2C_POLLED
- irq_attach(STM32_IRQ_I2C3EV, stm32_i2c3_isr);
- irq_attach(STM32_IRQ_I2C3ER, stm32_i2c3_isr);
- up_enable_irq(STM32_IRQ_I2C3EV);
- up_enable_irq(STM32_IRQ_I2C3ER);
+ irq_attach(priv->config->ev_irq, priv->config->isr);
+ irq_attach(priv->config->er_irq, priv->config->isr);
+ up_enable_irq(priv->config->ev_irq);
+ up_enable_irq(priv->config->er_irq);
#endif
- break;
-#endif
-
- default:
- return ERROR;
- }
/* Set peripheral frequency, where it must be at least 2 MHz for 100 kHz
* or 4 MHz for 400 kHz. This also disables all I2C interrupts.
@@ -1427,42 +1494,23 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv)
stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0);
- switch (priv->base)
- {
-#ifdef CONFIG_STM32_I2C1
- case STM32_I2C1_BASE:
- stm32_unconfiggpio(GPIO_I2C1_SCL);
- stm32_unconfiggpio(GPIO_I2C1_SDA);
+ /* Unconfigure GPIO pins */
-#ifndef CONFIG_I2C_POLLED
- up_disable_irq(STM32_IRQ_I2C1EV);
- up_disable_irq(STM32_IRQ_I2C1ER);
- irq_detach(STM32_IRQ_I2C1EV);
- irq_detach(STM32_IRQ_I2C1ER);
-#endif
- modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_I2C1EN, 0);
- break;
-#endif
-
-#ifdef CONFIG_STM32_I2C2
- case STM32_I2C2_BASE:
- stm32_unconfiggpio(GPIO_I2C2_SCL);
- stm32_unconfiggpio(GPIO_I2C2_SDA);
+ stm32_unconfiggpio(priv->config->scl_pin);
+ stm32_unconfiggpio(priv->config->sda_pin);
+
+ /* Disable and detach interrupts */
#ifndef CONFIG_I2C_POLLED
- up_disable_irq(STM32_IRQ_I2C2EV);
- up_disable_irq(STM32_IRQ_I2C2ER);
- irq_detach(STM32_IRQ_I2C2EV);
- irq_detach(STM32_IRQ_I2C2ER);
+ up_disable_irq(priv->config->ev_irq);
+ up_disable_irq(priv->config->er_irq);
+ irq_detach(priv->config->ev_irq);
+ irq_detach(priv->config->er_irq);
#endif
- modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_I2C2EN, 0);
- break;
-#endif
-
- default:
- return ERROR;
- }
+ /* Disable clocking */
+
+ modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
return OK;
}
@@ -1524,14 +1572,13 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
struct stm32_i2c_inst_s *inst = (struct stm32_i2c_inst_s *)dev;
FAR struct stm32_i2c_priv_s *priv = inst->priv;
uint32_t status = 0;
- uint32_t ahbenr;
int errval = 0;
ASSERT(count);
/* Disable FSMC that shares a pin with I2C1 (LBAR) */
- ahbenr = stm32_i2c_disablefsmc(priv);
+ (void)stm32_i2c_disablefsmc(priv);
/* Wait for any STOP in progress. NOTE: If we have to disable the FSMC
* then we cannot do this at the top of the loop, unfortunately. The STOP
@@ -1594,6 +1641,10 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/
stm32_i2c_clrstart(priv);
+
+ /* Clear busy flag in case of timeout */
+
+ status = priv->status & 0xffff;
}
else
{
@@ -1914,4 +1965,4 @@ int up_i2cuninitialize(FAR struct i2c_dev_s * dev)
return OK;
}
-#endif /* defined(CONFIG_STM32_I2C1) && defined(CONFIG_STM32_I2C2) */
+#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C2 || CONFIG_STM32_I2C3 */
diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c
index 40b1a29a0..8de698cd5 100644
--- a/nuttx/arch/arm/src/stm32/stm32_spi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_spi.c
@@ -49,7 +49,7 @@
* 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
+ * SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
@@ -881,7 +881,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
else
{
/* Less than fPCLK/128. This is as slow as we can go */
-
+
setbits = SPI_CR1_FPCLCKd256; /* 111: fPCLK/256 */
actual = priv->spiclock >> 8;
}
@@ -941,22 +941,22 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
setbits = 0;
clrbits = SPI_CR1_CPOL|SPI_CR1_CPHA;
break;
-
+
case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */
setbits = SPI_CR1_CPHA;
clrbits = SPI_CR1_CPOL;
break;
-
+
case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */
setbits = SPI_CR1_CPOL;
clrbits = SPI_CR1_CPHA;
break;
-
+
case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */
setbits = SPI_CR1_CPOL|SPI_CR1_CPHA;
clrbits = 0;
break;
-
+
default:
return;
}
@@ -1008,7 +1008,7 @@ static void spi_setbits(FAR struct spi_dev_s *dev, int nbits)
setbits = 0;
clrbits = SPI_CR1_DFF;
break;
-
+
case 16:
setbits = SPI_CR1_DFF;
clrbits = 0;
@@ -1111,7 +1111,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
}
/* Exchange one word */
-
+
word = spi_send(dev, word);
/* Is there a buffer to receive the return value? */
@@ -1120,7 +1120,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
{
*dest++ = word;
}
- }
+ }
}
else
{
@@ -1144,7 +1144,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
}
/* Exchange one word */
-
+
word = (uint8_t)spi_send(dev, (uint16_t)word);
/* Is there a buffer to receive the return value? */
@@ -1152,7 +1152,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
if (dest)
{
*dest++ = word;
- }
+ }
}
}
}
@@ -1331,7 +1331,7 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv)
priv->txdma = stm32_dmachannel(priv->txch);
DEBUGASSERT(priv->rxdma && priv->txdma);
#endif
-
+
/* Enable spi */
spi_modifycr1(priv, SPI_CR1_SPE, 0);
@@ -1360,7 +1360,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
FAR struct stm32_spidev_s *priv = NULL;
irqstate_t flags = irqsave();
-
+
#ifdef CONFIG_STM32_SPI1
if (port == 1)
{
@@ -1431,7 +1431,12 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
spi_portinitialize(priv);
}
}
+ else
#endif
+ {
+ spidbg("ERROR: Unsupported SPI port: %d\n", port);
+ return NULL;
+ }
irqrestore(flags);
return (FAR struct spi_dev_s *)priv;
diff --git a/nuttx/arch/avr/src/avr/avr_internal.h b/nuttx/arch/avr/src/avr/avr_internal.h
index c87254b77..031000cd1 100644
--- a/nuttx/arch/avr/src/avr/avr_internal.h
+++ b/nuttx/arch/avr/src/avr/avr_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/avr/src/avr/avr_internal.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -40,7 +40,10 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <sys/types.h>
# include <stdint.h>
# include <stdbool.h>
@@ -111,7 +114,7 @@ extern void up_copystate(uint8_t *dest, uint8_t *src);
*
************************************************************************************/
-extern void up_fullcontextrestore(uint8_t *restoreregs) __attribute__ ((noreturn));
+extern void up_fullcontextrestore(uint8_t *restoreregs) noreturn_function;
/************************************************************************************
* Name: up_switchcontext
diff --git a/nuttx/arch/avr/src/avr32/avr32_internal.h b/nuttx/arch/avr/src/avr32/avr32_internal.h
index 680e2c804..3d45f6c54 100644
--- a/nuttx/arch/avr/src/avr32/avr32_internal.h
+++ b/nuttx/arch/avr/src/avr32/avr32_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/avr/src/avr32/up_internal.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -40,7 +40,10 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@@ -109,7 +112,7 @@ extern void up_copystate(uint32_t *dest, uint32_t *src);
*
************************************************************************************/
-extern void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+extern void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
/************************************************************************************
* Name: up_switchcontext
diff --git a/nuttx/arch/avr/src/common/up_assert.c b/nuttx/arch/avr/src/common/up_assert.c
index 82c58d658..12bb564d3 100644
--- a/nuttx/arch/avr/src/common/up_assert.c
+++ b/nuttx/arch/avr/src/common/up_assert.c
@@ -90,7 +90,7 @@
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/hc/src/common/up_internal.h b/nuttx/arch/hc/src/common/up_internal.h
index e54b86dec..f1daf690f 100644
--- a/nuttx/arch/hc/src/common/up_internal.h
+++ b/nuttx/arch/hc/src/common/up_internal.h
@@ -41,7 +41,9 @@
****************************************************************************/
#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@@ -152,7 +154,7 @@ extern void up_copystate(uint8_t *dest, uint8_t *src);
extern void up_decodeirq(uint8_t *regs);
extern void up_irqinitialize(void);
extern int up_saveusercontext(uint8_t *saveregs);
-extern void up_fullcontextrestore(uint8_t *restoreregs) __attribute__ ((noreturn));
+extern void up_fullcontextrestore(uint8_t *restoreregs) noreturn_function;
extern void up_switchcontext(uint8_t *saveregs, uint8_t *restoreregs);
/* Interrupt handling */
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_assert.c b/nuttx/arch/hc/src/m9s12/m9s12_assert.c
index 386bcb2df..ff9ce5ca4 100644
--- a/nuttx/arch/hc/src/m9s12/m9s12_assert.c
+++ b/nuttx/arch/hc/src/m9s12/m9s12_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/hc/src/m9s12/m9s12_assert.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -247,7 +247,7 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/mips/include/mips32/syscall.h b/nuttx/arch/mips/include/mips32/syscall.h
index 9c497c8b6..d91eed993 100644
--- a/nuttx/arch/mips/include/mips32/syscall.h
+++ b/nuttx/arch/mips/include/mips32/syscall.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/include/mips32/syscall.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -150,7 +150,7 @@
/* SYS call 1:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*/
#define SYS_restore_context (1)
diff --git a/nuttx/arch/mips/src/mips32/up_assert.c b/nuttx/arch/mips/src/mips32/up_assert.c
index 881ec12cb..ed4ee4cf7 100644
--- a/nuttx/arch/mips/src/mips32/up_assert.c
+++ b/nuttx/arch/mips/src/mips32/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/src/mips32/up_assert.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -90,7 +90,7 @@
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/mips/src/mips32/up_swint0.c b/nuttx/arch/mips/src/mips32/up_swint0.c
index 6a1042721..87ccddf71 100644
--- a/nuttx/arch/mips/src/mips32/up_swint0.c
+++ b/nuttx/arch/mips/src/mips32/up_swint0.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/src/mips32/up_swint0.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -290,7 +290,7 @@ int up_swint0(int irq, FAR void *context)
{
/* R4=SYS_restore_context: This a restore context command:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
* At this point, the following values are saved in context:
*
diff --git a/nuttx/arch/sh/src/common/up_assert.c b/nuttx/arch/sh/src/common/up_assert.c
index cfd7854df..ccc0c98e6 100644
--- a/nuttx/arch/sh/src/common/up_assert.c
+++ b/nuttx/arch/sh/src/common/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_assert.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -76,7 +76,7 @@
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/sh/src/common/up_internal.h b/nuttx/arch/sh/src/common/up_internal.h
index 0504755f6..f47b1078f 100644
--- a/nuttx/arch/sh/src/common/up_internal.h
+++ b/nuttx/arch/sh/src/common/up_internal.h
@@ -40,7 +40,10 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@@ -144,7 +147,7 @@ extern void up_copystate(uint32_t *dest, uint32_t *src);
extern void up_dataabort(uint32_t *regs);
extern void up_decodeirq(uint32_t *regs);
extern uint32_t *up_doirq(int irq, uint32_t *regs);
-extern void up_fullcontextrestore(uint32_t *regs) __attribute__ ((noreturn));
+extern void up_fullcontextrestore(uint32_t *regs) noreturn_function;
extern void up_irqinitialize(void);
extern void up_prefetchabort(uint32_t *regs);
extern int up_saveusercontext(uint32_t *regs);
diff --git a/nuttx/arch/sim/src/up_internal.h b/nuttx/arch/sim/src/up_internal.h
index 04fd71efc..dff51b9cf 100644
--- a/nuttx/arch/sim/src/up_internal.h
+++ b/nuttx/arch/sim/src/up_internal.h
@@ -41,6 +41,7 @@
**************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <sys/types.h>
#include <nuttx/irq.h>
@@ -150,7 +151,7 @@ extern volatile int g_eventloop;
/* up_setjmp.S ************************************************************/
extern int up_setjmp(int *jb);
-extern void up_longjmp(int *jb, int val) __attribute__ ((noreturn));
+extern void up_longjmp(int *jb, int val) noreturn_function;
/* up_devconsole.c ********************************************************/
diff --git a/nuttx/arch/x86/include/i486/arch.h b/nuttx/arch/x86/include/i486/arch.h
index 64d9d85bf..6bb2418d7 100644
--- a/nuttx/arch/x86/include/i486/arch.h
+++ b/nuttx/arch/x86/include/i486/arch.h
@@ -45,7 +45,9 @@
****************************************************************************/
#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@@ -323,7 +325,7 @@ struct gdt_entry_s
uint8_t access; /* Access flags, determine ring segment can be used in */
uint8_t granularity;
uint8_t hibase; /* The last 8 bits of the base */
-} __attribute__((packed));
+} packed_struct;
/* This structure refers to the array of GDT entries, and is in the format
* required by the lgdt instruction.
@@ -333,7 +335,7 @@ struct gdt_ptr_s
{
uint16_t limit; /* The upper 16 bits of all selector limits */
uint32_t base; /* The address of the first GDT entry */
-} __attribute__((packed));
+} packed_struct;
/* IDT data structures ******************************************************
*
@@ -349,7 +351,7 @@ struct idt_entry_s
uint8_t zero; /* This must always be zero */
uint8_t flags; /* (See documentation) */
uint16_t hibase; /* Upper 16-bits of vector address for interrupt */
-} __attribute__((packed));
+} packed_struct;
/* A struct describing a pointer to an array of interrupt handlers. This is
* in a format suitable for giving to 'lidt'.
@@ -359,7 +361,7 @@ struct idt_ptr_s
{
uint16_t limit;
uint32_t base; /* The address of the first GDT entry */
-} __attribute__((packed));
+} packed_struct;
/****************************************************************************
* Inline functions
diff --git a/nuttx/arch/x86/src/common/up_assert.c b/nuttx/arch/x86/src/common/up_assert.c
index be82a3616..aa752f84e 100644
--- a/nuttx/arch/x86/src/common/up_assert.c
+++ b/nuttx/arch/x86/src/common/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/x86/src/common/up_assert.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -209,7 +209,7 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/x86/src/common/up_internal.h b/nuttx/arch/x86/src/common/up_internal.h
index 22956ecb3..df43ca1a8 100644
--- a/nuttx/arch/x86/src/common/up_internal.h
+++ b/nuttx/arch/x86/src/common/up_internal.h
@@ -40,7 +40,10 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@@ -174,7 +177,7 @@ extern void up_irqinitialize(void);
extern void weak_function up_dmainitialize(void);
#endif
extern int up_saveusercontext(uint32_t *saveregs);
-extern void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+extern void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
extern void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
extern void up_sigdeliver(void);
extern void up_lowputc(char ch);
diff --git a/nuttx/arch/x86/src/i486/up_irq.c b/nuttx/arch/x86/src/i486/up_irq.c
index 3eb6d6070..a160379e2 100644
--- a/nuttx/arch/x86/src/i486/up_irq.c
+++ b/nuttx/arch/x86/src/i486/up_irq.c
@@ -39,6 +39,7 @@
****************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <stdint.h>
#include <string.h>
@@ -62,7 +63,7 @@
* Private Function Prototypes
****************************************************************************/
-static void idt_outb(uint8_t val, uint16_t addr) __attribute__((noinline));
+static void idt_outb(uint8_t val, uint16_t addr) noinline_function;
static void up_remappic(void);
static void up_idtentry(unsigned int index, uint32_t base, uint16_t sel,
uint8_t flags);
diff --git a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
index 50ebdc041..8ba59a5a7 100644
--- a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
+++ b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
@@ -1,7 +1,7 @@
/**************************************************************************
* arch/x86/src/qemu/qemu_fullcontextrestore.S
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -89,7 +89,7 @@
* Name: up_fullcontextrestore
*
* Full C prototype:
- * void up_fullcontextrestore(uint32_t *regs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *regs) noreturn_function;
*
**************************************************************************/
diff --git a/nuttx/arch/x86/src/qemu/qemu_handlers.c b/nuttx/arch/x86/src/qemu/qemu_handlers.c
index aeb9b8b1f..a0d6028aa 100644
--- a/nuttx/arch/x86/src/qemu/qemu_handlers.c
+++ b/nuttx/arch/x86/src/qemu/qemu_handlers.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/x86/src/qemu/qemu_handlers.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -38,6 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <nuttx/arch.h>
#include <arch/io.h>
@@ -52,7 +53,7 @@
* Private Function Prototypes
****************************************************************************/
-static void idt_outb(uint8_t val, uint16_t addr) __attribute__((noinline));
+static void idt_outb(uint8_t val, uint16_t addr) noinline_function;
/****************************************************************************
* Private Data
diff --git a/nuttx/arch/z16/src/common/up_assert.c b/nuttx/arch/z16/src/common/up_assert.c
index d7d614a91..5832ead45 100644
--- a/nuttx/arch/z16/src/common/up_assert.c
+++ b/nuttx/arch/z16/src/common/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_assert.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -77,7 +77,7 @@
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/z80/src/common/up_assert.c b/nuttx/arch/z80/src/common/up_assert.c
index b35e8dd33..ff4e569fb 100644
--- a/nuttx/arch/z80/src/common/up_assert.c
+++ b/nuttx/arch/z80/src/common/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_assert.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -77,7 +77,7 @@
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/configs/amber/hello/defconfig b/nuttx/configs/amber/hello/defconfig
index b148b1e0d..66127604e 100644
--- a/nuttx/configs/amber/hello/defconfig
+++ b/nuttx/configs/amber/hello/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=4096
CONFIG_DRAM_START=0x800100
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
diff --git a/nuttx/configs/avr32dev1/nsh/defconfig b/nuttx/configs/avr32dev1/nsh/defconfig
index 730d84391..b9f6e35a6 100755
--- a/nuttx/configs/avr32dev1/nsh/defconfig
+++ b/nuttx/configs/avr32dev1/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x00000000
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/avr32dev1/ostest/defconfig b/nuttx/configs/avr32dev1/ostest/defconfig
index e8d8e378a..74ac8f072 100755
--- a/nuttx/configs/avr32dev1/ostest/defconfig
+++ b/nuttx/configs/avr32dev1/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x00000000
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/demo9s12ne64/ostest/defconfig b/nuttx/configs/demo9s12ne64/ostest/defconfig
index e3b6cac17..6265e6e53 100755
--- a/nuttx/configs/demo9s12ne64/ostest/defconfig
+++ b/nuttx/configs/demo9s12ne64/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ea3131/nsh/defconfig b/nuttx/configs/ea3131/nsh/defconfig
index 928fdb239..32521f012 100644
--- a/nuttx/configs/ea3131/nsh/defconfig
+++ b/nuttx/configs/ea3131/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x11028000
CONFIG_DRAM_VSTART=0x11028000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ea3131/ostest/defconfig b/nuttx/configs/ea3131/ostest/defconfig
index 6b6b9b584..1ef35f969 100644
--- a/nuttx/configs/ea3131/ostest/defconfig
+++ b/nuttx/configs/ea3131/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x11028000
CONFIG_DRAM_VSTART=0x11028000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ea3131/pgnsh/defconfig b/nuttx/configs/ea3131/pgnsh/defconfig
index 8f49d59a8..995bc90d9 100644
--- a/nuttx/configs/ea3131/pgnsh/defconfig
+++ b/nuttx/configs/ea3131/pgnsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x11028000
CONFIG_DRAM_VSTART=0x11028000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ea3131/usbserial/defconfig b/nuttx/configs/ea3131/usbserial/defconfig
index 7dae3c2cf..4e45989df 100644
--- a/nuttx/configs/ea3131/usbserial/defconfig
+++ b/nuttx/configs/ea3131/usbserial/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x11028000
CONFIG_DRAM_VSTART=0x11028000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ea3131/usbstorage/defconfig b/nuttx/configs/ea3131/usbstorage/defconfig
index 6ee7bb40d..772de7e69 100644
--- a/nuttx/configs/ea3131/usbstorage/defconfig
+++ b/nuttx/configs/ea3131/usbstorage/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x11028000
CONFIG_DRAM_VSTART=0x11028000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ea3152/ostest/defconfig b/nuttx/configs/ea3152/ostest/defconfig
index 5af1310f4..845faf60b 100644
--- a/nuttx/configs/ea3152/ostest/defconfig
+++ b/nuttx/configs/ea3152/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x11028000
CONFIG_DRAM_VSTART=0x11028000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig
index 3ad922097..0fdddc2df 100644
--- a/nuttx/configs/eagle100/httpd/defconfig
+++ b/nuttx/configs/eagle100/httpd/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig
index 78994b11e..943f46223 100644
--- a/nuttx/configs/eagle100/nettest/defconfig
+++ b/nuttx/configs/eagle100/nettest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig
index fb2fcf5ff..2e04850b3 100644
--- a/nuttx/configs/eagle100/nsh/defconfig
+++ b/nuttx/configs/eagle100/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/eagle100/nxflat/defconfig b/nuttx/configs/eagle100/nxflat/defconfig
index 7befde172..d4228f16b 100644
--- a/nuttx/configs/eagle100/nxflat/defconfig
+++ b/nuttx/configs/eagle100/nxflat/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig
index 6bcde74b9..6cffe1450 100644
--- a/nuttx/configs/eagle100/ostest/defconfig
+++ b/nuttx/configs/eagle100/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/eagle100/thttpd/defconfig b/nuttx/configs/eagle100/thttpd/defconfig
index b32960945..afb7dbce8 100644
--- a/nuttx/configs/eagle100/thttpd/defconfig
+++ b/nuttx/configs/eagle100/thttpd/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig
index e1422da7f..1e162a4a1 100644
--- a/nuttx/configs/ekk-lm3s9b96/nsh/defconfig
+++ b/nuttx/configs/ekk-lm3s9b96/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=98304
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig
index 4eebaca3a..d08e99077 100644
--- a/nuttx/configs/ekk-lm3s9b96/ostest/defconfig
+++ b/nuttx/configs/ekk-lm3s9b96/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=98304
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/fire-stm32v2/README.txt b/nuttx/configs/fire-stm32v2/README.txt
index d01ba3219..3a94365af 100644
--- a/nuttx/configs/fire-stm32v2/README.txt
+++ b/nuttx/configs/fire-stm32v2/README.txt
@@ -765,10 +765,18 @@ Where <subdir> is one of the following:
contains support for some built-in applications that can be enabled by making
some additional minor change to the configuration file.
- NOTE: This configuration uses to the mconf configuration tool to control
+ Reconfiguring: This configuration uses to the mconf configuration tool to control
the configuration. See the section entitled "NuttX Configuration Tool"
in the top-level README.txt file.
+ Start Delays: If no SD card is present in the slot, or if the network is not
+ connected, then there will be long start-up delays before you get the NSH
+ prompt. If I am focused on ENC28J60 debug, I usually disable MMC/SD so that
+ I don't have to bother with the SD card:
+
+ CONFIG_STM32_SDIO=n
+ CONFIG_MMCSD=n
+
STATUS: The board port is basically functional. Not all features have been
verified. The ENC28J60 network is not yet functional. Networking is
enabled by default in this configuration for testing purposes. To use this
diff --git a/nuttx/configs/fire-stm32v2/nsh/defconfig b/nuttx/configs/fire-stm32v2/nsh/defconfig
index 1a849ad36..fd5187801 100644
--- a/nuttx/configs/fire-stm32v2/nsh/defconfig
+++ b/nuttx/configs/fire-stm32v2/nsh/defconfig
@@ -201,7 +201,7 @@ CONFIG_ARCH_STACKDUMP=y
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=65536
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
-# CONFIG_ARCH_INTERRUPTSTACK is not set
+CONFIG_ARCH_INTERRUPTSTACK=0
#
# Boot options
@@ -289,8 +289,8 @@ CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
CONFIG_MAX_WDOGPARMS=2
-CONFIG_PREALLOC_WDOGS=4
-CONFIG_PREALLOC_TIMERS=4
+CONFIG_PREALLOC_WDOGS=16
+CONFIG_PREALLOC_TIMERS=8
#
# Stack and heap information
@@ -387,12 +387,17 @@ CONFIG_USART2_BITS=8
CONFIG_USART2_PARITY=0
CONFIG_USART2_2STOP=0
CONFIG_USBDEV=y
-# CONFIG_USBDEV_COMPOSITE is not set
+
+#
+# Device Controller Driver Options
+#
# CONFIG_USBDEV_ISOCHRONOUS is not set
# CONFIG_USBDEV_DUALSPEED is not set
CONFIG_USBDEV_SELFPOWERED=y
# CONFIG_USBDEV_BUSPOWERED is not set
+# CONFIG_USBDEV_DMA is not set
# CONFIG_USBDEV_TRACE is not set
+# CONFIG_USBDEV_COMPOSITE is not set
# CONFIG_PL2303 is not set
# CONFIG_CDCACM is not set
CONFIG_USBMSC=y
@@ -425,7 +430,7 @@ CONFIG_USBMSC_REMOVABLE=y
# Networking Support
#
CONFIG_NET=y
-# CONFIG_NET_NOINTS is not set
+CONFIG_NET_NOINTS=y
# CONFIG_NET_MULTIBUFFER is not set
# CONFIG_NET_IPv6 is not set
CONFIG_NSOCKET_DESCRIPTORS=16
@@ -521,142 +526,142 @@ CONFIG_NAMEDAPP=y
#
#
-# ADC example
+# ADC Example
#
# CONFIG_EXAMPLES_ADC is not set
#
-# Buttons example
+# Buttons Example
#
# CONFIG_EXAMPLES_BUTTONS is not set
#
-# CAN example
+# CAN Example
#
# CONFIG_EXAMPLES_CAN is not set
#
-# USB CDC/ACM class driver example
+# USB CDC/ACM Class Driver Example
#
# CONFIG_EXAMPLES_CDCACM is not set
#
-# USB composite class driver example
+# USB composite Class Driver Example
#
# CONFIG_EXAMPLES_COMPOSITE is not set
#
-# DHCP server example
+# DHCP Server Example
#
# CONFIG_EXAMPLES_DHCPD is not set
#
-# FTP client example
+# FTP Client Example
#
# CONFIG_EXAMPLES_FTPC is not set
#
-# FTP server example
+# FTP Server Example
#
# CONFIG_EXAMPLES_FTPD is not set
#
-# "Hello, World!" example
+# "Hello, World!" Example
#
# CONFIG_EXAMPLES_HELLO is not set
#
-# "Hello, World!" C++ example
+# "Hello, World!" C++ Example
#
# CONFIG_EXAMPLES_HELLOXX is not set
#
-# USB HID keyboard example
+# USB HID Keyboard Example
#
# CONFIG_EXAMPLES_HIDKBD is not set
#
-# IGMP example
+# IGMP Example
#
# CONFIG_EXAMPLES_IGMP is not set
#
-# LCD read/write example
+# LCD Read/Write Example
#
# CONFIG_EXAMPLES_LCDRW is not set
#
-# Memory management example
+# Memory Management Example
#
# CONFIG_EXAMPLES_MM is not set
#
-# File system mount example
+# File System Mount Example
#
# CONFIG_EXAMPLES_MOUNT is not set
#
-# FreeModBus example
+# FreeModBus Example
#
# CONFIG_EXAMPLES_MODBUS is not set
#
-# Network test example
+# Network Test Example
#
# CONFIG_EXAMPLES_NETTEST is not set
#
-# NuttShell (NSH) example
+# NuttShell (NSH) Example
#
CONFIG_EXAMPLES_NSH=y
#
-# NULL example
+# NULL Example
#
# CONFIG_EXAMPLES_NULL is not set
#
-# NX graphics example
+# NX Graphics Example
#
# CONFIG_EXAMPLES_NX is not set
#
-# NxConsole example
+# NxConsole Example
#
# CONFIG_EXAMPLES_NXCONSOLE is not set
#
-# NXFFS file system example
+# NXFFS File System Example
#
# CONFIG_EXAMPLES_NXFFS is not set
#
-# NXFLAT example
+# NXFLAT Example
#
# CONFIG_EXAMPLES_NXFLAT is not set
#
-# NX graphics "Hello, World!" example
+# NX Graphics "Hello, World!" Example
#
# CONFIG_EXAMPLES_NXHELLO is not set
#
-# NX graphics image example
+# NX Graphics image Example
#
# CONFIG_EXAMPLES_NXIMAGE is not set
#
-# NX graphics lines example
+# NX Graphics lines Example
#
# CONFIG_EXAMPLES_NXLINES is not set
#
-# NX graphics text example
+# NX Graphics Text Example
#
# CONFIG_EXAMPLES_NXTEXT is not set
#
-# OS test example
+# OS Test Example
#
# CONFIG_EXAMPLES_OSTEST is not set
@@ -666,81 +671,86 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_PASHELLO is not set
#
-# Pipe example
+# Pipe Example
#
# CONFIG_EXAMPLES_PIPE is not set
#
-# Poll example
+# Poll Example
#
# CONFIG_EXAMPLES_POLL is not set
#
-# Pulse width modulation (PWM) example
+# Pulse Width Modulation (PWM) Example
#
#
-# Quadrature encoder example
+# Quadrature Encoder Example
#
# CONFIG_EXAMPLES_QENCODER is not set
#
-# RGMP example
+# RGMP Example
#
# CONFIG_EXAMPLES_RGMP is not set
#
-# ROMFS example
+# ROMFS Example
#
# CONFIG_EXAMPLES_ROMFS is not set
#
-# sendmail example
+# sendmail Example
#
# CONFIG_EXAMPLES_SENDMAIL is not set
#
-# Serial loopback example
+# Serial Loopback Example
#
# CONFIG_EXAMPLES_SERLOOP is not set
#
-# Telnet daemon example
+# Telnet Daemon Example
#
# CONFIG_EXAMPLES_TELNETD is not set
#
-# THTTPD web server example
+# THTTPD Web Server Example
#
# CONFIG_EXAMPLES_THTTPD is not set
#
-# TIFF generation example
+# TIFF Generation Example
#
# CONFIG_EXAMPLES_TIFF is not set
#
-# Touchscreen example
+# Touchscreen Example
#
# CONFIG_EXAMPLES_TOUCHSCREEN is not set
#
-# UDP example
+# UDP Example
#
# CONFIG_EXAMPLES_UDP is not set
#
-# uIP web server example
+# UDP Discovery Daemon Example
+#
+# CONFIG_EXAMPLE_DISCOVER is not set
+
+#
+# uIP Web Server Example
#
# CONFIG_EXAMPLES_UIP is not set
#
-# USB serial test example
+# USB Serial Test Example
#
# CONFIG_EXAMPLES_USBSERIAL is not set
#
-# USB mass storage class example
+# USB Mass Storage Class Example
#
CONFIG_EXAMPLES_USBMSC=y
CONFIG_EXAMPLES_USBMSC_BUILTIN=y
@@ -759,26 +769,30 @@ CONFIG_EXAMPLES_USBMSC_DEVPATH3="/dev/mmcsd2"
# CONFIG_EXAMPLES_USBMSC_TRACEINTERRUPTS is not set
#
-# USB serial terminal example
+# USB Serial Terminal Example
#
# CONFIG_EXAMPLES_USBTERM is not set
#
-# Watchdog timer example
+# Watchdog timer Example
#
# CONFIG_EXAMPLES_WATCHDOG is not set
#
-# wget example
+# wget Example
#
# CONFIG_EXAMPLES_WGET is not set
#
-# WLAN example
+# WLAN Example
#
# CONFIG_EXAMPLES_WLAN is not set
#
+# XML RPC Example
+#
+
+#
# Interpreters
#
@@ -858,6 +872,16 @@ CONFIG_NETUTILS_WEBCLIENT=y
# CONFIG_NETUTILS_WEBSERVER is not set
#
+# UDP Discovery Utility
+#
+# CONFIG_NETUTILS_DISCOVER is not set
+
+#
+# XML-RPC library
+#
+# CONFIG_NETUTILS_XMLRPC is not set
+
+#
# ModBus
#
@@ -933,7 +957,7 @@ CONFIG_NSH_IOBUFFER_SIZE=512
CONFIG_NSH_IPADDR=0x0a000002
CONFIG_NSH_DRIPADDR=0x0a000001
CONFIG_NSH_NETMASK=0xffffff00
-# CONFIG_NSH_NOMAC is not set
+CONFIG_NSH_NOMAC=y
#
# System NSH Add-Ons
diff --git a/nuttx/configs/fire-stm32v2/src/Makefile b/nuttx/configs/fire-stm32v2/src/Makefile
index 4c4fd1d41..d605a8f3b 100644
--- a/nuttx/configs/fire-stm32v2/src/Makefile
+++ b/nuttx/configs/fire-stm32v2/src/Makefile
@@ -56,10 +56,6 @@ else
CSRCS += up_userleds.c
endif
-ifeq ($(CONFIG_ENC28J60),y)
-CSRCS += up_enc28j60.c
-endif
-
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c
endif
@@ -68,6 +64,14 @@ ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
+ifeq ($(CONFIG_ENC28J60),y)
+CSRCS += up_enc28j60.c
+endif
+
+ifeq ($(CONFIG_MTD_W25),y)
+CSRCS += up_w25.c
+endif
+
ifeq ($(CONFIG_USBMSC),y)
CSRCS += up_usbmsc.c
endif
diff --git a/nuttx/configs/fire-stm32v2/src/fire-internal.h b/nuttx/configs/fire-stm32v2/src/fire-internal.h
index 801fb127e..e9f7a8508 100644
--- a/nuttx/configs/fire-stm32v2/src/fire-internal.h
+++ b/nuttx/configs/fire-stm32v2/src/fire-internal.h
@@ -214,15 +214,16 @@
# warning "TFT LCD and ENCJ2860 shared PE1"
#endif
-/* CS and Reset are active low. Initial states are not selected and not in
- * reset (driver does a soft reset).
+/* CS and Reset are active low. Initial states are not selected and in
+ * reset. The ENC28J60 is taken out of reset when the driver is
+ * initialized (thedriver does a soft reset too).
*/
#ifdef CONFIG_ENC28J60
# define GPIO_ENC28J60_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
# define GPIO_ENC28J60_RESET (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
- GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN1)
+ GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN1)
# define GPIO_ENC28J60_INTR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
GPIO_EXTI|GPIO_PORTE|GPIO_PIN5)
#endif
@@ -302,6 +303,18 @@ void stm32_selectlcd(void);
int stm32_sdinitialize(int minor);
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MTD_W25
+int stm32_w25initialize(int minor);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_FIRE_STM32V2_SRC_FIRE_INTERNAL_H */
diff --git a/nuttx/configs/fire-stm32v2/src/up_autoleds.c b/nuttx/configs/fire-stm32v2/src/up_autoleds.c
index 4e70b01dd..5ecef46c0 100644
--- a/nuttx/configs/fire-stm32v2/src/up_autoleds.c
+++ b/nuttx/configs/fire-stm32v2/src/up_autoleds.c
@@ -115,23 +115,23 @@
#define LED_STARTED_ON_SETBITS (0)
#define LED_STARTED_ON_CLRBITS ((FIRE_LED1|FIRE_LED2|FIRE_LED3) << ON_CLRBITS_SHIFT)
-#define LED_STARTED_OFF_SETBITS LED_STARTED_ON_SETBITS
-#define LED_STARTED_OFF_CLRBITS LED_STARTED_ON_CLRBITS
+#define LED_STARTED_OFF_SETBITS (0)
+#define LED_STARTED_OFF_CLRBITS ((FIRE_LED1|FIRE_LED2|FIRE_LED3) << OFF_CLRBITS_SHIFT)
#define LED_HEAPALLOCATE_ON_SETBITS ((FIRE_LED1) << ON_SETBITS_SHIFT)
#define LED_HEAPALLOCATE_ON_CLRBITS ((FIRE_LED2|FIRE_LED3) << ON_CLRBITS_SHIFT)
-#define LED_HEAPALLOCATE_OFF_SETBITS LED_STARTED_ON_SETBITS
-#define LED_HEAPALLOCATE_OFF_CLRBITS LED_STARTED_ON_CLRBITS
+#define LED_HEAPALLOCATE_OFF_SETBITS (0)
+#define LED_HEAPALLOCATE_OFF_CLRBITS ((FIRE_LED1|FIRE_LED2|FIRE_LED3) << OFF_CLRBITS_SHIFT)
#define LED_IRQSENABLED_ON_SETBITS ((FIRE_LED2) << ON_SETBITS_SHIFT)
#define LED_IRQSENABLED_ON_CLRBITS ((FIRE_LED1|FIRE_LED3) << ON_CLRBITS_SHIFT)
-#define LED_IRQSENABLED_OFF_SETBITS LED_HEAPALLOCATE_ON_SETBITS
-#define LED_IRQSENABLED_OFF_CLRBITS LED_HEAPALLOCATE_ON_CLRBITS
+#define LED_IRQSENABLED_OFF_SETBITS ((FIRE_LED1) << OFF_SETBITS_SHIFT)
+#define LED_IRQSENABLED_OFF_CLRBITS ((FIRE_LED1|FIRE_LED2|FIRE_LED3) << OFF_CLRBITS_SHIFT)
#define LED_STACKCREATED_ON_SETBITS (0)
#define LED_STACKCREATED_ON_CLRBITS ((FIRE_LED1|FIRE_LED2|FIRE_LED3) << ON_CLRBITS_SHIFT)
-#define LED_STACKCREATED_OFF_SETBITS LED_IRQSENABLED_ON_SETBITS
-#define LED_STACKCREATED_OFF_CLRBITS LED_IRQSENABLED_ON_CLRBITS
+#define LED_STACKCREATED_OFF_SETBITS ((FIRE_LED2) << OFF_SETBITS_SHIFT)
+#define LED_STACKCREATED_OFF_CLRBITS ((FIRE_LED1|FIRE_LED3) << OFF_CLRBITS_SHIFT)
#define LED_FLASH_ON_SETBITS ((FIRE_LED3) << ON_SETBITS_SHIFT)
#define LED_FLASH_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
diff --git a/nuttx/configs/fire-stm32v2/src/up_enc28j60.c b/nuttx/configs/fire-stm32v2/src/up_enc28j60.c
index 5247f5886..d930d0112 100644
--- a/nuttx/configs/fire-stm32v2/src/up_enc28j60.c
+++ b/nuttx/configs/fire-stm32v2/src/up_enc28j60.c
@@ -157,12 +157,12 @@ static void up_enable(FAR const struct enc_lower_s *lower)
FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)lower;
DEBUGASSERT(priv->handler);
- (void)stm32_gpiosetevent(GPIO_ENC28J60_INTR, true, true, true, priv->handler);
+ (void)stm32_gpiosetevent(GPIO_ENC28J60_INTR, false, true, true, priv->handler);
}
static void up_disable(FAR const struct enc_lower_s *lower)
{
- (void)stm32_gpiosetevent(GPIO_ENC28J60_INTR, true, true, true, NULL);
+ (void)stm32_gpiosetevent(GPIO_ENC28J60_INTR, false, true, true, NULL);
}
/****************************************************************************
diff --git a/nuttx/configs/fire-stm32v2/src/up_mmcsd.c b/nuttx/configs/fire-stm32v2/src/up_mmcsd.c
index c0c6693d3..e06a17e89 100644
--- a/nuttx/configs/fire-stm32v2/src/up_mmcsd.c
+++ b/nuttx/configs/fire-stm32v2/src/up_mmcsd.c
@@ -47,6 +47,7 @@
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
+#include "stm32_sdio.h"
#include "fire-internal.h"
/****************************************************************************
diff --git a/nuttx/configs/fire-stm32v2/src/up_w25.c b/nuttx/configs/fire-stm32v2/src/up_w25.c
new file mode 100644
index 000000000..a3460a158
--- /dev/null
+++ b/nuttx/configs/fire-stm32v2/src/up_w25.c
@@ -0,0 +1,153 @@
+/****************************************************************************
+ * config/fire-stm32v2/src/up_w25.c
+ * arch/arm/src/board/up_w25.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/mount.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <errno.h>
+#include <debug.h>
+
+#ifdef CONFIG_STM32_SPI1
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+# include <nuttx/fs/nxffs.h>
+#endif
+
+#include "fire-internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+/* Can't support the W25 device if it SPI1 or W25 support is not enabled */
+
+#define HAVE_W25 1
+#if !defined(CONFIG_STM32_SPI1) || !defined(CONFIG_MTD_W25)
+# undef HAVE_W25
+#endif
+
+/* Can't support W25 features if mountpoints are disabled */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT)
+# undef HAVE_W25
+#endif
+
+/* Can't support both FAT and NXFFS */
+
+#if defined(CONFIG_FS_FAT) && defined(CONFIG_FS_NXFFS)
+# warning "Can't support both FAT and NXFFS -- using FAT"
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+int stm32_w25initialize(int minor)
+{
+#ifdef HAVE_W25
+ FAR struct spi_dev_s *spi;
+ FAR struct mtd_dev_s *mtd;
+#ifndef CONFIG_FS_NXFFS
+ uint8_t devname[12];
+#endif
+ int ret;
+
+ /* Get the SPI port */
+
+ spi = up_spiinitialize(2);
+ if (!spi)
+ {
+ fdbg("ERROR: Failed to initialize SPI port 2\n");
+ return -ENODEV;
+ }
+
+ /* Now bind the SPI interface to the SST 25 SPI FLASH driver */
+
+ mtd = sst25_initialize(spi);
+ if (!mtd)
+ {
+ fdbg("ERROR: Failed to bind SPI port 2 to the SST 25 FLASH driver\n");
+ return -ENODEV;
+ }
+
+#ifndef CONFIG_FS_NXFFS
+ /* And finally, use the FTL layer to wrap the MTD driver as a block driver */
+
+ ret = ftl_initialize(minor, mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Initialize the FTL layer\n");
+ return ret;
+ }
+#else
+ /* Initialize to provide NXFFS on the MTD interface */
+
+ ret = nxffs_initialize(mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: NXFFS initialization failed: %d\n", -ret);
+ return ret;
+ }
+
+ /* Mount the file system at /mnt/w25 */
+
+ snprintf(devname, 12, "/mnt/w25%c", a + minor);
+ ret = mount(NULL, devname, "nxffs", 0, NULL);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno);
+ return ret;
+ }
+#endif
+#endif
+ return OK;
+}
diff --git a/nuttx/configs/hymini-stm32v/buttons/defconfig b/nuttx/configs/hymini-stm32v/buttons/defconfig
index b03997e42..59b7b111f 100644
--- a/nuttx/configs/hymini-stm32v/buttons/defconfig
+++ b/nuttx/configs/hymini-stm32v/buttons/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=49152
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/hymini-stm32v/nsh/defconfig b/nuttx/configs/hymini-stm32v/nsh/defconfig
index 98849c1b8..1b0944d02 100755
--- a/nuttx/configs/hymini-stm32v/nsh/defconfig
+++ b/nuttx/configs/hymini-stm32v/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=49152
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/hymini-stm32v/nsh2/defconfig b/nuttx/configs/hymini-stm32v/nsh2/defconfig
index 95e7f8b95..fbd9d23b3 100644
--- a/nuttx/configs/hymini-stm32v/nsh2/defconfig
+++ b/nuttx/configs/hymini-stm32v/nsh2/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=49152
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/hymini-stm32v/nx/defconfig b/nuttx/configs/hymini-stm32v/nx/defconfig
index d4f468d32..645feac1b 100644
--- a/nuttx/configs/hymini-stm32v/nx/defconfig
+++ b/nuttx/configs/hymini-stm32v/nx/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=49152
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/hymini-stm32v/nxlines/defconfig b/nuttx/configs/hymini-stm32v/nxlines/defconfig
index 01da0ea84..689b17376 100644
--- a/nuttx/configs/hymini-stm32v/nxlines/defconfig
+++ b/nuttx/configs/hymini-stm32v/nxlines/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=49152
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/hymini-stm32v/usbserial/defconfig b/nuttx/configs/hymini-stm32v/usbserial/defconfig
index 15f0695cf..379e51a5e 100755
--- a/nuttx/configs/hymini-stm32v/usbserial/defconfig
+++ b/nuttx/configs/hymini-stm32v/usbserial/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=49152
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/hymini-stm32v/usbstorage/defconfig b/nuttx/configs/hymini-stm32v/usbstorage/defconfig
index 8e5cc1b53..b56f62754 100755
--- a/nuttx/configs/hymini-stm32v/usbstorage/defconfig
+++ b/nuttx/configs/hymini-stm32v/usbstorage/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=49152
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/kwikstik-k40/ostest/defconfig b/nuttx/configs/kwikstik-k40/ostest/defconfig
index 4d9047339..29bed1244 100755
--- a/nuttx/configs/kwikstik-k40/ostest/defconfig
+++ b/nuttx/configs/kwikstik-k40/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=9535
CONFIG_DRAM_START=0x1fff8000
CONFIG_DRAM_SIZE= 0x00010000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lincoln60/nsh/defconfig b/nuttx/configs/lincoln60/nsh/defconfig
index 035c8f074..a120e2c74 100644
--- a/nuttx/configs/lincoln60/nsh/defconfig
+++ b/nuttx/configs/lincoln60/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lincoln60/ostest/defconfig b/nuttx/configs/lincoln60/ostest/defconfig
index 90f980a13..6c74a9f54 100644
--- a/nuttx/configs/lincoln60/ostest/defconfig
+++ b/nuttx/configs/lincoln60/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lm3s6432-s2e/nsh/defconfig b/nuttx/configs/lm3s6432-s2e/nsh/defconfig
index a5f2466c2..b4dd453ac 100644
--- a/nuttx/configs/lm3s6432-s2e/nsh/defconfig
+++ b/nuttx/configs/lm3s6432-s2e/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lm3s6432-s2e/ostest/defconfig b/nuttx/configs/lm3s6432-s2e/ostest/defconfig
index bc9ce20f0..e04f3da8d 100644
--- a/nuttx/configs/lm3s6432-s2e/ostest/defconfig
+++ b/nuttx/configs/lm3s6432-s2e/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lm3s6965-ek/nsh/defconfig b/nuttx/configs/lm3s6965-ek/nsh/defconfig
index 145c992c9..bfad857f0 100755
--- a/nuttx/configs/lm3s6965-ek/nsh/defconfig
+++ b/nuttx/configs/lm3s6965-ek/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lm3s6965-ek/nx/defconfig b/nuttx/configs/lm3s6965-ek/nx/defconfig
index c6340c76b..4bc7d73a6 100755
--- a/nuttx/configs/lm3s6965-ek/nx/defconfig
+++ b/nuttx/configs/lm3s6965-ek/nx/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lm3s6965-ek/ostest/defconfig b/nuttx/configs/lm3s6965-ek/ostest/defconfig
index 1ef498dd8..8aeef4a00 100755
--- a/nuttx/configs/lm3s6965-ek/ostest/defconfig
+++ b/nuttx/configs/lm3s6965-ek/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lm3s8962-ek/nsh/defconfig b/nuttx/configs/lm3s8962-ek/nsh/defconfig
index 439165c90..8c3d834f5 100755
--- a/nuttx/configs/lm3s8962-ek/nsh/defconfig
+++ b/nuttx/configs/lm3s8962-ek/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lm3s8962-ek/nx/defconfig b/nuttx/configs/lm3s8962-ek/nx/defconfig
index 823d62ae9..49bbe0675 100755
--- a/nuttx/configs/lm3s8962-ek/nx/defconfig
+++ b/nuttx/configs/lm3s8962-ek/nx/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lm3s8962-ek/ostest/defconfig b/nuttx/configs/lm3s8962-ek/ostest/defconfig
index 291f4e1f2..adb806b9c 100755
--- a/nuttx/configs/lm3s8962-ek/ostest/defconfig
+++ b/nuttx/configs/lm3s8962-ek/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
index b0a1f736f..406f6f2ba 100644
--- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig
+++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=73728
CONFIG_DRAM_START=0x10080000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lpc4330-xplorer/ostest/defconfig b/nuttx/configs/lpc4330-xplorer/ostest/defconfig
index 267d46af5..560e3327b 100644
--- a/nuttx/configs/lpc4330-xplorer/ostest/defconfig
+++ b/nuttx/configs/lpc4330-xplorer/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_SIZE=73728
CONFIG_DRAM_START=0x10080000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig
index c2d7fc336..0b7f1c153 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig
+++ b/nuttx/configs/lpcxpresso-lpc1768/dhcpd/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8079
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig
index 425c4134e..cb78f88cc 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig
+++ b/nuttx/configs/lpcxpresso-lpc1768/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8079
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig
index c0289a08f..54c6828a8 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig
+++ b/nuttx/configs/lpcxpresso-lpc1768/nx/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8079
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig
index 0c5104ca7..a808333ff 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig
+++ b/nuttx/configs/lpcxpresso-lpc1768/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8079
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig
index 80ff88e8b..227bbdebd 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig
+++ b/nuttx/configs/lpcxpresso-lpc1768/thttpd/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8079
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig
index 1b1c97f59..4aca6768c 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig
+++ b/nuttx/configs/lpcxpresso-lpc1768/usbstorage/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8079
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/mbed/hidkbd/defconfig b/nuttx/configs/mbed/hidkbd/defconfig
index e65a2fd18..edcf8e181 100644
--- a/nuttx/configs/mbed/hidkbd/defconfig
+++ b/nuttx/configs/mbed/hidkbd/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/mbed/nsh/defconfig b/nuttx/configs/mbed/nsh/defconfig
index a073c8886..c1a35e4b1 100755
--- a/nuttx/configs/mbed/nsh/defconfig
+++ b/nuttx/configs/mbed/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/micropendous3/hello/defconfig b/nuttx/configs/micropendous3/hello/defconfig
index 091e9147e..4563a12e3 100644
--- a/nuttx/configs/micropendous3/hello/defconfig
+++ b/nuttx/configs/micropendous3/hello/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=4096
CONFIG_DRAM_START=0x800100
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
diff --git a/nuttx/configs/mirtoo/nsh/defconfig b/nuttx/configs/mirtoo/nsh/defconfig
index bcc18dc3c..c210c134b 100644
--- a/nuttx/configs/mirtoo/nsh/defconfig
+++ b/nuttx/configs/mirtoo/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/mirtoo/nxffs/defconfig b/nuttx/configs/mirtoo/nxffs/defconfig
index d7454bda6..1dbb2c02c 100644
--- a/nuttx/configs/mirtoo/nxffs/defconfig
+++ b/nuttx/configs/mirtoo/nxffs/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/mirtoo/ostest/defconfig b/nuttx/configs/mirtoo/ostest/defconfig
index fdbc4b561..702b01bc8 100644
--- a/nuttx/configs/mirtoo/ostest/defconfig
+++ b/nuttx/configs/mirtoo/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/mx1ads/ostest/defconfig b/nuttx/configs/mx1ads/ostest/defconfig
index f20216aa8..c699aab51 100644
--- a/nuttx/configs/mx1ads/ostest/defconfig
+++ b/nuttx/configs/mx1ads/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=16777216
CONFIG_DRAM_START=0x08000000
CONFIG_DRAM_VSTART=0x00000000
CONFIG_DRAM_NUTTXENTRY=0x01004000
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
#
diff --git a/nuttx/configs/ne64badge/ostest/defconfig b/nuttx/configs/ne64badge/ostest/defconfig
index 4f480675d..59f52f661 100755
--- a/nuttx/configs/ne64badge/ostest/defconfig
+++ b/nuttx/configs/ne64badge/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/nucleus2g/nsh/defconfig b/nuttx/configs/nucleus2g/nsh/defconfig
index 6dcef15a7..9397820cd 100755
--- a/nuttx/configs/nucleus2g/nsh/defconfig
+++ b/nuttx/configs/nucleus2g/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/nucleus2g/ostest/defconfig b/nuttx/configs/nucleus2g/ostest/defconfig
index 622db2a5f..848fafdba 100755
--- a/nuttx/configs/nucleus2g/ostest/defconfig
+++ b/nuttx/configs/nucleus2g/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/nucleus2g/usbserial/defconfig b/nuttx/configs/nucleus2g/usbserial/defconfig
index 36b1ff47b..d0decf903 100755
--- a/nuttx/configs/nucleus2g/usbserial/defconfig
+++ b/nuttx/configs/nucleus2g/usbserial/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/nucleus2g/usbstorage/defconfig b/nuttx/configs/nucleus2g/usbstorage/defconfig
index 5dfe47457..ec79e8fd3 100755
--- a/nuttx/configs/nucleus2g/usbstorage/defconfig
+++ b/nuttx/configs/nucleus2g/usbstorage/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig
index c34f0b999..3498195b1 100755
--- a/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/ftpc/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
index 10dc25101..9acf60d9d 100755
--- a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
index 6ac19b8e7..040b3ecff 100755
--- a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
index 37e2b9bf0..1324ca5d4 100755
--- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/nx/defconfig b/nuttx/configs/olimex-lpc1766stk/nx/defconfig
index a3a912b2a..de5763c0e 100755
--- a/nuttx/configs/olimex-lpc1766stk/nx/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nx/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
index a01564222..f36f911e6 100755
--- a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
index f2074597c..a30c2b9a6 100755
--- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig
index f69918025..1c287cfca 100755
--- a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
index 506ef91d7..4ead7ffeb 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
index eaf51a8f4..53cf8001c 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
index 4b7b2942d..0df5f2cf7 100755
--- a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
@@ -47,7 +47,7 @@ CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x10000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/olimex-lpc2378/nsh/defconfig b/nuttx/configs/olimex-lpc2378/nsh/defconfig
index 98cd2b5fe..7311d0c20 100755
--- a/nuttx/configs/olimex-lpc2378/nsh/defconfig
+++ b/nuttx/configs/olimex-lpc2378/nsh/defconfig
@@ -52,7 +52,7 @@ CONFIG_BOARD_LOOPSPERMSEC=3270
CONFIG_ARCH_LEDS=y
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x40000000
-CONFIG_ARCH_INTERRUPTSTACK=
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
# Identify toolchain and linker options
diff --git a/nuttx/configs/olimex-lpc2378/ostest/defconfig b/nuttx/configs/olimex-lpc2378/ostest/defconfig
index df6c0e1cb..b96aadd87 100755
--- a/nuttx/configs/olimex-lpc2378/ostest/defconfig
+++ b/nuttx/configs/olimex-lpc2378/ostest/defconfig
@@ -52,7 +52,7 @@ CONFIG_BOARD_LOOPSPERMSEC=3270
CONFIG_ARCH_LEDS=y
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x40000000
-CONFIG_ARCH_INTERRUPTSTACK=
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
# Identify toolchain and linker options
diff --git a/nuttx/configs/olimex-stm32-p107/nsh/defconfig b/nuttx/configs/olimex-stm32-p107/nsh/defconfig
index 91e757cf1..5c38a49ef 100644
--- a/nuttx/configs/olimex-stm32-p107/nsh/defconfig
+++ b/nuttx/configs/olimex-stm32-p107/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=65536
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
diff --git a/nuttx/configs/olimex-stm32-p107/ostest/defconfig b/nuttx/configs/olimex-stm32-p107/ostest/defconfig
index 0a8d66455..3710ee95b 100644
--- a/nuttx/configs/olimex-stm32-p107/ostest/defconfig
+++ b/nuttx/configs/olimex-stm32-p107/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=65536
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
diff --git a/nuttx/configs/olimex-strp711/nettest/defconfig b/nuttx/configs/olimex-strp711/nettest/defconfig
index f69d3f8cb..e8455ab94 100755
--- a/nuttx/configs/olimex-strp711/nettest/defconfig
+++ b/nuttx/configs/olimex-strp711/nettest/defconfig
@@ -223,8 +223,8 @@ CONFIG_NUNGET_CHARS=2
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
CONFIG_MAX_WDOGPARMS=2
-CONFIG_PREALLOC_WDOGS=4
-CONFIG_PREALLOC_TIMERS=4
+CONFIG_PREALLOC_WDOGS=16
+CONFIG_PREALLOC_TIMERS=8
#
# Filesystem configuration
@@ -235,6 +235,7 @@ CONFIG_FS_ROMFS=n
#
# ENC28J60 configuration
#
+CONFIG_NETDEVICES=y
CONFIG_ENC28J60=y
#CONFIG_ENC28J60_SPIMODE
CONFIG_ENC28J60_FREQUENCY=20000000
@@ -252,10 +253,11 @@ CONFIG_MMCSD_READONLY=n
# TCP/IP and UDP support via uIP
#
CONFIG_NET=y
+CONFIG_NET_NOINTS=y
CONFIG_NET_IPv6=n
-CONFIG_NSOCKET_DESCRIPTORS=8
+CONFIG_NSOCKET_DESCRIPTORS=16
CONFIG_NET_SOCKOPTS=y
-CONFIG_NET_BUFSIZE=420
+CONFIG_NET_BUFSIZE=562
CONFIG_NET_TCP=y
CONFIG_NET_TCP_CONNS=8
CONFIG_NET_NTCP_READAHEAD_BUFFERS=8
@@ -365,7 +367,7 @@ CONFIG_NSH_TELNET=n
CONFIG_NSH_ARCHINIT=n
CONFIG_NSH_IOBUFFER_SIZE=512
CONFIG_NSH_DHCPC=n
-CONFIG_NSH_NOMAC=n
+CONFIG_NSH_NOMAC=y
CONFIG_NSH_IPADDR=0x0a000002
CONFIG_NSH_DRIPADDR=0x0a000001
CONFIG_NSH_NETMASK=0xffffff00
diff --git a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig
index 74242863f..09febe7b1 100644
--- a/nuttx/configs/pcblogic-pic32mx/nsh/defconfig
+++ b/nuttx/configs/pcblogic-pic32mx/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
diff --git a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig
index d012b4a24..dc76a54bb 100644
--- a/nuttx/configs/pcblogic-pic32mx/ostest/defconfig
+++ b/nuttx/configs/pcblogic-pic32mx/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
diff --git a/nuttx/configs/pic32-starterkit/nsh/defconfig b/nuttx/configs/pic32-starterkit/nsh/defconfig
index 2f0248f41..5c19d2e43 100644
--- a/nuttx/configs/pic32-starterkit/nsh/defconfig
+++ b/nuttx/configs/pic32-starterkit/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/pic32-starterkit/nsh2/defconfig b/nuttx/configs/pic32-starterkit/nsh2/defconfig
index be8ef53a0..8d9bd8e27 100644
--- a/nuttx/configs/pic32-starterkit/nsh2/defconfig
+++ b/nuttx/configs/pic32-starterkit/nsh2/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/pic32-starterkit/ostest/defconfig b/nuttx/configs/pic32-starterkit/ostest/defconfig
index bcd26cce5..687b63970 100644
--- a/nuttx/configs/pic32-starterkit/ostest/defconfig
+++ b/nuttx/configs/pic32-starterkit/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/pic32mx7mmb/nsh/defconfig b/nuttx/configs/pic32mx7mmb/nsh/defconfig
index 53ad041da..bb9531694 100644
--- a/nuttx/configs/pic32mx7mmb/nsh/defconfig
+++ b/nuttx/configs/pic32mx7mmb/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/pic32mx7mmb/ostest/defconfig b/nuttx/configs/pic32mx7mmb/ostest/defconfig
index ac6b9a82d..a14fa9948 100644
--- a/nuttx/configs/pic32mx7mmb/ostest/defconfig
+++ b/nuttx/configs/pic32mx7mmb/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/sam3u-ek/knsh/defconfig b/nuttx/configs/sam3u-ek/knsh/defconfig
index 06b93cc13..82616f338 100755
--- a/nuttx/configs/sam3u-ek/knsh/defconfig
+++ b/nuttx/configs/sam3u-ek/knsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4768
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/sam3u-ek/nsh/defconfig b/nuttx/configs/sam3u-ek/nsh/defconfig
index a336861f5..56071d223 100755
--- a/nuttx/configs/sam3u-ek/nsh/defconfig
+++ b/nuttx/configs/sam3u-ek/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4768
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/sam3u-ek/nx/defconfig b/nuttx/configs/sam3u-ek/nx/defconfig
index 5bf51a0fb..943c47cfc 100755
--- a/nuttx/configs/sam3u-ek/nx/defconfig
+++ b/nuttx/configs/sam3u-ek/nx/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4768
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/sam3u-ek/ostest/defconfig b/nuttx/configs/sam3u-ek/ostest/defconfig
index 2757531f0..098fc3600 100755
--- a/nuttx/configs/sam3u-ek/ostest/defconfig
+++ b/nuttx/configs/sam3u-ek/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4768
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/sam3u-ek/touchscreen/defconfig b/nuttx/configs/sam3u-ek/touchscreen/defconfig
index e70b710ac..2165dec4b 100755
--- a/nuttx/configs/sam3u-ek/touchscreen/defconfig
+++ b/nuttx/configs/sam3u-ek/touchscreen/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=4768
CONFIG_DRAM_SIZE=32768
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile
index 11e36f136..50ddaa5ca 100644
--- a/nuttx/configs/shenzhou/src/Makefile
+++ b/nuttx/configs/shenzhou/src/Makefile
@@ -68,6 +68,10 @@ ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
+ifeq ($(CONFIG_MTD_W25),y)
+CSRCS += up_w25.c
+endif
+
ifeq ($(CONFIG_USBMSC),y)
CSRCS += up_usbmsc.c
endif
diff --git a/nuttx/configs/shenzhou/src/shenzhou-internal.h b/nuttx/configs/shenzhou/src/shenzhou-internal.h
index 6f9683a56..19460bc99 100644
--- a/nuttx/configs/shenzhou/src/shenzhou-internal.h
+++ b/nuttx/configs/shenzhou/src/shenzhou-internal.h
@@ -270,5 +270,17 @@ int stm32_usbhost_initialize(void);
int stm32_sdinitialize(int minor);
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MTD_W25
+int stm32_w25initialize(int minor);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_SHENZHOUL_SRC_SHENZHOU_INTERNAL_H */
diff --git a/nuttx/configs/shenzhou/src/up_w25.c b/nuttx/configs/shenzhou/src/up_w25.c
new file mode 100644
index 000000000..aa547f6fe
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_w25.c
@@ -0,0 +1,153 @@
+/****************************************************************************
+ * config/shenzhou/src/up_w25.c
+ * arch/arm/src/board/up_w25.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/mount.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <errno.h>
+#include <debug.h>
+
+#ifdef CONFIG_STM32_SPI1
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+# include <nuttx/fs/nxffs.h>
+#endif
+
+#include "shenzhou-internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+/* Can't support the W25 device if it SPI1 or W25 support is not enabled */
+
+#define HAVE_W25 1
+#if !defined(CONFIG_STM32_SPI1) || !defined(CONFIG_MTD_W25)
+# undef HAVE_W25
+#endif
+
+/* Can't support W25 features if mountpoints are disabled */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT)
+# undef HAVE_W25
+#endif
+
+/* Can't support both FAT and NXFFS */
+
+#if defined(CONFIG_FS_FAT) && defined(CONFIG_FS_NXFFS)
+# warning "Can't support both FAT and NXFFS -- using FAT"
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+int stm32_w25initialize(int minor)
+{
+#ifdef HAVE_W25
+ FAR struct spi_dev_s *spi;
+ FAR struct mtd_dev_s *mtd;
+#ifndef CONFIG_FS_NXFFS
+ uint8_t devname[12];
+#endif
+ int ret;
+
+ /* Get the SPI port */
+
+ spi = up_spiinitialize(2);
+ if (!spi)
+ {
+ fdbg("ERROR: Failed to initialize SPI port 2\n");
+ return -ENODEV;
+ }
+
+ /* Now bind the SPI interface to the SST 25 SPI FLASH driver */
+
+ mtd = sst25_initialize(spi);
+ if (!mtd)
+ {
+ fdbg("ERROR: Failed to bind SPI port 2 to the SST 25 FLASH driver\n");
+ return -ENODEV;
+ }
+
+#ifndef CONFIG_FS_NXFFS
+ /* And finally, use the FTL layer to wrap the MTD driver as a block driver */
+
+ ret = ftl_initialize(minor, mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Initialize the FTL layer\n");
+ return ret;
+ }
+#else
+ /* Initialize to provide NXFFS on the MTD interface */
+
+ ret = nxffs_initialize(mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: NXFFS initialization failed: %d\n", -ret);
+ return ret;
+ }
+
+ /* Mount the file system at /mnt/w25 */
+
+ snprintf(devname, 12, "/mnt/w25%c", a + minor);
+ ret = mount(NULL, devname, "nxffs", 0, NULL);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno);
+ return ret;
+ }
+#endif
+#endif
+ return OK;
+}
diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig
index dd0a89ecc..a5b60fe4e 100755
--- a/nuttx/configs/stm3210e-eval/RIDE/defconfig
+++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/buttons/defconfig b/nuttx/configs/stm3210e-eval/buttons/defconfig
index b355f4067..fbfac0dc6 100644
--- a/nuttx/configs/stm3210e-eval/buttons/defconfig
+++ b/nuttx/configs/stm3210e-eval/buttons/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/composite/defconfig b/nuttx/configs/stm3210e-eval/composite/defconfig
index 2a76e5caf..84ed18494 100755
--- a/nuttx/configs/stm3210e-eval/composite/defconfig
+++ b/nuttx/configs/stm3210e-eval/composite/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig
index 886b2aa07..27d26ff73 100755
--- a/nuttx/configs/stm3210e-eval/nsh/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig
index 3c0fb3d70..d4fa891fb 100644
--- a/nuttx/configs/stm3210e-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/nx/defconfig b/nuttx/configs/stm3210e-eval/nx/defconfig
index 79a3fe7f9..cab297583 100644
--- a/nuttx/configs/stm3210e-eval/nx/defconfig
+++ b/nuttx/configs/stm3210e-eval/nx/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/nxconsole/defconfig b/nuttx/configs/stm3210e-eval/nxconsole/defconfig
index 243e4ad08..35ba0dcc1 100644
--- a/nuttx/configs/stm3210e-eval/nxconsole/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxconsole/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/nxlines/defconfig b/nuttx/configs/stm3210e-eval/nxlines/defconfig
index bd2968e67..b81f4127c 100644
--- a/nuttx/configs/stm3210e-eval/nxlines/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxlines/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/nxtext/defconfig b/nuttx/configs/stm3210e-eval/nxtext/defconfig
index 5d4b1f061..22dd209a9 100644
--- a/nuttx/configs/stm3210e-eval/nxtext/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxtext/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig
index cabd5fa27..7a2e5b528 100755
--- a/nuttx/configs/stm3210e-eval/ostest/defconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/pm/defconfig b/nuttx/configs/stm3210e-eval/pm/defconfig
index 73f7ae52a..6ca7cda87 100644
--- a/nuttx/configs/stm3210e-eval/pm/defconfig
+++ b/nuttx/configs/stm3210e-eval/pm/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig
index b3d182bde..99a5e2572 100755
--- a/nuttx/configs/stm3210e-eval/usbserial/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3210e-eval/usbstorage/defconfig b/nuttx/configs/stm3210e-eval/usbstorage/defconfig
index 3a2a2d571..812226ee6 100755
--- a/nuttx/configs/stm3210e-eval/usbstorage/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbstorage/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3220g-eval/dhcpd/defconfig b/nuttx/configs/stm3220g-eval/dhcpd/defconfig
index 3abf0bdab..3958aa801 100644
--- a/nuttx/configs/stm3220g-eval/dhcpd/defconfig
+++ b/nuttx/configs/stm3220g-eval/dhcpd/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=10926
CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3220g-eval/nettest/defconfig b/nuttx/configs/stm3220g-eval/nettest/defconfig
index 47a560f4f..0b19651cd 100644
--- a/nuttx/configs/stm3220g-eval/nettest/defconfig
+++ b/nuttx/configs/stm3220g-eval/nettest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=10926
CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3220g-eval/nsh/defconfig b/nuttx/configs/stm3220g-eval/nsh/defconfig
index 6e019875d..c2cf20a5c 100644
--- a/nuttx/configs/stm3220g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3220g-eval/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=10926
CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3220g-eval/nsh2/defconfig b/nuttx/configs/stm3220g-eval/nsh2/defconfig
index 980fc1930..de7e59bca 100644
--- a/nuttx/configs/stm3220g-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3220g-eval/nsh2/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=10926
CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3220g-eval/nxwm/defconfig b/nuttx/configs/stm3220g-eval/nxwm/defconfig
index 4ce770bf1..0182a15d6 100644
--- a/nuttx/configs/stm3220g-eval/nxwm/defconfig
+++ b/nuttx/configs/stm3220g-eval/nxwm/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=10926
CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3220g-eval/ostest/defconfig b/nuttx/configs/stm3220g-eval/ostest/defconfig
index b2d36c9cd..46e82d6e1 100644
--- a/nuttx/configs/stm3220g-eval/ostest/defconfig
+++ b/nuttx/configs/stm3220g-eval/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=10926
CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3220g-eval/telnetd/defconfig b/nuttx/configs/stm3220g-eval/telnetd/defconfig
index 024b4d1a5..823f455c1 100644
--- a/nuttx/configs/stm3220g-eval/telnetd/defconfig
+++ b/nuttx/configs/stm3220g-eval/telnetd/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=10926
CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/dhcpd/defconfig b/nuttx/configs/stm3240g-eval/dhcpd/defconfig
index 83678b12a..09bab66b9 100644
--- a/nuttx/configs/stm3240g-eval/dhcpd/defconfig
+++ b/nuttx/configs/stm3240g-eval/dhcpd/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/nettest/defconfig b/nuttx/configs/stm3240g-eval/nettest/defconfig
index 3446e8c35..2560310da 100644
--- a/nuttx/configs/stm3240g-eval/nettest/defconfig
+++ b/nuttx/configs/stm3240g-eval/nettest/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig
index 03f4d3c0f..dad3b3854 100644
--- a/nuttx/configs/stm3240g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/nsh2/defconfig b/nuttx/configs/stm3240g-eval/nsh2/defconfig
index d0e628cc4..86504cc83 100644
--- a/nuttx/configs/stm3240g-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh2/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/nxconsole/defconfig b/nuttx/configs/stm3240g-eval/nxconsole/defconfig
index dc3ba7ced..70f7465b0 100644
--- a/nuttx/configs/stm3240g-eval/nxconsole/defconfig
+++ b/nuttx/configs/stm3240g-eval/nxconsole/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/nxwm/defconfig b/nuttx/configs/stm3240g-eval/nxwm/defconfig
index 2ace5113d..ec98c273b 100644
--- a/nuttx/configs/stm3240g-eval/nxwm/defconfig
+++ b/nuttx/configs/stm3240g-eval/nxwm/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/ostest/defconfig b/nuttx/configs/stm3240g-eval/ostest/defconfig
index 449a143a5..33bb63d5d 100644
--- a/nuttx/configs/stm3240g-eval/ostest/defconfig
+++ b/nuttx/configs/stm3240g-eval/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/telnetd/defconfig b/nuttx/configs/stm3240g-eval/telnetd/defconfig
index 67762012c..5609f0d18 100644
--- a/nuttx/configs/stm3240g-eval/telnetd/defconfig
+++ b/nuttx/configs/stm3240g-eval/telnetd/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm3240g-eval/webserver/defconfig b/nuttx/configs/stm3240g-eval/webserver/defconfig
index 07d8cfa7b..0bde916e4 100644
--- a/nuttx/configs/stm3240g-eval/webserver/defconfig
+++ b/nuttx/configs/stm3240g-eval/webserver/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm32f4discovery/nsh/defconfig b/nuttx/configs/stm32f4discovery/nsh/defconfig
index 8e1861d73..a5c503591 100644
--- a/nuttx/configs/stm32f4discovery/nsh/defconfig
+++ b/nuttx/configs/stm32f4discovery/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm32f4discovery/nxlines/defconfig b/nuttx/configs/stm32f4discovery/nxlines/defconfig
index 45d819e8a..c6bd3f5df 100644
--- a/nuttx/configs/stm32f4discovery/nxlines/defconfig
+++ b/nuttx/configs/stm32f4discovery/nxlines/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig
index 5640cebd1..39675a166 100644
--- a/nuttx/configs/stm32f4discovery/ostest/defconfig
+++ b/nuttx/configs/stm32f4discovery/ostest/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/stm32f4discovery/pm/defconfig b/nuttx/configs/stm32f4discovery/pm/defconfig
index fb03c477e..8960253f9 100644
--- a/nuttx/configs/stm32f4discovery/pm/defconfig
+++ b/nuttx/configs/stm32f4discovery/pm/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=196608
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
diff --git a/nuttx/configs/sure-pic32mx/nsh/defconfig b/nuttx/configs/sure-pic32mx/nsh/defconfig
index ded591f3e..ffd95e4ac 100644
--- a/nuttx/configs/sure-pic32mx/nsh/defconfig
+++ b/nuttx/configs/sure-pic32mx/nsh/defconfig
@@ -50,7 +50,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/sure-pic32mx/ostest/defconfig b/nuttx/configs/sure-pic32mx/ostest/defconfig
index d6e3f894f..731529df8 100644
--- a/nuttx/configs/sure-pic32mx/ostest/defconfig
+++ b/nuttx/configs/sure-pic32mx/ostest/defconfig
@@ -50,7 +50,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/sure-pic32mx/usbnsh/defconfig b/nuttx/configs/sure-pic32mx/usbnsh/defconfig
index e1873b4c7..0abcd72b8 100644
--- a/nuttx/configs/sure-pic32mx/usbnsh/defconfig
+++ b/nuttx/configs/sure-pic32mx/usbnsh/defconfig
@@ -50,7 +50,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/teensy/hello/defconfig b/nuttx/configs/teensy/hello/defconfig
index 29c7194e3..dee8b264e 100644
--- a/nuttx/configs/teensy/hello/defconfig
+++ b/nuttx/configs/teensy/hello/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=8192
CONFIG_DRAM_START=0x800100
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/teensy/nsh/defconfig b/nuttx/configs/teensy/nsh/defconfig
index 4f13b9351..32b7e5a41 100755
--- a/nuttx/configs/teensy/nsh/defconfig
+++ b/nuttx/configs/teensy/nsh/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=8192
CONFIG_DRAM_START=0x800100
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/teensy/usbstorage/defconfig b/nuttx/configs/teensy/usbstorage/defconfig
index a0f906665..68d54b870 100755
--- a/nuttx/configs/teensy/usbstorage/defconfig
+++ b/nuttx/configs/teensy/usbstorage/defconfig
@@ -47,7 +47,7 @@ CONFIG_DRAM_SIZE=8192
CONFIG_DRAM_START=0x800100
CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/twr-k60n512/nsh/defconfig b/nuttx/configs/twr-k60n512/nsh/defconfig
index 0f91b6721..47aecfea6 100644
--- a/nuttx/configs/twr-k60n512/nsh/defconfig
+++ b/nuttx/configs/twr-k60n512/nsh/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=9535
CONFIG_DRAM_START=0x1fff0000
CONFIG_DRAM_SIZE=131072
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/twr-k60n512/ostest/defconfig b/nuttx/configs/twr-k60n512/ostest/defconfig
index 461b795f1..984ff5cff 100644
--- a/nuttx/configs/twr-k60n512/ostest/defconfig
+++ b/nuttx/configs/twr-k60n512/ostest/defconfig
@@ -46,7 +46,7 @@ CONFIG_BOARD_LOOPSPERMSEC=9535
CONFIG_DRAM_START=0x1fff0000
CONFIG_DRAM_SIZE=131072
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ubw32/nsh/defconfig b/nuttx/configs/ubw32/nsh/defconfig
index 174d7c9a8..cfc0dad30 100644
--- a/nuttx/configs/ubw32/nsh/defconfig
+++ b/nuttx/configs/ubw32/nsh/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/ubw32/ostest/defconfig b/nuttx/configs/ubw32/ostest/defconfig
index 2a51efc25..0fc2984bc 100644
--- a/nuttx/configs/ubw32/ostest/defconfig
+++ b/nuttx/configs/ubw32/ostest/defconfig
@@ -48,7 +48,7 @@ CONFIG_DRAM_START=0xa0000000
CONFIG_ARCH_NOINTC=n
CONFIG_ARCH_VECNOTIRQ=y
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig
index 48af2e07c..c55fae0f3 100755
--- a/nuttx/configs/vsn/nsh/defconfig
+++ b/nuttx/configs/vsn/nsh/defconfig
@@ -49,7 +49,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=65536
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
-CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index 294566d01..32d127aa4 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -119,6 +119,14 @@ config I2C_NTRACE
default n
depends on I2C_TRACE
+config ARCH_HAVE_I2CRESET
+ bool
+
+config I2C_RESET
+ bool "Support up_i2creset"
+ default n
+ depends on I2C && ARCH_HAVE_I2CRESET
+
menuconfig SPI
bool "SPI Driver Support"
default n
diff --git a/nuttx/drivers/mtd/Kconfig b/nuttx/drivers/mtd/Kconfig
index bda5afa84..ae656c474 100644
--- a/nuttx/drivers/mtd/Kconfig
+++ b/nuttx/drivers/mtd/Kconfig
@@ -36,19 +36,19 @@ config AT45DB_PWRSAVE
bool "enables power save"
default n
depends on MTD_AT45DB
-
+
config MTD_MP25P
- bool "SPI-based M25P1 falsh"
+ bool "SPI-based M25P FLASH"
default n
select SPI
config MP25P_SPIMODE
- int "mp25p spi mode"
+ int "MP25P SPI mode"
default 0
depends on MTD_MP25P
config MP25P_MANUFACTURER
- hex "mp25p manufacturers ID"
+ hex "MP25P manufacturers ID"
default 0x20
depends on MTD_MP25P
---help---
@@ -66,3 +66,68 @@ config MTD_RAMTRON
config MTD_RAM
bool "Memory bus ram"
default n
+
+config MTD_SST25
+ bool "SPI-based SST25 FLASH"
+ default n
+ select SPI
+
+config SST25_SPIMODE
+ int "SST25 SPI Mode"
+ default 0
+ depends on MTD_SST25
+
+config SST25_SPIFREQUENCY
+ int "SST25 SPI Frequency"
+ default 20000000
+ depends on MTD_SST25
+
+config SST25_READONLY
+ bool "SST25 Read-Only FLASH"
+ default n
+ depends on MTD_SST25
+
+config SST25_SECTOR512
+ bool "Simulate 512 byte Erase Blocks"
+ default n
+ depends on MTD_SST25
+
+config SST25_SLOWWRITE
+ bool
+ default y
+ depends on MTD_SST25
+
+config SST25_SLOWREAD
+ bool
+ default n
+ depends on MTD_SST25
+
+config MTD_W25
+ bool "SPI-based W25 FLASH"
+ default n
+ select SPI
+
+config W25_SPIMODE
+ int "W25 SPI Mode"
+ default 0
+ depends on MTD_W25
+
+config W25_SPIFREQUENCY
+ int "W25 SPI Frequency"
+ default 20000000
+ depends on MTD_W25
+
+config W25_READONLY
+ bool "W25 Read-Only FLASH"
+ default n
+ depends on MTD_W25
+
+config W25_SECTOR512
+ bool "Simulate 512 byte Erase Blocks"
+ default n
+ depends on MTD_W25
+
+config W25_SLOWREAD
+ bool
+ default n
+ depends on MTD_W25
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index 866d7c713..258e77ec9 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -47,6 +47,10 @@ ifeq ($(CONFIG_MTD_SST25),y)
CSRCS += sst25.c
endif
+ifeq ($(CONFIG_MTD_W25),y)
+CSRCS += w25.c
+endif
+
# Include MTD driver support
DEPPATH += --dep-path mtd
diff --git a/nuttx/drivers/mtd/sst25.c b/nuttx/drivers/mtd/sst25.c
index 01838f078..66d201add 100644
--- a/nuttx/drivers/mtd/sst25.c
+++ b/nuttx/drivers/mtd/sst25.c
@@ -1,5 +1,5 @@
/************************************************************************************
- * drivers/mtd/m25px.c
+ * drivers/mtd/sst25.c
* Driver for SPI-based SST25 FLASH.
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
diff --git a/nuttx/drivers/mtd/w25.c b/nuttx/drivers/mtd/w25.c
new file mode 100644
index 000000000..0d7028fec
--- /dev/null
+++ b/nuttx/drivers/mtd/w25.c
@@ -0,0 +1,1188 @@
+/************************************************************************************
+ * drivers/mtd/w25.c
+ * Driver for SPI-based W25x16, x32, and x64 and W25q16, q32, q64, and q128 FLASH
+ *
+ * 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 <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/fs/ioctl.h>
+#include <nuttx/spi.h>
+#include <nuttx/mtd.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+/* Per the data sheet, the W25 parts can be driven with either SPI mode 0 (CPOL=0
+ * and CPHA=0) or mode 3 (CPOL=1 and CPHA=1). But I have heard that other devices
+ * can operate in mode 0 or 1. So you may need to specify CONFIG_W25_SPIMODE to
+ * select the best mode for your device. If CONFIG_W25_SPIMODE is not defined,
+ * mode 0 will be used.
+ */
+
+#ifndef CONFIG_W25_SPIMODE
+# define CONFIG_W25_SPIMODE SPIDEV_MODE0
+#endif
+
+/* SPI Frequency. May be up to 25MHz. */
+
+#ifndef CONFIG_W25_SPIFREQUENCY
+# define CONFIG_W25_SPIFREQUENCY 20000000
+#endif
+
+/* W25 Instructions *****************************************************************/
+/* Command Value Description */
+/* */
+#define W25_WREN 0x06 /* Write enable */
+#define W25_WRDI 0x04 /* Write Disable */
+#define W25_RDSR 0x05 /* Read status register */
+#define W25_WRSR 0x01 /* Write Status Register */
+#define W25_RDDATA 0x03 /* Read data bytes */
+#define W25_FRD 0x0b /* Higher speed read */
+#define W25_FRDD 0x3b /* Fast read, dual output */
+#define W25_PP 0x02 /* Program page */
+#define W25_BE 0xd8 /* Block Erase (64KB) */
+#define W25_SE 0x20 /* Sector erase (4KB) */
+#define W25_CE 0xc7 /* Chip erase */
+#define W25_PD 0xb9 /* Power down */
+#define W25_PURDID 0xab /* Release PD, Device ID */
+#define W25_RDMFID 0x90 /* Read Manufacturer / Device */
+#define W25_JEDEC_ID 0x9f /* JEDEC ID read */
+
+/* W25 Registers ********************************************************************/
+/* Read ID (RDID) register values */
+
+#define W25_MANUFACTURER 0xef /* Winbond Serial Flash */
+#define W25X16_DEVID 0x14 /* W25X16 device ID (0xab, 0x90) */
+#define W25X32_DEVID 0x15 /* W25X16 device ID (0xab, 0x90) */
+#define W25X64_DEVID 0x16 /* W25X16 device ID (0xab, 0x90) */
+
+/* JEDEC Read ID register values */
+
+#define W25_JEDEC_MANUFACTURER 0xef /* SST manufacturer ID */
+#define W25X_JEDEC_MEMORY_TYPE 0x30 /* W25X memory type */
+#define W25Q_JEDEC_MEMORY_TYPE_A 0x40 /* W25Q memory type */
+#define W25Q_JEDEC_MEMORY_TYPE_B 0x60 /* W25Q memory type */
+
+#define W25_JEDEC_CAPACITY_16MBIT 0x15 /* 512x4096 = 16Mbit memory capacity */
+#define W25_JEDEC_CAPACITY_32MBIT 0x16 /* 1024x4096 = 32Mbit memory capacity */
+#define W25_JEDEC_CAPACITY_64MBIT 0x17 /* 2048x4096 = 64Mbit memory capacity */
+#define W25_JEDEC_CAPACITY_128MBIT 0x18 /* 4096x4096 = 128Mbit memory capacity */
+
+#define NSECTORS_16MBIT 512 /* 512 sectors x 4096 bytes/sector = 2Mb */
+#define NSECTORS_32MBIT 1024 /* 1024 sectors x 4096 bytes/sector = 4Mb */
+#define NSECTORS_64MBIT 2048 /* 2048 sectors x 4096 bytes/sector = 8Mb */
+#define NSECTORS_128MBIT 4096 /* 4096 sectors x 4096 bytes/sector = 16Mb */
+
+/* Status register bit definitions */
+
+#define W25_SR_BUSY (1 << 0) /* Bit 0: Write in progress */
+#define W25_SR_WEL (1 << 1) /* Bit 1: Write enable latch bit */
+#define W25_SR_BP_SHIFT (2) /* Bits 2-5: Block protect bits */
+#define W25_SR_BP_MASK (15 << W25_SR_BP_SHIFT)
+# define W25X16_SR_BP_NONE (0 << W25_SR_BP_SHIFT) /* Unprotected */
+# define W25X16_SR_BP_UPPER32nd (1 << W25_SR_BP_SHIFT) /* Upper 32nd */
+# define W25X16_SR_BP_UPPER16th (2 << W25_SR_BP_SHIFT) /* Upper 16th */
+# define W25X16_SR_BP_UPPER8th (3 << W25_SR_BP_SHIFT) /* Upper 8th */
+# define W25X16_SR_BP_UPPERQTR (4 << W25_SR_BP_SHIFT) /* Upper quarter */
+# define W25X16_SR_BP_UPPERHALF (5 << W25_SR_BP_SHIFT) /* Upper half */
+# define W25X16_SR_BP_ALL (6 << W25_SR_BP_SHIFT) /* All sectors */
+# define W25X16_SR_BP_LOWER32nd (9 << W25_SR_BP_SHIFT) /* Lower 32nd */
+# define W25X16_SR_BP_LOWER16th (10 << W25_SR_BP_SHIFT) /* Lower 16th */
+# define W25X16_SR_BP_LOWER8th (11 << W25_SR_BP_SHIFT) /* Lower 8th */
+# define W25X16_SR_BP_LOWERQTR (12 << W25_SR_BP_SHIFT) /* Lower quarter */
+# define W25X16_SR_BP_LOWERHALF (13 << W25_SR_BP_SHIFT) /* Lower half */
+
+# define W25X32_SR_BP_NONE (0 << W25_SR_BP_SHIFT) /* Unprotected */
+# define W25X32_SR_BP_UPPER64th (1 << W25_SR_BP_SHIFT) /* Upper 64th */
+# define W25X32_SR_BP_UPPER32nd (2 << W25_SR_BP_SHIFT) /* Upper 32nd */
+# define W25X32_SR_BP_UPPER16th (3 << W25_SR_BP_SHIFT) /* Upper 16th */
+# define W25X32_SR_BP_UPPER8th (4 << W25_SR_BP_SHIFT) /* Upper 8th */
+# define W25X32_SR_BP_UPPERQTR (5 << W25_SR_BP_SHIFT) /* Upper quarter */
+# define W25X32_SR_BP_UPPERHALF (6 << W25_SR_BP_SHIFT) /* Upper half */
+# define W25X32_SR_BP_ALL (7 << W25_SR_BP_SHIFT) /* All sectors */
+# define W25X32_SR_BP_LOWER64th (9 << W25_SR_BP_SHIFT) /* Lower 64th */
+# define W25X32_SR_BP_LOWER32nd (10 << W25_SR_BP_SHIFT) /* Lower 32nd */
+# define W25X32_SR_BP_LOWER16th (11 << W25_SR_BP_SHIFT) /* Lower 16th */
+# define W25X32_SR_BP_LOWER8th (12 << W25_SR_BP_SHIFT) /* Lower 8th */
+# define W25X32_SR_BP_LOWERQTR (13 << W25_SR_BP_SHIFT) /* Lower quarter */
+# define W25X32_SR_BP_LOWERHALF (14 << W25_SR_BP_SHIFT) /* Lower half */
+
+# define W25X64_SR_BP_NONE (0 << W25_SR_BP_SHIFT) /* Unprotected */
+# define W25X64_SR_BP_UPPER64th (1 << W25_SR_BP_SHIFT) /* Upper 64th */
+# define W25X64_SR_BP_UPPER32nd (2 << W25_SR_BP_SHIFT) /* Upper 32nd */
+# define W25X64_SR_BP_UPPER16th (3 << W25_SR_BP_SHIFT) /* Upper 16th */
+# define W25X64_SR_BP_UPPER8th (4 << W25_SR_BP_SHIFT) /* Upper 8th */
+# define W25X64_SR_BP_UPPERQTR (5 << W25_SR_BP_SHIFT) /* Upper quarter */
+# define W25X64_SR_BP_UPPERHALF (6 << W25_SR_BP_SHIFT) /* Upper half */
+# define W25X46_SR_BP_ALL (7 << W25_SR_BP_SHIFT) /* All sectors */
+# define W25X64_SR_BP_LOWER64th (9 << W25_SR_BP_SHIFT) /* Lower 64th */
+# define W25X64_SR_BP_LOWER32nd (10 << W25_SR_BP_SHIFT) /* Lower 32nd */
+# define W25X64_SR_BP_LOWER16th (11 << W25_SR_BP_SHIFT) /* Lower 16th */
+# define W25X64_SR_BP_LOWER8th (12 << W25_SR_BP_SHIFT) /* Lower 8th */
+# define W25X64_SR_BP_LOWERQTR (13 << W25_SR_BP_SHIFT) /* Lower quarter */
+# define W25X64_SR_BP_LOWERHALF (14 << W25_SR_BP_SHIFT) /* Lower half */
+ /* Bit 6: Reserved */
+#define W25_SR_SRP (1 << 7) /* Bit 7: Status register write protect */
+
+#define W25_DUMMY 0xa5
+
+/* Chip Geometries ******************************************************************/
+/* All members of the family support uniform 4K-byte sectors and 256 byte pages */
+
+#define W25_SECTOR_SHIFT 12 /* Sector size 1 << 12 = 4Kb */
+#define W25_SECTOR_SIZE (1 << 12) /* Sector size 1 << 12 = 4Kb */
+#define W25_PAGE_SHIFT 8 /* Sector size 1 << 8 = 256b */
+#define W25_PAGE_SIZE (1 << 8) /* Sector size 1 << 8 = 256b */
+
+#ifdef CONFIG_W25_SECTOR512 /* Simulate a 512 byte sector */
+# define W25_SECTOR512_SHIFT 9 /* Sector size 1 << 9 = 512 bytes */
+# define W25_SECTOR512_SIZE (1 << 9) /* Sector size 1 << 9 = 512 bytes */
+#endif
+
+#define W25_ERASED_STATE 0xff /* State of FLASH when erased */
+
+/* Cache flags */
+
+#define W25_CACHE_VALID (1 << 0) /* 1=Cache has valid data */
+#define W25_CACHE_DIRTY (1 << 1) /* 1=Cache is dirty */
+#define W25_CACHE_ERASED (1 << 2) /* 1=Backing FLASH is erased */
+
+#define IS_VALID(p) ((((p)->flags) & W25_CACHE_VALID) != 0)
+#define IS_DIRTY(p) ((((p)->flags) & W25_CACHE_DIRTY) != 0)
+#define IS_ERASED(p) ((((p)->flags) & W25_CACHE_DIRTY) != 0)
+
+#define SET_VALID(p) do { (p)->flags |= W25_CACHE_VALID; } while (0)
+#define SET_DIRTY(p) do { (p)->flags |= W25_CACHE_DIRTY; } while (0)
+#define SET_ERASED(p) do { (p)->flags |= W25_CACHE_DIRTY; } while (0)
+
+#define CLR_VALID(p) do { (p)->flags &= ~W25_CACHE_VALID; } while (0)
+#define CLR_DIRTY(p) do { (p)->flags &= ~W25_CACHE_DIRTY; } while (0)
+#define CLR_ERASED(p) do { (p)->flags &= ~W25_CACHE_DIRTY; } while (0)
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+
+/* This type represents the state of the MTD device. The struct mtd_dev_s must
+ * appear at the beginning of the definition so that you can freely cast between
+ * pointers to struct mtd_dev_s and struct w25_dev_s.
+ */
+
+struct w25_dev_s
+{
+ struct mtd_dev_s mtd; /* MTD interface */
+ FAR struct spi_dev_s *spi; /* Saved SPI interface instance */
+ uint16_t nsectors; /* Number of erase sectors */
+
+#if defined(CONFIG_W25_SECTOR512) && !defined(CONFIG_W25_READONLY)
+ uint8_t flags; /* Buffered sector flags */
+ uint16_t esectno; /* Erase sector number in the cache*/
+ FAR uint8_t *sector; /* Allocated sector data */
+#endif
+};
+
+/************************************************************************************
+ * Private Function Prototypes
+ ************************************************************************************/
+
+/* Helpers */
+
+static void w25_lock(FAR struct spi_dev_s *spi);
+static inline void w25_unlock(FAR struct spi_dev_s *spi);
+static inline int w25_readid(FAR struct w25_dev_s *priv);
+#ifndef CONFIG_W25_READONLY
+static void w25_unprotect(FAR struct w25_dev_s *priv);
+#endif
+static uint8_t w25_waitwritecomplete(FAR struct w25_dev_s *priv);
+static inline void w25_wren(FAR struct w25_dev_s *priv);
+static inline void w25_wrdi(FAR struct w25_dev_s *priv);
+static void w25_sectorerase(FAR struct w25_dev_s *priv, off_t offset);
+static inline int w25_chiperase(FAR struct w25_dev_s *priv);
+static void w25_byteread(FAR struct w25_dev_s *priv, FAR uint8_t *buffer,
+ off_t address, size_t nbytes);
+#ifndef CONFIG_W25_READONLY
+static void w25_pagewrite(FAR struct w25_dev_s *priv, FAR const uint8_t *buffer,
+ off_t address, size_t nbytes);
+#endif
+#ifdef CONFIG_W25_SECTOR512
+static void w25_cacheflush(struct w25_dev_s *priv);
+static FAR uint8_t *w25_cacheread(struct w25_dev_s *priv, off_t sector);
+static void w25_cacheerase(struct w25_dev_s *priv, off_t sector);
+static void w25_cachewrite(FAR struct w25_dev_s *priv, FAR const uint8_t *buffer,
+ off_t sector, size_t nsectors);
+#endif
+
+/* MTD driver methods */
+
+static int w25_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
+static ssize_t w25_bread(FAR struct mtd_dev_s *dev, off_t startblock,
+ size_t nblocks, FAR uint8_t *buf);
+static ssize_t w25_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,
+ size_t nblocks, FAR const uint8_t *buf);
+static ssize_t w25_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR uint8_t *buffer);
+static int w25_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: w25_lock
+ ************************************************************************************/
+
+static void w25_lock(FAR struct spi_dev_s *spi)
+{
+ /* On SPI busses where there are multiple devices, it will be necessary to
+ * lock SPI to have exclusive access to the busses for a sequence of
+ * transfers. The bus should be locked before the chip is selected.
+ *
+ * This is a blocking call and will not return until we have exclusiv access to
+ * the SPI buss. We will retain that exclusive access until the bus is unlocked.
+ */
+
+ (void)SPI_LOCK(spi, true);
+
+ /* After locking the SPI bus, the we also need call the setfrequency, setbits, and
+ * setmode methods to make sure that the SPI is properly configured for the device.
+ * If the SPI buss is being shared, then it may have been left in an incompatible
+ * state.
+ */
+
+ SPI_SETMODE(spi, CONFIG_W25_SPIMODE);
+ SPI_SETBITS(spi, 8);
+ (void)SPI_SETFREQUENCY(spi, CONFIG_W25_SPIFREQUENCY);
+}
+
+/************************************************************************************
+ * Name: w25_unlock
+ ************************************************************************************/
+
+static inline void w25_unlock(FAR struct spi_dev_s *spi)
+{
+ (void)SPI_LOCK(spi, false);
+}
+
+/************************************************************************************
+ * Name: w25_readid
+ ************************************************************************************/
+
+static inline int w25_readid(struct w25_dev_s *priv)
+{
+ uint16_t manufacturer;
+ uint16_t memory;
+ uint16_t capacity;
+
+ fvdbg("priv: %p\n", priv);
+
+ /* Lock the SPI bus, configure the bus, and select this FLASH part. */
+
+ w25_lock(priv->spi);
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send the "Read ID (RDID)" command and read the first three ID bytes */
+
+ (void)SPI_SEND(priv->spi, W25_JEDEC_ID);
+ manufacturer = SPI_SEND(priv->spi, W25_DUMMY);
+ memory = SPI_SEND(priv->spi, W25_DUMMY);
+ capacity = SPI_SEND(priv->spi, W25_DUMMY);
+
+ /* Deselect the FLASH and unlock the bus */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+ w25_unlock(priv->spi);
+
+ fvdbg("manufacturer: %02x memory: %02x capacity: %02x\n",
+ manufacturer, memory, capacity);
+
+ /* Check for a valid manufacturer and memory type */
+
+ if (manufacturer == W25_JEDEC_MANUFACTURER &&
+ (memory == W25X_JEDEC_MEMORY_TYPE ||
+ memory == W25Q_JEDEC_MEMORY_TYPE_A ||
+ memory == W25Q_JEDEC_MEMORY_TYPE_B))
+ {
+ /* Okay.. is it a FLASH capacity that we understand? If so, save
+ * the FLASH capacity.
+ */
+
+ /* 16M-bit / 2M-byte (2,097,152)
+ *
+ * W24X16, W25Q16BV, W25Q16CL, W25Q16CV, W25Q16DW
+ */
+
+ if (capacity == W25_JEDEC_CAPACITY_16MBIT)
+ {
+ priv->nsectors = NSECTORS_16MBIT;
+ }
+
+ /* 32M-bit / M-byte (4,194,304)
+ *
+ * W25X32, W25Q32BV, W25Q32DW
+ */
+
+ else if (capacity == W25_JEDEC_CAPACITY_32MBIT)
+ {
+ priv->nsectors = NSECTORS_32MBIT;
+ }
+
+ /* 64M-bit / 8M-byte (8,388,608)
+ *
+ * W25X64, W25Q64BV, W25Q64CV, W25Q64DW
+ */
+
+ else if (capacity == W25_JEDEC_CAPACITY_64MBIT)
+ {
+ priv->nsectors = NSECTORS_64MBIT;
+ }
+
+ /* 128M-bit / 16M-byte (16,777,216)
+ *
+ * W25Q128BV
+ */
+
+ else if (capacity == W25_JEDEC_CAPACITY_128MBIT)
+ {
+ priv->nsectors = NSECTORS_128MBIT;
+ }
+ else
+ {
+ /* Nope.. we don't understand this capacity. */
+
+ return -ENODEV;
+ }
+
+ return OK;
+ }
+
+ /* We don't understand the manufacturer or the memory type */
+
+ return -ENODEV;
+}
+
+/************************************************************************************
+ * Name: w25_unprotect
+ ************************************************************************************/
+
+#ifndef CONFIG_W25_READONLY
+static void w25_unprotect(FAR struct w25_dev_s *priv)
+{
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send "Write enable (WREN)" */
+
+ w25_wren(priv);
+
+ /* Re-select this FLASH part (This might not be necessary... but is it shown in
+ * the SST25 timing diagrams from which this code was leveraged.)
+ */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send "Write enable status (EWSR)" */
+
+ SPI_SEND(priv->spi, W25_WRSR);
+
+ /* Following by the new status value */
+
+ SPI_SEND(priv->spi, 0);
+ SPI_SEND(priv->spi, 0);
+}
+#endif
+
+/************************************************************************************
+ * Name: w25_waitwritecomplete
+ ************************************************************************************/
+
+static uint8_t w25_waitwritecomplete(struct w25_dev_s *priv)
+{
+ uint8_t status;
+
+ /* Are we the only device on the bus? */
+
+#ifdef CONFIG_SPI_OWNBUS
+
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send "Read Status Register (RDSR)" command */
+
+ (void)SPI_SEND(priv->spi, W25_RDSR);
+
+ /* Loop as long as the memory is busy with a write cycle */
+
+ do
+ {
+ /* Send a dummy byte to generate the clock needed to shift out the status */
+
+ status = SPI_SEND(priv->spi, W25_DUMMY);
+ }
+ while ((status & W25_SR_BUSY) != 0);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+
+#else
+
+ /* Loop as long as the memory is busy with a write cycle */
+
+ do
+ {
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send "Read Status Register (RDSR)" command */
+
+ (void)SPI_SEND(priv->spi, W25_RDSR);
+
+ /* Send a dummy byte to generate the clock needed to shift out the status */
+
+ status = SPI_SEND(priv->spi, W25_DUMMY);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+
+ /* Given that writing could take up to few tens of milliseconds, and erasing
+ * could take more. The following short delay in the "busy" case will allow
+ * other peripherals to access the SPI bus.
+ */
+
+#if 0 /* Makes writes too slow */
+ if ((status & W25_SR_BUSY) != 0)
+ {
+ w25_unlock(priv->spi);
+ usleep(1000);
+ w25_lock(priv->spi);
+ }
+#endif
+ }
+ while ((status & W25_SR_BUSY) != 0);
+#endif
+
+ return status;
+}
+
+/************************************************************************************
+ * Name: w25_wren
+ ************************************************************************************/
+
+static inline void w25_wren(struct w25_dev_s *priv)
+{
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send "Write Enable (WREN)" command */
+
+ (void)SPI_SEND(priv->spi, W25_WREN);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+}
+
+/************************************************************************************
+ * Name: w25_wrdi
+ ************************************************************************************/
+
+static inline void w25_wrdi(struct w25_dev_s *priv)
+{
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send "Write Disable (WRDI)" command */
+
+ (void)SPI_SEND(priv->spi, W25_WRDI);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+}
+
+/************************************************************************************
+ * Name: w25_sectorerase
+ ************************************************************************************/
+
+static void w25_sectorerase(struct w25_dev_s *priv, off_t sector)
+{
+ off_t address = sector << W25_SECTOR_SHIFT;
+
+ fvdbg("sector: %08lx\n", (long)sector);
+
+ /* Wait for any preceding write or erase operation to complete. */
+
+ (void)w25_waitwritecomplete(priv);
+
+ /* Send write enable instruction */
+
+ w25_wren(priv);
+
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send the "Sector Erase (SE)" instruction */
+
+ (void)SPI_SEND(priv->spi, W25_SE);
+
+ /* Send the sector address high byte first. Only the most significant bits (those
+ * corresponding to the sector) have any meaning.
+ */
+
+ (void)SPI_SEND(priv->spi, (address >> 16) & 0xff);
+ (void)SPI_SEND(priv->spi, (address >> 8) & 0xff);
+ (void)SPI_SEND(priv->spi, address & 0xff);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+}
+
+/************************************************************************************
+ * Name: w25_chiperase
+ ************************************************************************************/
+
+static inline int w25_chiperase(struct w25_dev_s *priv)
+{
+ fvdbg("priv: %p\n", priv);
+
+ /* Wait for any preceding write or erase operation to complete. */
+
+ (void)w25_waitwritecomplete(priv);
+
+ /* Send write enable instruction */
+
+ w25_wren(priv);
+
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send the "Chip Erase (CE)" instruction */
+
+ (void)SPI_SEND(priv->spi, W25_CE);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+ fvdbg("Return: OK\n");
+ return OK;
+}
+
+/************************************************************************************
+ * Name: w25_byteread
+ ************************************************************************************/
+
+static void w25_byteread(FAR struct w25_dev_s *priv, FAR uint8_t *buffer,
+ off_t address, size_t nbytes)
+{
+ uint8_t status;
+
+ fvdbg("address: %08lx nbytes: %d\n", (long)address, (int)nbytes);
+
+ /* Wait for any preceding write or erase operation to complete. */
+
+ status = w25_waitwritecomplete(priv);
+ DEBUGASSERT((status & (W25_SR_WEL|W25_SR_BP_MASK)) == 0);
+
+ /* Make sure that writing is disabled */
+
+ w25_wrdi(priv);
+
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send "Read from Memory " instruction */
+
+#ifdef CONFIG_W25_SLOWREAD
+ (void)SPI_SEND(priv->spi, W25_RDDATA);
+#else
+ (void)SPI_SEND(priv->spi, W25_FRD);
+#endif
+
+ /* Send the address high byte first. */
+
+ (void)SPI_SEND(priv->spi, (address >> 16) & 0xff);
+ (void)SPI_SEND(priv->spi, (address >> 8) & 0xff);
+ (void)SPI_SEND(priv->spi, address & 0xff);
+
+ /* Send a dummy byte */
+
+#ifndef CONFIG_W25_SLOWREAD
+ (void)SPI_SEND(priv->spi, W25_DUMMY);
+#endif
+
+ /* Then read all of the requested bytes */
+
+ SPI_RECVBLOCK(priv->spi, buffer, nbytes);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+}
+
+/************************************************************************************
+ * Name: w25_pagewrite
+ ************************************************************************************/
+
+#ifndef CONFIG_W25_READONLY
+static void w25_pagewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer,
+ off_t address, size_t nbytes)
+{
+ uint8_t status;
+
+ fvdbg("address: %08lx nwords: %d\n", (long)address, (int)nbytes);
+ DEBUGASSERT(priv && buffer && ((uintptr_t)buffer & 0xff) == 0 &&
+ (nbytes & 0xff) == 0);
+
+ for (; nbytes > 0; nbytes -= W25_PAGE_SIZE)
+ {
+ /* Wait for any preceding write or erase operation to complete. */
+
+ status = w25_waitwritecomplete(priv);
+ DEBUGASSERT((status & (W25_SR_WEL|W25_SR_BP_MASK)) == 0);
+
+ /* Enable write access to the FLASH */
+
+ w25_wren(priv);
+
+ /* Select this FLASH part */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, true);
+
+ /* Send the "Page Program (W25_PP)" Command */
+
+ SPI_SEND(priv->spi, W25_PP);
+
+ /* Send the address high byte first. */
+
+ (void)SPI_SEND(priv->spi, (address >> 16) & 0xff);
+ (void)SPI_SEND(priv->spi, (address >> 8) & 0xff);
+ (void)SPI_SEND(priv->spi, address & 0xff);
+
+ /* Then send the page of data */
+
+ SPI_SNDBLOCK(priv->spi, buffer, W25_PAGE_SIZE);
+
+ /* Deselect the FLASH and setup for the next pass through the loop */
+
+ SPI_SELECT(priv->spi, SPIDEV_FLASH, false);
+
+ /* Update addresses */
+
+ address += W25_PAGE_SIZE;
+ buffer += W25_PAGE_SIZE;
+ }
+
+ /* Disable writing */
+
+ w25_wrdi(priv);
+}
+#endif
+
+/************************************************************************************
+ * Name: w25_cacheflush
+ ************************************************************************************/
+
+#if defined(CONFIG_W25_SECTOR512) && !defined(CONFIG_W25_READONLY)
+static void w25_cacheflush(struct w25_dev_s *priv)
+{
+ /* If the cached is dirty (meaning that it no longer matches the old FLASH contents)
+ * or was erased (with the cache containing the correct FLASH contents), then write
+ * the cached erase block to FLASH.
+ */
+
+ if (IS_DIRTY(priv) || IS_ERASED(priv))
+ {
+ /* Write entire erase block to FLASH */
+
+ w25_pagewrite(priv, priv->sector, (off_t)priv->esectno << W25_SECTOR_SHIFT,
+ W25_SECTOR_SIZE);
+
+ /* The case is no long dirty and the FLASH is no longer erased */
+
+ CLR_DIRTY(priv);
+ CLR_ERASED(priv);
+ }
+}
+#endif
+
+/************************************************************************************
+ * Name: w25_cacheread
+ ************************************************************************************/
+
+#if defined(CONFIG_W25_SECTOR512) && !defined(CONFIG_W25_READONLY)
+static FAR uint8_t *w25_cacheread(struct w25_dev_s *priv, off_t sector)
+{
+ off_t esectno;
+ int shift;
+ int index;
+
+ /* Convert from the 512 byte sector to the erase sector size of the device. For
+ * exmample, if the actual erase sector size if 4Kb (1 << 12), then we first
+ * shift to the right by 3 to get the sector number in 4096 increments.
+ */
+
+ shift = W25_SECTOR_SHIFT - W25_SECTOR512_SHIFT;
+ esectno = sector >> shift;
+ fvdbg("sector: %ld esectno: %d shift=%d\n", sector, esectno, shift);
+
+ /* Check if the requested erase block is already in the cache */
+
+ if (!IS_VALID(priv) || esectno != priv->esectno)
+ {
+ /* No.. Flush any dirty erase block currently in the cache */
+
+ w25_cacheflush(priv);
+
+ /* Read the erase block into the cache */
+
+ w25_byteread(priv, priv->sector, (esectno << W25_SECTOR_SHIFT), W25_SECTOR_SIZE);
+
+ /* Mark the sector as cached */
+
+ priv->esectno = esectno;
+
+ SET_VALID(priv); /* The data in the cache is valid */
+ CLR_DIRTY(priv); /* It should match the FLASH contents */
+ CLR_ERASED(priv); /* The underlying FLASH has not been erased */
+ }
+
+ /* Get the index to the 512 sector in the erase block that holds the argument */
+
+ index = sector & ((1 << shift) - 1);
+
+ /* Return the address in the cache that holds this sector */
+
+ return &priv->sector[index << W25_SECTOR512_SHIFT];
+}
+#endif
+
+/************************************************************************************
+ * Name: w25_cacheerase
+ ************************************************************************************/
+
+#if defined(CONFIG_W25_SECTOR512) && !defined(CONFIG_W25_READONLY)
+static void w25_cacheerase(struct w25_dev_s *priv, off_t sector)
+{
+ FAR uint8_t *dest;
+
+ /* First, make sure that the erase block containing the 512 byte sector is in
+ * the cache.
+ */
+
+ dest = w25_cacheread(priv, sector);
+
+ /* Erase the block containing this sector if it is not already erased.
+ * The erased indicated will be cleared when the data from the erase sector
+ * is read into the cache and set here when we erase the block.
+ */
+
+ if (!IS_ERASED(priv))
+ {
+ off_t esectno = sector >> (W25_SECTOR_SHIFT - W25_SECTOR512_SHIFT);
+ fvdbg("sector: %ld esectno: %d\n", sector, esectno);
+
+ w25_sectorerase(priv, esectno);
+ SET_ERASED(priv);
+ }
+
+ /* Put the cached sector data into the erase state and mart the cache as dirty
+ * (but don't update the FLASH yet. The caller will do that at a more optimal
+ * time).
+ */
+
+ memset(dest, W25_ERASED_STATE, W25_SECTOR512_SIZE);
+ SET_DIRTY(priv);
+}
+#endif
+
+/************************************************************************************
+ * Name: w25_cachewrite
+ ************************************************************************************/
+
+#if defined(CONFIG_W25_SECTOR512) && !defined(CONFIG_W25_READONLY)
+static void w25_cachewrite(FAR struct w25_dev_s *priv, FAR const uint8_t *buffer,
+ off_t sector, size_t nsectors)
+{
+ FAR uint8_t *dest;
+
+ for (; nsectors > 0; nsectors--)
+ {
+ /* First, make sure that the erase block containing 512 byte sector is in
+ * memory.
+ */
+
+ dest = w25_cacheread(priv, sector);
+
+ /* Erase the block containing this sector if it is not already erased.
+ * The erased indicated will be cleared when the data from the erase sector
+ * is read into the cache and set here when we erase the sector.
+ */
+
+ if (!IS_ERASED(priv))
+ {
+ off_t esectno = sector >> (W25_SECTOR_SHIFT - W25_SECTOR512_SHIFT);
+ fvdbg("sector: %ld esectno: %d\n", sector, esectno);
+
+ w25_sectorerase(priv, esectno);
+ SET_ERASED(priv);
+ }
+
+ /* Copy the new sector data into cached erase block */
+
+ memcpy(dest, buffer, W25_SECTOR512_SIZE);
+ SET_DIRTY(priv);
+
+ /* Set up for the next 512 byte sector */
+
+ buffer += W25_SECTOR512_SIZE;
+ sector++;
+ }
+
+ /* Flush the last erase block left in the cache */
+
+ w25_cacheflush(priv);
+}
+#endif
+
+/************************************************************************************
+ * Name: w25_erase
+ ************************************************************************************/
+
+static int w25_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
+{
+#ifdef CONFIG_W25_READONLY
+ return -EACESS
+#else
+ FAR struct w25_dev_s *priv = (FAR struct w25_dev_s *)dev;
+ size_t blocksleft = nblocks;
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
+ /* Lock access to the SPI bus until we complete the erase */
+
+ w25_lock(priv->spi);
+
+ while (blocksleft-- > 0)
+ {
+ /* Erase each sector */
+
+#ifdef CONFIG_W25_SECTOR512
+ w25_cacheerase(priv, startblock);
+#else
+ w25_sectorerase(priv, startblock);
+#endif
+ startblock++;
+ }
+
+#ifdef CONFIG_W25_SECTOR512
+ /* Flush the last erase block left in the cache */
+
+ w25_cacheflush(priv);
+#endif
+
+ w25_unlock(priv->spi);
+ return (int)nblocks;
+#endif
+}
+
+/************************************************************************************
+ * Name: w25_bread
+ ************************************************************************************/
+
+static ssize_t w25_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR uint8_t *buffer)
+{
+#ifdef CONFIG_W25_SECTOR512
+ ssize_t nbytes;
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
+ /* On this device, we can handle the block read just like the byte-oriented read */
+
+ nbytes = w25_read(dev, startblock << W25_SECTOR512_SHIFT, nblocks << W25_SECTOR512_SHIFT, buffer);
+ if (nbytes > 0)
+ {
+ return nbytes >> W25_SECTOR512_SHIFT;
+ }
+
+ return (int)nbytes;
+#else
+ FAR struct w25_dev_s *priv = (FAR struct w25_dev_s *)dev;
+ ssize_t nbytes;
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
+ /* On this device, we can handle the block read just like the byte-oriented read */
+
+ nbytes = w25_read(dev, startblock << W25_SECTOR_SHIFT, nblocks << W25_SECTOR_SHIFT, buffer);
+ if (nbytes > 0)
+ {
+ return nbytes >> W25_SECTOR_SHIFT;
+ }
+
+ return (int)nbytes;
+#endif
+}
+
+/************************************************************************************
+ * Name: w25_bwrite
+ ************************************************************************************/
+
+static ssize_t w25_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const uint8_t *buffer)
+{
+#ifdef CONFIG_W25_READONLY
+ return -EACCESS;
+#else
+ FAR struct w25_dev_s *priv = (FAR struct w25_dev_s *)dev;
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
+ /* Lock the SPI bus and write all of the pages to FLASH */
+
+ w25_lock(priv->spi);
+
+#if defined(CONFIG_W25_SECTOR512)
+ w25_cachewrite(priv, buffer, startblock, nblocks);
+#else
+ w25_pagewrite(priv, buffer, startblock << W25_SECTOR_SHIFT,
+ nblocks << W25_SECTOR_SHIFT);
+#endif
+ w25_unlock(priv->spi);
+
+ return nblocks;
+#endif
+}
+
+/************************************************************************************
+ * Name: w25_read
+ ************************************************************************************/
+
+static ssize_t w25_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR uint8_t *buffer)
+{
+ FAR struct w25_dev_s *priv = (FAR struct w25_dev_s *)dev;
+
+ fvdbg("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes);
+
+ /* Lock the SPI bus and select this FLASH part */
+
+ w25_lock(priv->spi);
+ w25_byteread(priv, buffer, offset, nbytes);
+ w25_unlock(priv->spi);
+
+ fvdbg("return nbytes: %d\n", (int)nbytes);
+ return nbytes;
+}
+
+/************************************************************************************
+ * Name: w25_ioctl
+ ************************************************************************************/
+
+static int w25_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
+{
+ FAR struct w25_dev_s *priv = (FAR struct w25_dev_s *)dev;
+ int ret = -EINVAL; /* Assume good command with bad parameters */
+
+ fvdbg("cmd: %d \n", cmd);
+
+ switch (cmd)
+ {
+ case MTDIOC_GEOMETRY:
+ {
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg);
+ if (geo)
+ {
+ /* Populate the geometry structure with information need to know
+ * the capacity and how to access the device.
+ *
+ * NOTE: that the device is treated as though it where just an array
+ * of fixed size blocks. That is most likely not true, but the client
+ * will expect the device logic to do whatever is necessary to make it
+ * appear so.
+ */
+
+#ifdef CONFIG_W25_SECTOR512
+ geo->blocksize = (1 << W25_SECTOR512_SHIFT);
+ geo->erasesize = (1 << W25_SECTOR512_SHIFT);
+ geo->neraseblocks = priv->nsectors << (W25_SECTOR_SHIFT - W25_SECTOR512_SHIFT);
+#else
+ geo->blocksize = W25_SECTOR_SIZE;
+ geo->erasesize = W25_SECTOR_SIZE;
+ geo->neraseblocks = priv->nsectors;
+#endif
+ ret = OK;
+
+ fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n",
+ geo->blocksize, geo->erasesize, geo->neraseblocks);
+ }
+ }
+ break;
+
+ case MTDIOC_BULKERASE:
+ {
+ /* Erase the entire device */
+
+ w25_lock(priv->spi);
+ ret = w25_chiperase(priv);
+ w25_unlock(priv->spi);
+ }
+ break;
+
+ case MTDIOC_XIPBASE:
+ default:
+ ret = -ENOTTY; /* Bad command */
+ break;
+ }
+
+ fvdbg("return %d\n", ret);
+ return ret;
+}
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: w25_initialize
+ *
+ * Description:
+ * Create an initialize MTD device instance. MTD devices are not registered
+ * in the file system, but are created as instances that can be bound to
+ * other functions (such as a block or character driver front end).
+ *
+ ************************************************************************************/
+
+FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *spi)
+{
+ FAR struct w25_dev_s *priv;
+ int ret;
+
+ fvdbg("spi: %p\n", spi);
+
+ /* Allocate a state structure (we allocate the structure instead of using
+ * a fixed, static allocation so that we can handle multiple FLASH devices.
+ * The current implementation would handle only one FLASH part per SPI
+ * device (only because of the SPIDEV_FLASH definition) and so would have
+ * to be extended to handle multiple FLASH parts on the same SPI bus.
+ */
+
+ priv = (FAR struct w25_dev_s *)kzalloc(sizeof(struct w25_dev_s));
+ if (priv)
+ {
+ /* Initialize the allocated structure */
+
+ priv->mtd.erase = w25_erase;
+ priv->mtd.bread = w25_bread;
+ priv->mtd.bwrite = w25_bwrite;
+ priv->mtd.read = w25_read;
+ priv->mtd.ioctl = w25_ioctl;
+ priv->spi = spi;
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(spi, SPIDEV_FLASH, false);
+
+ /* Identify the FLASH chip and get its capacity */
+
+ ret = w25_readid(priv);
+ if (ret != OK)
+ {
+ /* Unrecognized! Discard all of that work we just did and return NULL */
+
+ fdbg("Unrecognized\n");
+ kfree(priv);
+ priv = NULL;
+ }
+ else
+ {
+ /* Make sure the the FLASH is unprotected so that we can write into it */
+
+#ifndef CONFIG_W25_READONLY
+ w25_unprotect(priv);
+#endif
+
+#ifdef CONFIG_W25_SECTOR512 /* Simulate a 512 byte sector */
+ /* Allocate a buffer for the erase block cache */
+
+ priv->sector = (FAR uint8_t *)kmalloc(W25_SECTOR_SIZE);
+ if (!priv->sector)
+ {
+ /* Allocation failed! Discard all of that work we just did and return NULL */
+
+ fdbg("Allocation failed\n");
+ kfree(priv);
+ priv = NULL;
+ }
+#endif
+ }
+ }
+
+ /* Return the implementation-specific state structure as the MTD device */
+
+ fvdbg("Return %p\n", priv);
+ return (FAR struct mtd_dev_s *)priv;
+}
diff --git a/nuttx/drivers/net/Kconfig b/nuttx/drivers/net/Kconfig
index b5c09bf01..a42d35fea 100644
--- a/nuttx/drivers/net/Kconfig
+++ b/nuttx/drivers/net/Kconfig
@@ -25,6 +25,7 @@ config ENC28J60
References:
ENC28J60 Data Sheet, Stand-Alone Ethernet Controller with SPI Interface,
DS39662C, 2008 Microchip Technology Inc.
+
if ENC28J60
config ENC28J60_NINTERFACES
int "Number of physical ENC28J60"
@@ -61,6 +62,14 @@ config ENC28J60_HALFDUPPLEX
default n
---help---
Default is full duplex
+
+config ENC28J60_DUMPPACKET
+ bool "Dump Packets"
+ default n
+ ---help---
+ If selected, the ENC28J60 driver will dump the contents of each
+ packet to the console.
+
endif
config NET_E1000
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index d3c735b11..bb79910b3 100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -110,7 +110,7 @@
/* We need to have the work queue to handle SPI interrupts */
-#if !defined(CONFIG_SCHED_WORKQUEUE) && !defined(CONFIG_SPI_OWNBUS)
+#ifndef CONFIG_SCHED_WORKQUEUE
# error "Worker thread support is required (CONFIG_SCHED_WORKQUEUE)"
#endif
@@ -122,6 +122,12 @@
# define enc_dumppacket(m,a,n)
#endif
+/* The ENC28J60 will not do interrupt level processing */
+
+#ifndef CONFIG_NET_NOINTS
+# warrning "CONFIG_NET_NOINTS should be set"
+#endif
+
/* Timing *******************************************************************/
/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
@@ -144,7 +150,7 @@
#define ALIGNED_BUFSIZE ((CONFIG_NET_BUFSIZE + 255) & ~255)
#define PKTMEM_TX_START 0x0000 /* Start TX buffer at 0 */
-#define PKTMEM_TX_ENDP1 ALIGNED_BUFSIZE /* Allow TX buffer for one frame + */
+#define PKTMEM_TX_ENDP1 ALIGNED_BUFSIZE /* Allow TX buffer for one frame */
#define PKTMEM_RX_START PKTMEM_TX_ENDP1 /* Followed by RX buffer */
#define PKTMEM_RX_END PKTMEM_END /* RX buffer goes to the end of SRAM */
@@ -171,7 +177,7 @@
enum enc_state_e
{
- ENCSTATE_UNIT = 0, /* The interface is in an unknown state */
+ ENCSTATE_UNINIT = 0, /* The interface is in an uninitialized state */
ENCSTATE_DOWN, /* The interface is down */
ENCSTATE_UP /* The interface is up */
};
@@ -200,10 +206,10 @@ struct enc_driver_s
/* If we don't own the SPI bus, then we cannot do SPI accesses from the
* interrupt handler.
*/
-
-#ifndef CONFIG_SPI_OWNBUS
- struct work_s work; /* Work queue support */
-#endif
+
+ struct work_s irqwork; /* Interrupt continuation work queue support */
+ struct work_s towork; /* Tx timeout work queue support */
+ struct work_s pollwork; /* Poll timeout work queue support */
/* This is the contained SPI driver intstance */
@@ -279,15 +285,17 @@ static void enc_txif(FAR struct enc_driver_s *priv);
static void enc_txerif(FAR struct enc_driver_s *priv);
static void enc_txerif(FAR struct enc_driver_s *priv);
static void enc_rxerif(FAR struct enc_driver_s *priv);
-static void enc_rxdispath(FAR struct enc_driver_s *priv);
+static void enc_rxdispatch(FAR struct enc_driver_s *priv);
static void enc_pktif(FAR struct enc_driver_s *priv);
-static void enc_worker(FAR void *arg);
+static void enc_irqworker(FAR void *arg);
static int enc_interrupt(int irq, FAR void *context);
/* Watchdog timer expirations */
-static void enc_polltimer(int argc, uint32_t arg, ...);
+static void enc_toworker(FAR void *arg);
static void enc_txtimeout(int argc, uint32_t arg, ...);
+static void enc_pollworker(FAR void *arg);
+static void enc_polltimer(int argc, uint32_t arg, ...);
/* NuttX callback functions */
@@ -652,14 +660,14 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
DEBUGASSERT(priv && priv->spi);
- /* Select ENC28J60 chip */
-
- enc_select(priv);
-
/* Set the bank */
enc_setbank(priv, GETBANK(ctrlreg));
+ /* Select ENC28J60 chip */
+
+ enc_select(priv);
+
/* Send the RCR command and collect the data. How we collect the data
* depends on if this is a PHY/CAN or not. The normal sequence requires
* 16-clocks: 8 to clock out the cmd and 8 to clock in the data.
@@ -672,10 +680,10 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
* 8 dummy bits, and 8 to clock in the PHY/MAC data.
*/
- (void)SPI_SEND(priv->spi, 0); /* Clock in the dummy byte */
+ (void)SPI_SEND(priv->spi, 0); /* Clock in the dummy byte */
}
- rddata = SPI_SEND(priv->spi, 0); /* Clock in the data */
+ rddata = SPI_SEND(priv->spi, 0); /* Clock in the data */
/* De-select ENC28J60 chip */
@@ -1026,6 +1034,7 @@ static int enc_transmit(FAR struct enc_driver_s *priv)
* OK on success; a negated errno on failure
*
* Assumptions:
+ * Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
@@ -1095,6 +1104,7 @@ static void enc_linkstatus(FAR struct enc_driver_s *priv)
* None
*
* Assumptions:
+ * Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
@@ -1195,7 +1205,7 @@ static void enc_rxerif(FAR struct enc_driver_s *priv)
}
/****************************************************************************
- * Function: enc_rxdispath
+ * Function: enc_rxdispatch
*
* Description:
* Give the newly received packet to uIP.
@@ -1207,10 +1217,11 @@ static void enc_rxerif(FAR struct enc_driver_s *priv)
* None
*
* Assumptions:
+ * Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
-static void enc_rxdispath(FAR struct enc_driver_s *priv)
+static void enc_rxdispatch(FAR struct enc_driver_s *priv)
{
/* We only accept IP packets of the configured type and ARP packets */
@@ -1267,6 +1278,7 @@ static void enc_rxdispath(FAR struct enc_driver_s *priv)
* None
*
* Assumptions:
+ * Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
@@ -1326,7 +1338,7 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
nlldbg("Bad packet size dropped (%d)\n", pktlen);
#ifdef CONFIG_ENC28J60_STATS
priv->stats.rxpktlen++;
-#endif
+#endif
}
/* Otherwise, read and process the packet */
@@ -1340,11 +1352,11 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
/* Copy the data data from the receive buffer to priv->dev.d_buf */
enc_rdbuffer(priv, priv->dev.d_buf, priv->dev.d_len);
- enc_dumppacket("Received Packet", priv->ld_dev.d_buf, priv->ld_dev.d_len);
+ enc_dumppacket("Received Packet", priv->dev.d_buf, priv->dev.d_len);
/* Dispatch the packet to uIP */
- enc_rxdispath(priv);
+ enc_rxdispatch(priv);
}
/* Move the RX read pointer to the start of the next received packet.
@@ -1360,7 +1372,7 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
}
/****************************************************************************
- * Function: enc_worker
+ * Function: enc_irqworker
*
* Description:
* Perform interrupt handling logic outside of the interrupt handler (on
@@ -1376,14 +1388,26 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
*
****************************************************************************/
-static void enc_worker(FAR void *arg)
+static void enc_irqworker(FAR void *arg)
{
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
+ uip_lock_t lock;
uint8_t eir;
DEBUGASSERT(priv);
- /* Disable further interrupts by clearing the global interrup enable bit */
+ /* Get exclusive access to uIP. */
+
+ lock = uip_lock();
+
+ /* Disable further interrupts by clearing the global interrupt enable bit.
+ * "After an interrupt occurs, the host controller should clear the global
+ * enable bit for the interrupt pin before servicing the interrupt. Clearing
+ * the enable bit will cause the interrupt pin to return to the non-asserted
+ * state (high). Doing so will prevent the host controller from missing a
+ * falling edge should another interrupt occur while the immediate interrupt
+ * is being serviced."
+ */
enc_bfcgreg(priv, ENC_EIE, EIE_INTIE);
@@ -1395,9 +1419,12 @@ static void enc_worker(FAR void *arg)
while ((eir = enc_rdgreg(priv, ENC_EIR) & EIR_ALLINTS) != 0)
{
/* Handle interrupts according to interrupt register register bit
- * settings
- *
- * DMAIF: The DMA interrupt indicates that the DMA module has completed
+ * settings.
+ */
+
+ nllvdbg("EIR: %02x\n", eir);
+
+ /* DMAIF: The DMA interrupt indicates that the DMA module has completed
* its memory copy or checksum calculation. Additionally, this interrupt
* will be caused if the host controller cancels a DMA operation by
* manually clearing the DMAST bit. Once set, DMAIF can only be cleared
@@ -1514,6 +1541,8 @@ static void enc_worker(FAR void *arg)
uint8_t pktcnt = enc_rdbreg(priv, ENC_EPKTCNT);
if (pktcnt > 0)
{
+ nllvdbg("EPKTCNT: %02x\n", pktcnt);
+
#ifdef CONFIG_ENC28J60_STATS
if (pktcnt > priv->stats.maxpktcnt)
{
@@ -1551,12 +1580,19 @@ static void enc_worker(FAR void *arg)
enc_rxerif(priv); /* Handle the RX error */
enc_bfcgreg(priv, ENC_EIR, EIR_RXERIF); /* Clear the RXERIF interrupt */
}
-
}
+ /* Release lock on uIP */
+
+ uip_unlock(lock);
+
/* Enable Ethernet interrupts */
enc_bfsgreg(priv, ENC_EIE, EIE_INTIE);
+
+ /* Enable GPIO interrupts */
+
+ priv->lower->enable(priv->lower);
}
/****************************************************************************
@@ -1580,15 +1616,6 @@ static int enc_interrupt(int irq, FAR void *context)
{
register FAR struct enc_driver_s *priv = &g_enc28j60[0];
-#ifdef CONFIG_SPI_OWNBUS
- /* In very simple environments, we own the SPI and can do data transfers
- * from the interrupt handler. That is actually a very bad idea in any
- * case because it keeps interrupts disabled for a long time.
- */
-
- enc_worker((FAR void*)priv);
- return OK;
-#else
/* In complex environments, we cannot do SPI transfers from the interrupt
* handler because semaphores are probably used to lock the SPI bus. In
* this case, we will defer processing to the worker thread. This is also
@@ -1596,20 +1623,26 @@ static int enc_interrupt(int irq, FAR void *context)
* a good thing to do in any event.
*/
- return work_queue(HPWORK, &priv->work, enc_worker, (FAR void *)priv, 0);
-#endif
+ DEBUGASSERT(work_available(&priv->irqwork));
+
+ /* Notice that further GPIO interrupts are disabled until the work is
+ * actually performed. This is to prevent overrun of the worker thread.
+ * Interrupts are re-enabled in enc_irqworker() when the work is completed.
+ */
+
+ priv->lower->disable(priv->lower);
+ return work_queue(HPWORK, &priv->irqwork, enc_irqworker, (FAR void *)priv, 0);
}
/****************************************************************************
- * Function: enc_txtimeout
+ * Function: enc_toworker
*
* Description:
- * Our TX watchdog timed out. Called from the timer interrupt handler.
- * The last TX never completed. Reset the hardware and start again.
+ * Our TX watchdog timed out. This is the worker thread continuation of
+ * the watchdog timer interrupt. Reset the hardware and start again.
*
* Parameters:
- * argc - The number of available arguments
- * arg - The first argument
+ * arg - The reference to the driver structure (case to void*)
*
* Returned Value:
* None
@@ -1618,14 +1651,21 @@ static int enc_interrupt(int irq, FAR void *context)
*
****************************************************************************/
-static void enc_txtimeout(int argc, uint32_t arg, ...)
+static void enc_toworker(FAR void *arg)
{
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
+ uip_lock_t lock;
int ret;
+ nlldbg("Tx timeout\n");
+ DEBUGASSERT(priv);
+
+ /* Get exclusive access to uIP. */
+
+ lock = uip_lock();
+
/* Increment statistics and dump debug info */
- nlldbg("Tx timeout\n");
#ifdef CONFIG_ENC28J60_STATS
priv->stats.txtimeouts++;
#endif
@@ -1642,13 +1682,18 @@ static void enc_txtimeout(int argc, uint32_t arg, ...)
/* Then poll uIP for new XMIT data */
(void)uip_poll(&priv->dev, enc_uiptxpoll);
+
+ /* Release lock on uIP */
+
+ uip_unlock(lock);
}
/****************************************************************************
- * Function: enc_polltimer
+ * Function: enc_txtimeout
*
* Description:
- * Periodic timer handler. Called from the timer interrupt handler.
+ * Our TX watchdog timed out. Called from the timer interrupt handler.
+ * The last TX never completed. Perform work on the worker thread.
*
* Parameters:
* argc - The number of available arguments
@@ -1661,9 +1706,55 @@ static void enc_txtimeout(int argc, uint32_t arg, ...)
*
****************************************************************************/
-static void enc_polltimer(int argc, uint32_t arg, ...)
+static void enc_txtimeout(int argc, uint32_t arg, ...)
{
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
+ int ret;
+
+ /* In complex environments, we cannot do SPI transfers from the timout
+ * handler because semaphores are probably used to lock the SPI bus. In
+ * this case, we will defer processing to the worker thread. This is also
+ * much kinder in the use of system resources and is, therefore, probably
+ * a good thing to do in any event.
+ */
+
+ DEBUGASSERT(priv && work_available(&priv->towork));
+
+ /* Notice that Tx timeout watchdog is not active so further Tx timeouts
+ * can occur until we restart the Tx timeout watchdog.
+ */
+
+ ret = work_queue(HPWORK, &priv->towork, enc_toworker, (FAR void *)priv, 0);
+ DEBUGASSERT(ret == OK);
+}
+
+/****************************************************************************
+ * Function: enc_pollworker
+ *
+ * Description:
+ * Periodic timer handler continuation.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void enc_pollworker(FAR void *arg)
+{
+ FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
+ uip_lock_t lock;
+
+ DEBUGASSERT(priv);
+
+ /* Get exclusive access to uIP. */
+
+ lock = uip_lock();
/* Verify that the hardware is ready to send another packet. The driver
* start a transmission process by setting ECON1.TXRTS. When the packet is
@@ -1681,12 +1772,55 @@ static void enc_polltimer(int argc, uint32_t arg, ...)
(void)uip_timer(&priv->dev, enc_uiptxpoll, ENC_POLLHSEC);
}
+ /* Release lock on uIP */
+
+ uip_unlock(lock);
+
/* Setup the watchdog poll timer again */
(void)wd_start(priv->txpoll, ENC_WDDELAY, enc_polltimer, 1, arg);
}
/****************************************************************************
+ * Function: enc_polltimer
+ *
+ * Description:
+ * Periodic timer handler. Called from the timer interrupt handler.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void enc_polltimer(int argc, uint32_t arg, ...)
+{
+ FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
+ int ret;
+
+ /* In complex environments, we cannot do SPI transfers from the timout
+ * handler because semaphores are probably used to lock the SPI bus. In
+ * this case, we will defer processing to the worker thread. This is also
+ * much kinder in the use of system resources and is, therefore, probably
+ * a good thing to do in any event.
+ */
+
+ DEBUGASSERT(priv && work_available(&priv->pollwork));
+
+ /* Notice that poll watchdog is not active so further poll timeouts can
+ * occur until we restart the poll timeout watchdog.
+ */
+
+ ret = work_queue(HPWORK, &priv->pollwork, enc_pollworker, (FAR void *)priv, 0);
+ DEBUGASSERT(ret == OK);
+}
+
+/****************************************************************************
* Function: enc_ifup
*
* Description:
@@ -1727,11 +1861,9 @@ static int enc_ifup(struct uip_driver_s *dev)
*/
enc_wrphy(priv, ENC_PHIE, PHIE_PGEIE | PHIE_PLNKIE);
- enc_bfsgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE);
- enc_bfsgreg(priv, ENC_EIR, EIR_DMAIF | EIR_LINKIF | EIR_TXIF |
- EIR_TXERIF | EIR_RXERIF | EIR_PKTIF);
- enc_wrgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE | EIE_LINKIE |
- EIE_TXIE | EIE_TXERIE | EIE_RXERIE);
+ enc_bfcgreg(priv, ENC_EIR, EIR_ALLINTS);
+ enc_wrgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE | EIE_LINKIE |
+ EIE_TXIE | EIE_TXERIE | EIE_RXERIE);
/* Enable the receiver */
@@ -2160,7 +2292,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
enc_wrbreg(priv, ENC_MAIPGL, 0x12);
- /* Set ack-to-Back Inter-Packet Gap */
+ /* Set Back-to-Back Inter-Packet Gap */
enc_wrbreg(priv, ENC_MABBIPG, 0x15);
#endif
@@ -2245,7 +2377,7 @@ int enc_initialize(FAR struct spi_dev_s *spi,
* bringing the interface up.
*/
- priv->ifstate = ENCSTATE_UNIT;
+ priv->ifstate = ENCSTATE_UNINIT;
/* Attach the interrupt to the driver (but don't enable it yet) */
diff --git a/nuttx/drivers/net/enc28j60.h b/nuttx/drivers/net/enc28j60.h
index 3c787c533..dab9cc5cf 100644
--- a/nuttx/drivers/net/enc28j60.h
+++ b/nuttx/drivers/net/enc28j60.h
@@ -131,10 +131,10 @@
#define ECON1_BSEL_SHIFT (0) /* Bits 0-1: Bank select */
#define ECON1_BSEL_MASK (3 << ECON1_BSEL_SHIFT)
-# define ECON1_BSEL_BANK0 (0 << 0) /* Bank 0 */
-# define ECON1_BSEL_BANK1 (1 << 1) /* Bank 1 */
-# define ECON1_BSEL_BANK2 (2 << 0) /* Bank 2 */
-# define ECON1_BSEL_BANK3 (3 << 0) /* Bank 3 */
+# define ECON1_BSEL_BANK0 (0 << ECON1_BSEL_SHIFT) /* Bank 0 */
+# define ECON1_BSEL_BANK1 (1 << ECON1_BSEL_SHIFT) /* Bank 1 */
+# define ECON1_BSEL_BANK2 (2 << ECON1_BSEL_SHIFT) /* Bank 2 */
+# define ECON1_BSEL_BANK3 (3 << ECON1_BSEL_SHIFT) /* Bank 3 */
#define ECON1_RXEN (1 << 2) /* Bit 2: Receive Enable */
#define ECON1_TXRTS (1 << 3) /* Bit 3: Transmit Request to Send */
#define ECON1_CSUMEN (1 << 4) /* Bit 4: DMA Checksum Enable */
diff --git a/nuttx/include/nuttx/analog/adc.h b/nuttx/include/nuttx/analog/adc.h
index 873f5d9da..f654bff05 100644
--- a/nuttx/include/nuttx/analog/adc.h
+++ b/nuttx/include/nuttx/analog/adc.h
@@ -47,6 +47,7 @@
************************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <sys/types.h>
#include <stdint.h>
@@ -78,7 +79,7 @@ struct adc_msg_s
{
uint8_t am_channel; /* The 8-bit ADC Channel */
int32_t am_data; /* ADC convert result (4 bytes) */
-} __attribute__((__packed__));
+} packed_struct;
struct adc_fifo_s
{
diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h
index 733d58eec..1e0af4382 100644
--- a/nuttx/include/nuttx/compiler.h
+++ b/nuttx/include/nuttx/compiler.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/compiler.h
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -92,6 +92,14 @@
# define reentrant_function
# define naked_function
+/* The inline_function attribute informs GCC that the function should always
+ * be inlined, regardless of the level of optimization. The noinline_function
+ * indicates that the function should never be inlined.
+ */
+
+# define inline_function __attribute__ ((always_inline))
+# define noinline_function __attribute__ ((noinline))
+
/* GCC has does not use storage classes to qualify addressing */
# define FAR
@@ -224,10 +232,15 @@
# define noreturn_function
# define packed_struct
-/* SDCC does support "naked" function s*/
+/* SDCC does support "naked" functions */
# define naked_function __naked
+/* SDCC does not support forced inlining. */
+
+# define inline_function
+# define noinline_function
+
/* The reentrant attribute informs SDCC that the function
* must be reentrant. In this case, SDCC will store input
* arguments on the stack to support reentrancy.
@@ -320,11 +333,13 @@
# define weak_function
# define weak_const_function
-/* The Zilog compiler does not support the noreturn, packed, or naked attributes */
+/* The Zilog compiler does not support the noreturn, packed, naked attributes */
# define noreturn_function
# define packed_struct
# define naked_function
+# define inline_function
+# define noinline_function
/* The Zilog compiler does not support the reentrant attribute */
@@ -406,7 +421,8 @@
# define packed_struct
# define reentrant_function
# define naked_function
-
+# define inline_function
+# define noinline_function
# define FAR
# define NEAR
diff --git a/nuttx/include/nuttx/gran.h b/nuttx/include/nuttx/gran.h
index 5390618a3..5e980dd9c 100644
--- a/nuttx/include/nuttx/gran.h
+++ b/nuttx/include/nuttx/gran.h
@@ -92,11 +92,10 @@ extern "C" {
* Set up one granule allocator instance. Allocations will be aligned to
* the alignment size (log2align; allocations will be in units of the
* granule size (log2gran). Larger granules will give better performance
- * and less overhead but more losses of memory due to alignment
- * quantization waste. Additional memory waste can occur form alignment;
- * log2align should be set to 0 unless you are using the granule allocator
- * to manage DMA memory and your hardware has specific memory alignment
- * requirements.
+ * and less overhead but more losses of memory due to quantization waste.
+ * Additional memory waste can occur from alignment; log2align should be
+ * set to 0 unless you are using the granule allocator to manage DMA memory
+ * and your hardware has specific memory alignment requirements.
*
* Geneneral Usage Summary. This is an example using the GCC section
* attribute to position a DMA heap in memory (logic in the linker script
diff --git a/nuttx/include/nuttx/i2c.h b/nuttx/include/nuttx/i2c.h
index b2238b1cf..23356ecd3 100644
--- a/nuttx/include/nuttx/i2c.h
+++ b/nuttx/include/nuttx/i2c.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/i2c.h
*
- * Copyright(C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Copyright(C) 2009-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,6 +47,16 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* If a dynamic timeout is selected, then a non-negative, non-zero micro-
+ * seconds per byte vale must be provided as well.
+ */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+# if CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE < 1
+# warning "Ignoring CONFIG_STM32_I2C_DYNTIMEO because of CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE"
+# undef CONFIG_STM32_I2C_DYNTIMEO
+# endif
+#endif
/* I2C address calculation. Convert 7- and 10-bit address to 8-bit and
* 16-bit read/write address
@@ -323,7 +333,19 @@ EXTERN FAR struct i2c_dev_s *up_i2cinitialize(int port);
*
****************************************************************************/
-EXTERN int up_i2cuninitialize(FAR struct i2c_dev_s * dev);
+EXTERN int up_i2cuninitialize(FAR struct i2c_dev_s *dev);
+
+/************************************************************************************
+ * Name: up_i2creset
+ *
+ * Description:
+ * Reset an I2C bus
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_I2C_RESET
+EXTERN int up_i2creset(FAR struct i2c_dev_s *dev);
+#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/mtd.h b/nuttx/include/nuttx/mtd.h
index 5b955a45f..44582c412 100644
--- a/nuttx/include/nuttx/mtd.h
+++ b/nuttx/include/nuttx/mtd.h
@@ -220,6 +220,19 @@ EXTERN FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
EXTERN FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
+
+/****************************************************************************
+ * Name: w25_initialize
+ *
+ * Description:
+ * Create an initialized MTD device instance. MTD devices are not registered
+ * in the file system, but are created as instances that can be bound to
+ * other functions (such as a block or character driver front end).
+ *
+ ****************************************************************************/
+
+EXTERN FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *dev);
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/include/nuttx/net/enc28j60.h b/nuttx/include/nuttx/net/enc28j60.h
index 2e39d88ac..7d0d7c3e5 100644
--- a/nuttx/include/nuttx/net/enc28j60.h
+++ b/nuttx/include/nuttx/net/enc28j60.h
@@ -85,6 +85,22 @@ struct enc_stats_s
/* The ENC28J60 normal provides interrupts to the MCU via a GPIO pin. The
* following structure provides an MCU-independent mechanixm for controlling
* the ENC28J60 GPIO interrupt.
+ *
+ * The ENC32J60 interrupt is an active low, *level* interrupt. "When an
+ * interrupt occurs, the interrupt flag is set. If the interrupt is enabled
+ * in the EIE register and the INTIE global interrupt enable bit is set, the
+ * INT pin will be driven low"
+ *
+ * "When an enabled interrupt occurs, the interrupt pin will remain low until
+ * all flags which are causing the interrupt are cleared or masked off
+ * (enable bit is cleared) by the host controller." However, the interrupt
+ * will behave like a falling edge interrupt because "After an interrupt
+ * occurs, the host controller [clears] the global enable bit for the
+ * interrupt pin before servicing the interrupt. Clearing the enable bit
+ * will cause the interrupt pin to return to the non-asserted state (high).
+ * Doing so will prevent the host controller from missing a falling edge
+ * should another interrupt occur while the immediate interrupt is being
+ * serviced."
*/
struct enc_lower_s
diff --git a/nuttx/mm/README.txt b/nuttx/mm/README.txt
index b0b80deae..2668432e3 100644
--- a/nuttx/mm/README.txt
+++ b/nuttx/mm/README.txt
@@ -46,8 +46,8 @@ This directory contains the NuttX memory management logic. This include:
3) Granule Allocator. A non-standard granule allocator is also available
in this directory The granule allocator allocates memory in units
- of a fixed sized block ("granule"). All memory is aligned to the size
- of one granule.
+ of a fixed sized block ("granule"). Allocations may be aligned to a user-
+ provided address boundary.
The granule allocator interfaces are defined in nuttx/include/nuttx/gran.h.
The granule allocator consists of these files in this directory:
@@ -59,13 +59,34 @@ This directory contains the NuttX memory management logic. This include:
as of this writing. The intent of the granule allocator is to provide
a tool to support platform-specific management of aligned DMA memory.
- NOTE: Because each granule is aligned to the granule size and each
- allocations is in units of the granule size, selection of the granule
- size is important: Larger granules will give better performance and
- less overhead but more losses of memory due to alignment and quantization
- waste.
+ NOTE: Because each granule may be aligned and each allocation is in
+ units of the granule size, selection of the granule size is important:
+ Larger granules will give better performance and less overhead but more
+ losses of memory due to quantization waste. Additional memory waste
+ can occur from alignment; Of course, heap alignment should no be
+ used unless (a) you are using the granule allocator to manage DMA memory
+ and (b) your hardware has specific memory alignment requirements.
The current implementation also restricts the maximum allocation size
to 32 granules. That restriction could be eliminated with some
additional coding effort, but currently requires larger granule
sizes for larger allocations.
+
+ Geneneral Usage Example. This is an example using the GCC section
+ attribute to position a DMA heap in memory (logic in the linker script
+ would assign the section .dmaheap to the DMA memory.
+
+ FAR uint32_t g_dmaheap[DMAHEAP_SIZE] __attribute__((section(.dmaheap)));
+
+ The heap is created by calling gran_initialize. Here the granual size
+ is set to 64 bytes and the alignment to 16 bytes:
+
+ GRAN_HANDLE handle = gran_initialize(g_dmaheap, DMAHEAP_SIZE, 6, 4);
+
+ Then the GRAN_HANDLE can be used to allocate memory (There is no
+ GRAN_HANDLE if CONFIG_GRAN_SINGLE=y):
+
+ FAR uint8_t *dma_memory = (FAR uint8_t *)gran_alloc(handle, 47);
+
+ The actual memory allocates will be 64 byte (wasting 17 bytes) and
+ will be aligned at least to (1 << log2align).
diff --git a/nuttx/mm/mm_graninit.c b/nuttx/mm/mm_graninit.c
index 16cebdcf3..e43839ad6 100644
--- a/nuttx/mm/mm_graninit.c
+++ b/nuttx/mm/mm_graninit.c
@@ -158,11 +158,10 @@ gran_common_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gran,
* Set up one granule allocator instance. Allocations will be aligned to
* the alignment size (log2align; allocations will be in units of the
* granule size (log2gran). Larger granules will give better performance
- * and less overhead but more losses of memory due to alignment
- * quantization waste. Additional memory waste can occur form alignment;
- * log2align should be set to 0 unless you are using the granule allocator
- * to manage DMA memory and your hardware has specific memory alignment
- * requirements.
+ * and less overhead but more losses of memory due to quantization waste.
+ * Additional memory waste can occur from alignment; log2align should be
+ * set to 0 unless you are using the granule allocator to manage DMA memory
+ * and your hardware has specific memory alignment requirements.
*
* Geneneral Usage Summary. This is an example using the GCC section
* attribute to position a DMA heap in memory (logic in the linker script
diff --git a/nuttx/net/Kconfig b/nuttx/net/Kconfig
index 267045402..718b28b8f 100644
--- a/nuttx/net/Kconfig
+++ b/nuttx/net/Kconfig
@@ -34,7 +34,7 @@ config NET_NOINTS
bool "Not interrupt driven"
default n
---help---
- NET_NOINT indicates that uIP not called from the interrupt level.
+ NET_NOINT indicates that uIP is not called from the interrupt level.
If NET_NOINTS is defined, critical sections will be managed with semaphores;
Otherwise, it assumed that uIP will be called from interrupt level handling
and critical sections will be managed by enabling and disabling interrupts.
diff --git a/nuttx/net/uip/uip_lock.c b/nuttx/net/uip/uip_lock.c
index 0e770cef7..5abcda269 100644
--- a/nuttx/net/uip/uip_lock.c
+++ b/nuttx/net/uip/uip_lock.c
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
+#include <unistd.h>
#include <semaphore.h>
#include <assert.h>
#include <errno.h>