summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog6
-rw-r--r--nuttx/arch/Kconfig2
-rw-r--r--nuttx/arch/arm/Kconfig2
-rw-r--r--nuttx/arch/arm/src/calypso/calypso_heap.c14
-rw-r--r--nuttx/arch/arm/src/imx/imx_allocateheap.c4
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig64
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_allocateheap.c19
-rw-r--r--nuttx/arch/z16/src/common/up_allocateheap.c2
-rw-r--r--nuttx/arch/z80/src/common/up_allocateheap.c2
-rw-r--r--nuttx/configs/compal_e99/nsh_compalram/defconfig4
-rw-r--r--nuttx/configs/compal_e99/nsh_highram/defconfig4
-rw-r--r--nuttx/configs/hymini-stm32v/buttons/defconfig8
-rwxr-xr-xnuttx/configs/hymini-stm32v/nsh/defconfig8
-rw-r--r--nuttx/configs/hymini-stm32v/nsh2/defconfig8
-rw-r--r--nuttx/configs/hymini-stm32v/nx/defconfig8
-rw-r--r--nuttx/configs/hymini-stm32v/nxlines/defconfig8
-rwxr-xr-xnuttx/configs/hymini-stm32v/usbserial/defconfig8
-rwxr-xr-xnuttx/configs/hymini-stm32v/usbstorage/defconfig8
-rwxr-xr-xnuttx/configs/kwikstik-k40/ostest/defconfig8
-rw-r--r--nuttx/configs/olimex-stm32-p107/nsh/defconfig8
-rw-r--r--nuttx/configs/olimex-stm32-p107/ostest/defconfig8
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt2
-rwxr-xr-xnuttx/configs/stm3210e-eval/RIDE/defconfig8
-rw-r--r--nuttx/configs/stm3210e-eval/buttons/defconfig8
-rwxr-xr-xnuttx/configs/stm3210e-eval/composite/defconfig8
-rwxr-xr-xnuttx/configs/stm3210e-eval/nsh/defconfig8
-rw-r--r--nuttx/configs/stm3210e-eval/nsh2/defconfig8
-rw-r--r--nuttx/configs/stm3210e-eval/nx/defconfig8
-rw-r--r--nuttx/configs/stm3210e-eval/nxconsole/defconfig8
-rw-r--r--nuttx/configs/stm3210e-eval/nxlines/defconfig8
-rw-r--r--nuttx/configs/stm3210e-eval/nxtext/defconfig8
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/defconfig8
-rw-r--r--nuttx/configs/stm3210e-eval/pm/defconfig8
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbserial/defconfig8
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbstorage/defconfig8
-rw-r--r--nuttx/configs/stm3220g-eval/README.txt8
-rw-r--r--nuttx/configs/stm3220g-eval/dhcpd/defconfig10
-rw-r--r--nuttx/configs/stm3220g-eval/nettest/defconfig10
-rw-r--r--nuttx/configs/stm3220g-eval/nsh/defconfig10
-rw-r--r--nuttx/configs/stm3220g-eval/nsh2/defconfig10
-rw-r--r--nuttx/configs/stm3220g-eval/nxwm/defconfig10
-rw-r--r--nuttx/configs/stm3220g-eval/ostest/defconfig10
-rw-r--r--nuttx/configs/stm3220g-eval/telnetd/defconfig10
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt8
-rw-r--r--nuttx/configs/stm3240g-eval/dhcpd/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/nettest/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/nsh/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/nsh2/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/nxconsole/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/nxwm/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/ostest/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/telnetd/defconfig10
-rw-r--r--nuttx/configs/stm3240g-eval/webserver/defconfig10
-rwxr-xr-xnuttx/configs/stm32f4discovery/README.txt14
-rw-r--r--nuttx/configs/stm32f4discovery/ostest/defconfig8
-rw-r--r--nuttx/configs/twr-k60n512/nsh/defconfig8
-rw-r--r--nuttx/configs/twr-k60n512/ostest/defconfig8
-rwxr-xr-xnuttx/configs/vsn/nsh/defconfig10
-rw-r--r--nuttx/mm/Kconfig36
59 files changed, 145 insertions, 424 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 252edd737..66f56401d 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3263,4 +3263,8 @@
* Kconfig: Refactor serial settings (moved from chip to drivers/serial).
AVR "teensy" now builds with Kconfig (contributed by Richard Cochran).
* Kconfig: Add configuration settings for the LPC17xx
- * Kconfig: Add configuratino settings for the LM3S (from Richard Cochran).
+ * Kconfig: Add configuration settings for the LM3S (from Richard Cochran).
+ * Kconfig: Verify configuration settings for the STM32. This include
+ changes in the way that the external SRAM is configured: Define
+ CONFIG_HEAP2_SIZE (decimal) instead of CONFIG_HEAP2_END (hex).
+
diff --git a/nuttx/arch/Kconfig b/nuttx/arch/Kconfig
index fea56b739..90bc4da91 100644
--- a/nuttx/arch/Kconfig
+++ b/nuttx/arch/Kconfig
@@ -58,11 +58,13 @@ config ARCH_X86
config ARCH_Z16
bool "ZNEO"
+ select ARCH_HAVE_HEAP2
---help---
ZiLOG ZNEO 16-bit architectures (z16f).
config ARCH_Z80
bool "z80"
+ select ARCH_HAVE_HEAP2
---help---
ZiLOG 8-bit architectures (z80, ez80, z8).
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index e6b195aff..2b06f354c 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -17,6 +17,7 @@ config ARCH_CHIP_C5471
config ARCH_CHIP_CALYPSO
bool "Calypso"
select ARCH_ARM7TDMI
+ select ARCH_HAVE_HEAP2
---help---
TI Calypso-based cell phones (ARM7TDMI)
@@ -29,6 +30,7 @@ config ARCH_CHIP_DM320
config ARCH_CHIP_IMX
bool "Freescale iMX"
select ARCH_ARM920T
+ select ARCH_HAVE_HEAP2
---help---
Freescale iMX architectures (ARM920T)
diff --git a/nuttx/arch/arm/src/calypso/calypso_heap.c b/nuttx/arch/arm/src/calypso/calypso_heap.c
index b51596f90..095fd1a5a 100644
--- a/nuttx/arch/arm/src/calypso/calypso_heap.c
+++ b/nuttx/arch/arm/src/calypso/calypso_heap.c
@@ -37,6 +37,10 @@
*
****************************************************************************/
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <nuttx/config.h>
#include <nuttx/mm.h>
@@ -53,6 +57,14 @@
#include "up_internal.h"
/****************************************************************************
+ * Preprocessor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: up_addregion
*
* Description:
@@ -84,7 +96,7 @@ void up_addregion(void)
/* Configure the RHEA bridge with some sane default values */
calypso_rhea_cfg(0, 0, 0xff, 0, 1, 0, 0);
- mm_addregion((FAR void*)CONFIG_HEAP2_START, CONFIG_HEAP2_END-CONFIG_HEAP2_START);
+ mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
}
#endif
diff --git a/nuttx/arch/arm/src/imx/imx_allocateheap.c b/nuttx/arch/arm/src/imx/imx_allocateheap.c
index 1574cac00..a42b2fb85 100644
--- a/nuttx/arch/arm/src/imx/imx_allocateheap.c
+++ b/nuttx/arch/arm/src/imx/imx_allocateheap.c
@@ -111,8 +111,8 @@ void up_addregion(void)
/* Check for any additional memory regions */
-#if defined(CONFIG_HEAP2_BASE) && defined(CONFIG_HEAP2_END)
- mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE);
+#if defined(CONFIG_HEAP2_BASE) && defined(CONFIG_HEAP2_SIZE)
+ mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
#endif
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 442f7c659..db785fd62 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -84,7 +84,42 @@ config STM32_STM32F20XX
config STM32_STM32F40XX
bool
- default y if ARCH_CHIP_STM32F405RG || ARCH_CHIP_STM32F405VG || ARCH_CHIP_STM32F405ZG || ARCH_CHIP_STM32F407VE || ARCH_CHIP_STM32F407VG || ARCH_CHIP_STM32F407ZE || ARCH_CHIP_STM32F407ZG || ARCH_CHIP_STM32F407IE || ARCH_CHIP_STM32F407IE
+ default y if ARCH_CHIP_STM32F405RG || ARCH_CHIP_STM32F405VG || ARCH_CHIP_STM32F405ZG || ARCH_CHIP_STM32F407VE || ARCH_CHIP_STM32F407VG || ARCH_CHIP_STM32F407ZE || ARCH_CHIP_STM32F407ZG || ARCH_CHIP_STM32F407IE || ARCH_CHIP_STM32F407IG
+
+choice
+ prompt "Toolchain Selection"
+ default STM32_CODESOURCERYW
+ depends on ARCH_CHIP_STM32
+
+config STM32_CODESOURCERYW
+ bool "CodeSourcery for Windows"
+
+config STM32_CODESOURCERYL
+ bool "CodeSourcery for Linux"
+
+config STM32_ATOLLIC_LITE
+ bool "Atollic Lite for Windows"
+
+config STM32_ATOLLIC_PRO
+ bool "Atollic Pro for Windows"
+
+config STM32_DEVKITARM
+ bool "DevkitARM (Windows)"
+
+config STM32_RAISONANCE
+ bool "STMicro Raisonance for Windows"
+
+config STM32_BUILDROOT
+ bool "NuttX buildroot (Cygwin or Linux)"
+
+endchoice
+
+config STM32_DFU
+ bool "DFU bootloader"
+ default n
+ ---help---
+ Configure and position code for use with the STMicro DFU bootloader. Do
+ not select this option if you will load code using JTAG/SWM.
menu "STM32 Peripheral Support"
@@ -228,7 +263,7 @@ config STM32_SPI4
config STM32_SYSCFG
bool "SYSCFG"
- default n
+ default y
depends on STM32_STM32F20XX || STM32_STM32F40XX
config STM32_TIM1
@@ -517,24 +552,11 @@ config STM32_CCMEXCLUDE
config STM32_FSMC_SRAM
bool "External SRAM on FSMC"
default n
- depends on FSMC
+ depends on STM32_FSMC
+ select ARCH_HAVE_HEAP2
---help---
In addition to internal SRAM, SRAM may also be available through the FSMC.
-config HEAP2_BASE
- hex "FSMC SRAM base address"
- default 0x00000000
- depends on STM32_FSMC_SRAM
- ---help---
- The base address of the SRAM in the FSMC address space.
-
-config HEAP2_END
- hex "FSMC SRAM end+1 address"
- default 0x00000000
- depends on STM32_FSMC_SRAM
- ---help---
- The end (+1) of the SRAM in the FSMC address space
-
config STM32_TIM1_PWM
bool "TIM1 PWM"
default n
@@ -1536,6 +1558,7 @@ config STM32_PHYADDR
config STM32_MII
bool "Use MII interface"
default n
+ depends on STM32_ETHMAC
---help---
Support Ethernet MII interface.
@@ -1549,13 +1572,14 @@ config STM32_MII_MCO2
config STM32_AUTONEG
bool "Use autonegtiation"
default y
+ depends on STM32_ETHMAC
---help---
Use PHY autonegotion to determine speed and mode
config STM32_ETHFD
bool "Full duplex"
default n
- depends on !STM32_AUTONEG
+ depends on STM32_ETHMAC && !STM32_AUTONEG
---help---
If STM32_AUTONEG is not defined, then this may be defined to select full duplex
mode. Default: half-duplex
@@ -1563,7 +1587,7 @@ config STM32_ETHFD
config STM32_ETH100MBPS
bool "100 Mbps"
default n
- depends on !STM32_AUTONEG
+ depends on STM32_ETHMAC && !STM32_AUTONEG
---help---
If STM32_AUTONEG is not defined, then this may be defined to select 100 MBps
speed. Default: 10 Mbps
@@ -1607,6 +1631,7 @@ config STM32_PHYSR_FULLDUPLEX
config STM32_ETH_PTP
bool "Precision Time Protocol (PTP)"
default n
+ depends on STM32_ETHMAC
---help---
Precision Time Protocol (PTP). Not supported but some hooks are indicated
with this condition.
@@ -1616,6 +1641,7 @@ endmenu
config STM32_RMII
bool
default y if !STM32_MII
+ depends on STM32_ETHMAC
config STM32_MII_MCO1
bool
diff --git a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
index 4c186a852..8aa5622c8 100644
--- a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
+++ b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
@@ -73,13 +73,14 @@
*
* CONFIG_STM32_FSMC=y : Enables the FSMC
* CONFIG_STM32_FSMC_SRAM=y : Indicates that SRAM is available via the
- * FSMC (as opposed to an LCD or FLASH).
+ * FSMC (as opposed to an LCD or FLASH).
* CONFIG_HEAP2_BASE : The base address of the SRAM in the FSMC
- * address space
- * CONFIG_HEAP2_END : The end (+1) of the SRAM in the FSMC
- * address space
+ * address space
+ * CONFIG_HEAP2_SIZE : The size of the SRAM in the FSMC
+ * address space
* CONFIG_MM_REGIONS : Must be set to a large enough value to
- * include the FSMC SRAM (as determined by the rules provided below)
+ * include the FSMC SRAM (as determined by
+ * the rules provided below)
*/
#ifndef CONFIG_STM32_FSMC
@@ -256,12 +257,12 @@
/* If FSMC SRAM is going to be used as heap, then verify that the starting
* address and size of the external SRAM region has been provided in the
- * configuration (as CONFIG_HEAP2_BASE and CONFIG_HEAP2_END).
+ * configuration (as CONFIG_HEAP2_BASE and CONFIG_HEAP2_SIZE).
*/
#ifdef CONFIG_STM32_FSMC_SRAM
-# if !defined(CONFIG_HEAP2_BASE) || !defined(CONFIG_HEAP2_END)
-# error "CONFIG_HEAP2_BASE and CONFIG_HEAP2_END must be provided"
+# if !defined(CONFIG_HEAP2_BASE) || !defined(CONFIG_HEAP2_SIZE)
+# error "CONFIG_HEAP2_BASE and CONFIG_HEAP2_SIZE must be provided"
# undef CONFIG_STM32_FSMC_SRAM
# endif
#endif
@@ -317,7 +318,7 @@ void up_addregion(void)
/* Add the external FSMC SRAM heap region. */
#ifdef CONFIG_STM32_FSMC_SRAM
- mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE);
+ mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
#endif
}
#endif
diff --git a/nuttx/arch/z16/src/common/up_allocateheap.c b/nuttx/arch/z16/src/common/up_allocateheap.c
index 62d96e0b3..0b6c766d3 100644
--- a/nuttx/arch/z16/src/common/up_allocateheap.c
+++ b/nuttx/arch/z16/src/common/up_allocateheap.c
@@ -107,6 +107,6 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
#if CONFIG_MM_REGIONS > 1
void up_addregion(void)
{
- mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE);
+ mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
}
#endif
diff --git a/nuttx/arch/z80/src/common/up_allocateheap.c b/nuttx/arch/z80/src/common/up_allocateheap.c
index cb2f55593..368785cf2 100644
--- a/nuttx/arch/z80/src/common/up_allocateheap.c
+++ b/nuttx/arch/z80/src/common/up_allocateheap.c
@@ -109,6 +109,6 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
#if CONFIG_MM_REGIONS > 1
void up_addregion(void)
{
- mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE);
+ mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
}
#endif
diff --git a/nuttx/configs/compal_e99/nsh_compalram/defconfig b/nuttx/configs/compal_e99/nsh_compalram/defconfig
index a52e2aaf0..a60fbf947 100644
--- a/nuttx/configs/compal_e99/nsh_compalram/defconfig
+++ b/nuttx/configs/compal_e99/nsh_compalram/defconfig
@@ -45,8 +45,8 @@ CONFIG_ARCH_BOARD_COMPALE99=y
CONFIG_BOARD_LOOPSPERMSEC=1250
CONFIG_ROM_VECTORS=n
CONFIG_MM_REGIONS=2
-CONFIG_HEAP2_START=0x01000000
-CONFIG_HEAP2_END=0x01200000
+CONFIG_HEAP2_BASE=0x01000000
+CONFIG_HEAP2_SIZE=2097152
CONFIG_ARCH_LEDS=n
CONFIG_ARCH_INTERRUPTSTACK=1024
CONFIG_ARCH_STACKDUMP=y
diff --git a/nuttx/configs/compal_e99/nsh_highram/defconfig b/nuttx/configs/compal_e99/nsh_highram/defconfig
index e5f997ebf..4ed6e486b 100644
--- a/nuttx/configs/compal_e99/nsh_highram/defconfig
+++ b/nuttx/configs/compal_e99/nsh_highram/defconfig
@@ -45,8 +45,8 @@ CONFIG_ARCH_BOARD_COMPALE99=y
CONFIG_BOARD_LOOPSPERMSEC=1250
CONFIG_ROM_VECTORS=n
CONFIG_MM_REGIONS=2
-CONFIG_HEAP2_START=0x01000000
-CONFIG_HEAP2_END=0x01200000
+CONFIG_HEAP2_BASE=0x01000000
+CONFIG_HEAP2_SIZE=2097152
CONFIG_ARCH_LEDS=n
CONFIG_ARCH_INTERRUPTSTACK=1024
CONFIG_ARCH_STACKDUMP=y
diff --git a/nuttx/configs/hymini-stm32v/buttons/defconfig b/nuttx/configs/hymini-stm32v/buttons/defconfig
index 503864319..a5792af4f 100644
--- a/nuttx/configs/hymini-stm32v/buttons/defconfig
+++ b/nuttx/configs/hymini-stm32v/buttons/defconfig
@@ -156,14 +156,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=y
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/hymini-stm32v/nsh/defconfig b/nuttx/configs/hymini-stm32v/nsh/defconfig
index 17aaf9f6c..89d40eb58 100755
--- a/nuttx/configs/hymini-stm32v/nsh/defconfig
+++ b/nuttx/configs/hymini-stm32v/nsh/defconfig
@@ -154,14 +154,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103V specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/hymini-stm32v/nsh2/defconfig b/nuttx/configs/hymini-stm32v/nsh2/defconfig
index 54574b26c..8b835ee27 100644
--- a/nuttx/configs/hymini-stm32v/nsh2/defconfig
+++ b/nuttx/configs/hymini-stm32v/nsh2/defconfig
@@ -159,14 +159,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/hymini-stm32v/nx/defconfig b/nuttx/configs/hymini-stm32v/nx/defconfig
index 2d3d03832..7eeff113e 100644
--- a/nuttx/configs/hymini-stm32v/nx/defconfig
+++ b/nuttx/configs/hymini-stm32v/nx/defconfig
@@ -154,14 +154,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103V specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/hymini-stm32v/nxlines/defconfig b/nuttx/configs/hymini-stm32v/nxlines/defconfig
index 1dc04c013..f2ca2651f 100644
--- a/nuttx/configs/hymini-stm32v/nxlines/defconfig
+++ b/nuttx/configs/hymini-stm32v/nxlines/defconfig
@@ -158,14 +158,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103V specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/hymini-stm32v/usbserial/defconfig b/nuttx/configs/hymini-stm32v/usbserial/defconfig
index 8f0e1f3d4..2f4b27f96 100755
--- a/nuttx/configs/hymini-stm32v/usbserial/defconfig
+++ b/nuttx/configs/hymini-stm32v/usbserial/defconfig
@@ -156,14 +156,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103V specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/hymini-stm32v/usbstorage/defconfig b/nuttx/configs/hymini-stm32v/usbstorage/defconfig
index 85627dfda..33c8b4db3 100755
--- a/nuttx/configs/hymini-stm32v/usbstorage/defconfig
+++ b/nuttx/configs/hymini-stm32v/usbstorage/defconfig
@@ -155,14 +155,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103V specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/kwikstik-k40/ostest/defconfig b/nuttx/configs/kwikstik-k40/ostest/defconfig
index 3f26570ce..400ff8876 100755
--- a/nuttx/configs/kwikstik-k40/ostest/defconfig
+++ b/nuttx/configs/kwikstik-k40/ostest/defconfig
@@ -166,14 +166,6 @@ CONFIG_UART4_PARITY=0
CONFIG_UART5_PARITY=0
#
-# K40X256VLQ100 specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/olimex-stm32-p107/nsh/defconfig b/nuttx/configs/olimex-stm32-p107/nsh/defconfig
index 781dcd64c..18858d5df 100644
--- a/nuttx/configs/olimex-stm32-p107/nsh/defconfig
+++ b/nuttx/configs/olimex-stm32-p107/nsh/defconfig
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/olimex-stm32-p107/ostest/defconfig b/nuttx/configs/olimex-stm32-p107/ostest/defconfig
index ad07b7aa1..5532a921f 100644
--- a/nuttx/configs/olimex-stm32-p107/ostest/defconfig
+++ b/nuttx/configs/olimex-stm32-p107/ostest/defconfig
@@ -186,14 +186,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=y
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=y
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index 0d292565e..8582e95ff 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -362,7 +362,7 @@ The on-board SRAM can be configured by setting
CONFIG_STM32_FSMC=y : Enables the FSMC
CONFIG_STM32_FSMC_SRAM=y : Enable external SRAM support
CONFIG_HEAP2_BASE=0x68000000 : SRAM will be located at 0x680000000
- CONFIG_HEAP2_END=(0x68000000+(1*1024*1024)) : The size of the SRAM is 1Mbyte
+ CONFIG_HEAP2_SIZE=1048576 : The size of the SRAM is 1Mbyte
CONFIG_MM_REGIONS=2 : There will be two memory regions
: in the heap
diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig
index 4d87e2d2c..942f3e4ba 100755
--- a/nuttx/configs/stm3210e-eval/RIDE/defconfig
+++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig
@@ -152,14 +152,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/buttons/defconfig b/nuttx/configs/stm3210e-eval/buttons/defconfig
index 08703af7d..102b09140 100644
--- a/nuttx/configs/stm3210e-eval/buttons/defconfig
+++ b/nuttx/configs/stm3210e-eval/buttons/defconfig
@@ -163,14 +163,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=y
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/composite/defconfig b/nuttx/configs/stm3210e-eval/composite/defconfig
index 16415e793..e79cdb8c0 100755
--- a/nuttx/configs/stm3210e-eval/composite/defconfig
+++ b/nuttx/configs/stm3210e-eval/composite/defconfig
@@ -161,14 +161,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig
index 3aedb6bd5..d5fd9a30c 100755
--- a/nuttx/configs/stm3210e-eval/nsh/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh/defconfig
@@ -161,14 +161,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig
index a9d279051..20e276a6a 100644
--- a/nuttx/configs/stm3210e-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig
@@ -182,14 +182,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/nx/defconfig b/nuttx/configs/stm3210e-eval/nx/defconfig
index 359e70969..7a7eaf1d9 100644
--- a/nuttx/configs/stm3210e-eval/nx/defconfig
+++ b/nuttx/configs/stm3210e-eval/nx/defconfig
@@ -161,14 +161,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/nxconsole/defconfig b/nuttx/configs/stm3210e-eval/nxconsole/defconfig
index 4d30ed8ea..6084a228a 100644
--- a/nuttx/configs/stm3210e-eval/nxconsole/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxconsole/defconfig
@@ -161,14 +161,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/nxlines/defconfig b/nuttx/configs/stm3210e-eval/nxlines/defconfig
index 476f85e5f..554b15f6f 100644
--- a/nuttx/configs/stm3210e-eval/nxlines/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxlines/defconfig
@@ -161,14 +161,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/nxtext/defconfig b/nuttx/configs/stm3210e-eval/nxtext/defconfig
index cef3a6246..4e95c1108 100644
--- a/nuttx/configs/stm3210e-eval/nxtext/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxtext/defconfig
@@ -161,14 +161,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig
index 18239c995..cb9336433 100755
--- a/nuttx/configs/stm3210e-eval/ostest/defconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/defconfig
@@ -162,14 +162,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/pm/defconfig b/nuttx/configs/stm3210e-eval/pm/defconfig
index 48b9e83b3..370399882 100644
--- a/nuttx/configs/stm3210e-eval/pm/defconfig
+++ b/nuttx/configs/stm3210e-eval/pm/defconfig
@@ -192,14 +192,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig
index da13a876d..829e55196 100755
--- a/nuttx/configs/stm3210e-eval/usbserial/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig
@@ -162,14 +162,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3210e-eval/usbstorage/defconfig b/nuttx/configs/stm3210e-eval/usbstorage/defconfig
index 05b5a288f..72ef6cc67 100755
--- a/nuttx/configs/stm3210e-eval/usbstorage/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbstorage/defconfig
@@ -161,14 +161,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM3210E-EVAL specific LCD settings
#
CONFIG_STM32_AM240320_DISABLE=n
diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt
index bbd42cbc9..04585f69f 100644
--- a/nuttx/configs/stm3220g-eval/README.txt
+++ b/nuttx/configs/stm3220g-eval/README.txt
@@ -352,7 +352,7 @@ The on-board SRAM can be configured by setting
CONFIG_STM32_FSMC=y
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
- CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
+ CONFIG_HEAP2_SIZE=2097152
CONFIG_MM_REGIONS=2
Configuration Options
@@ -368,7 +368,7 @@ NuttX configuration file:
FSMC (as opposed to an LCD or FLASH).
CONFIG_HEAP2_BASE : The base address of the SRAM in the FSMC
address space
- CONFIG_HEAP2_END : The end (+1) of the SRAM in the FSMC
+ CONFIG_HEAP2_SIZE : The size of the SRAM in the FSMC
address space
CONFIG_MM_REGIONS : Must be set to a large enough value to
include the FSMC SRAM
@@ -475,9 +475,9 @@ STM3220G-EVAL-specific Configuration Options
CONFIG_STM32_FSMC_SRAM - Indicates that SRAM is available via the
FSMC (as opposed to an LCD or FLASH).
- CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space
+ CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space (hex)
- CONFIG_HEAP2_END - The end (+1) of the SRAM in the FSMC address space
+ CONFIG_HEAP2_SIZE - The size of the SRAM in the FSMC address space (decimal)
CONFIG_ARCH_IRQPRIO - The STM3220xxx supports interrupt prioritization
diff --git a/nuttx/configs/stm3220g-eval/dhcpd/defconfig b/nuttx/configs/stm3220g-eval/dhcpd/defconfig
index d8cac6aab..848121e04 100644
--- a/nuttx/configs/stm3220g-eval/dhcpd/defconfig
+++ b/nuttx/configs/stm3220g-eval/dhcpd/defconfig
@@ -78,7 +78,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F20xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F20xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3220g-eval/nettest/defconfig b/nuttx/configs/stm3220g-eval/nettest/defconfig
index ebd176269..7e660ad02 100644
--- a/nuttx/configs/stm3220g-eval/nettest/defconfig
+++ b/nuttx/configs/stm3220g-eval/nettest/defconfig
@@ -78,7 +78,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F20xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F20xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3220g-eval/nsh/defconfig b/nuttx/configs/stm3220g-eval/nsh/defconfig
index 937ce7686..48912bd8b 100644
--- a/nuttx/configs/stm3220g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3220g-eval/nsh/defconfig
@@ -78,7 +78,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F20xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F20xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3220g-eval/nsh2/defconfig b/nuttx/configs/stm3220g-eval/nsh2/defconfig
index 7e4d8127c..c2ede9c67 100644
--- a/nuttx/configs/stm3220g-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3220g-eval/nsh2/defconfig
@@ -78,7 +78,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F20xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F20xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3220g-eval/nxwm/defconfig b/nuttx/configs/stm3220g-eval/nxwm/defconfig
index cbbdca2e3..6e6933325 100644
--- a/nuttx/configs/stm3220g-eval/nxwm/defconfig
+++ b/nuttx/configs/stm3220g-eval/nxwm/defconfig
@@ -78,7 +78,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=n
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F20xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F20xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3220g-eval/ostest/defconfig b/nuttx/configs/stm3220g-eval/ostest/defconfig
index 1ae110716..d0ace11bc 100644
--- a/nuttx/configs/stm3220g-eval/ostest/defconfig
+++ b/nuttx/configs/stm3220g-eval/ostest/defconfig
@@ -78,7 +78,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F20xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F20xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3220g-eval/telnetd/defconfig b/nuttx/configs/stm3220g-eval/telnetd/defconfig
index f39e104bd..2ff215afc 100644
--- a/nuttx/configs/stm3220g-eval/telnetd/defconfig
+++ b/nuttx/configs/stm3220g-eval/telnetd/defconfig
@@ -78,7 +78,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -184,14 +184,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F20xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F20xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index 15e8b9f3d..151811189 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -451,7 +451,7 @@ The on-board SRAM can be configured by setting
CONFIG_STM32_FSMC=y
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
- CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
+ CONFIG_HEAP2_SIZE=2097152
CONFIG_MM_REGIONS=2 (or =3, see below)
Configuration Options
@@ -472,7 +472,7 @@ present in the NuttX configuration file:
FSMC (as opposed to an LCD or FLASH).
CONFIG_HEAP2_BASE : The base address of the SRAM in the FSMC
address space
- CONFIG_HEAP2_END : The end (+1) of the SRAM in the FSMC
+ CONFIG_HEAP2_SIZE : The size of the SRAM in the FSMC
address space
CONFIG_MM_REGIONS : Must be set to a large enough value to
include the FSMC SRAM
@@ -591,9 +591,9 @@ STM3240G-EVAL-specific Configuration Options
CONFIG_STM32_FSMC_SRAM - Indicates that SRAM is available via the
FSMC (as opposed to an LCD or FLASH).
- CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space
+ CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space (hex)
- CONFIG_HEAP2_END - The end (+1) of the SRAM in the FSMC address space
+ CONFIG_HEAP2_END - The size of the SRAM in the FSMC address space (decimal)
CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
diff --git a/nuttx/configs/stm3240g-eval/dhcpd/defconfig b/nuttx/configs/stm3240g-eval/dhcpd/defconfig
index a8372456f..382ce6155 100644
--- a/nuttx/configs/stm3240g-eval/dhcpd/defconfig
+++ b/nuttx/configs/stm3240g-eval/dhcpd/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/nettest/defconfig b/nuttx/configs/stm3240g-eval/nettest/defconfig
index 500a8ab15..9eb8f3d5c 100644
--- a/nuttx/configs/stm3240g-eval/nettest/defconfig
+++ b/nuttx/configs/stm3240g-eval/nettest/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig
index 4a0246ef4..8b2617ec0 100644
--- a/nuttx/configs/stm3240g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/nsh2/defconfig b/nuttx/configs/stm3240g-eval/nsh2/defconfig
index e9e0c272f..00d9dac0a 100644
--- a/nuttx/configs/stm3240g-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh2/defconfig
@@ -84,7 +84,7 @@ CONFIG_STM32_CCMEXCLUDE=y
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -191,14 +191,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/nxconsole/defconfig b/nuttx/configs/stm3240g-eval/nxconsole/defconfig
index 8413a1b59..172d17b6f 100644
--- a/nuttx/configs/stm3240g-eval/nxconsole/defconfig
+++ b/nuttx/configs/stm3240g-eval/nxconsole/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/nxwm/defconfig b/nuttx/configs/stm3240g-eval/nxwm/defconfig
index de8ebffae..07bc408dc 100644
--- a/nuttx/configs/stm3240g-eval/nxwm/defconfig
+++ b/nuttx/configs/stm3240g-eval/nxwm/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=n
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/ostest/defconfig b/nuttx/configs/stm3240g-eval/ostest/defconfig
index 58b86beea..1f2304730 100644
--- a/nuttx/configs/stm3240g-eval/ostest/defconfig
+++ b/nuttx/configs/stm3240g-eval/ostest/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/telnetd/defconfig b/nuttx/configs/stm3240g-eval/telnetd/defconfig
index 39cde6b0f..44a0f27ba 100644
--- a/nuttx/configs/stm3240g-eval/telnetd/defconfig
+++ b/nuttx/configs/stm3240g-eval/telnetd/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm3240g-eval/webserver/defconfig b/nuttx/configs/stm3240g-eval/webserver/defconfig
index 5c6e573d5..7bd8e52ce 100644
--- a/nuttx/configs/stm3240g-eval/webserver/defconfig
+++ b/nuttx/configs/stm3240g-eval/webserver/defconfig
@@ -83,7 +83,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
CONFIG_STM32_FSMC_SRAM=y
CONFIG_HEAP2_BASE=0x64000000
-CONFIG_HEAP2_END=0x64200000
+CONFIG_HEAP2_SIZE=2097152
#
# Individual subsystems can be enabled:
@@ -190,14 +190,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt
index 93b8fee03..12b30c62c 100755
--- a/nuttx/configs/stm32f4discovery/README.txt
+++ b/nuttx/configs/stm32f4discovery/README.txt
@@ -445,13 +445,13 @@ present in the NuttX configuration file:
CONFIG_STM32_FSMC=y : Enables the FSMC
CONFIG_STM32_FSMC_SRAM=y : Indicates that SRAM is available via the
- FSMC (as opposed to an LCD or FLASH).
+ FSMC (as opposed to an LCD or FLASH).
CONFIG_HEAP2_BASE : The base address of the SRAM in the FSMC
- address space
- CONFIG_HEAP2_END : The end (+1) of the SRAM in the FSMC
- address space
+ address space
+ CONFIG_HEAP2_SIZE : The size of the SRAM in the FSMC
+ address space
CONFIG_MM_REGIONS : Must be set to a large enough value to
- include the FSMC SRAM
+ include the FSMC SRAM
SRAM Configurations
-------------------
@@ -704,9 +704,9 @@ STM32F4Discovery-specific Configuration Options
CONFIG_STM32_FSMC_SRAM - Indicates that SRAM is available via the
FSMC (as opposed to an LCD or FLASH).
- CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space
+ CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space (hex)
- CONFIG_HEAP2_END - The end (+1) of the SRAM in the FSMC address space
+ CONFIG_HEAP2_SIZE - The size of the SRAM in the FSMC address space (decimal)
CONFIG_ARCH_IRQPRIO - The STM32F4Discovery supports interrupt prioritization
diff --git a/nuttx/configs/stm32f4discovery/ostest/defconfig b/nuttx/configs/stm32f4discovery/ostest/defconfig
index c7cee2331..5c120c614 100644
--- a/nuttx/configs/stm32f4discovery/ostest/defconfig
+++ b/nuttx/configs/stm32f4discovery/ostest/defconfig
@@ -179,14 +179,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F40xxx specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# STM32F40xxx specific CAN device driver settings
#
CONFIG_CAN=n
diff --git a/nuttx/configs/twr-k60n512/nsh/defconfig b/nuttx/configs/twr-k60n512/nsh/defconfig
index b9670c398..ca1dbe335 100644
--- a/nuttx/configs/twr-k60n512/nsh/defconfig
+++ b/nuttx/configs/twr-k60n512/nsh/defconfig
@@ -165,14 +165,6 @@ CONFIG_UART4_PARITY=0
CONFIG_UART5_PARITY=0
#
-# K40X256VLQ100 specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/twr-k60n512/ostest/defconfig b/nuttx/configs/twr-k60n512/ostest/defconfig
index 5d5b1245c..1bb41c310 100644
--- a/nuttx/configs/twr-k60n512/ostest/defconfig
+++ b/nuttx/configs/twr-k60n512/ostest/defconfig
@@ -165,14 +165,6 @@ CONFIG_UART4_PARITY=0
CONFIG_UART5_PARITY=0
#
-# K40X256VLQ100 specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=n
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# General build options
#
CONFIG_RRLOAD_BINARY=n
diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig
index 348a67844..0ee46dec0 100755
--- a/nuttx/configs/vsn/nsh/defconfig
+++ b/nuttx/configs/vsn/nsh/defconfig
@@ -3,7 +3,7 @@
#
# Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
# Copyright (c) 2011 Uros Platise. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
# Uros Platise <uros.platise@isotel.eu>
#
# Redistribution and use in source and binary forms, with or without
@@ -182,14 +182,6 @@ CONFIG_UART4_2STOP=0
CONFIG_UART5_2STOP=0
#
-# STM32F103Z specific SSI device driver settings
-#
-CONFIG_SSI0_DISABLE=y
-CONFIG_SSI1_DISABLE=y
-CONFIG_SSI_POLLWAIT=y
-#CONFIG_SSI_TXLIMIT=4
-
-#
# OS support for I2C
#
CONFIG_I2C=y
diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig
index 000217dc5..bf3540138 100644
--- a/nuttx/mm/Kconfig
+++ b/nuttx/mm/Kconfig
@@ -3,15 +3,6 @@
# see misc/tools/kconfig-language.txt.
#
-config MM_REGIONS
- int "Number of memory regions"
- default 1
- ---help---
- If the architecture includes multiple, non-contiguous regions of
- memory to allocate from, this specifies the number of memory regions
- that the memory manager must handle and enables the API
- mm_addregion(start, end);
-
config MM_SMALL
bool "Small memory model"
default n
@@ -24,3 +15,30 @@ config MM_SMALL
have internal SRAM of size less than or equal to 64Kb. In this case,
CONFIG_MM_SMALL can be defined so that those MCUs will also benefit
from the smaller, 16-bit-based allocation overhead.
+
+config MM_REGIONS
+ int "Number of memory regions"
+ default 1
+ ---help---
+ If the architecture includes multiple, non-contiguous regions of
+ memory to allocate from, this specifies the number of memory regions
+ that the memory manager must handle and enables the API
+ mm_addregion(start, end);
+
+config ARCH_HAVE_HEAP2
+ bool
+
+config HEAP2_BASE
+ hex "Start address of second heap region"
+ default 0x00000000
+ depends on ARCH_HAVE_HEAP2
+ ---help---
+ The base address of the second heap region.
+
+config HEAP2_SIZE
+ int "Size of the second heap region"
+ default 0
+ depends on ARCH_HAVE_HEAP2
+ ---help---
+ The size of the second heap region.
+