summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-05-28 19:48:26 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-05-28 19:48:26 +0000
commit2def040cb811a71cf5e59effb304c47897640b5a (patch)
treed5af02e86fca6db39ff126655f20eb43ccacb13e /nuttx/configs
parentf01a56f6ca729b143cb2a65c108fac534bc76f10 (diff)
downloadpx4-nuttx-2def040cb811a71cf5e59effb304c47897640b5a.tar.gz
px4-nuttx-2def040cb811a71cf5e59effb304c47897640b5a.tar.bz2
px4-nuttx-2def040cb811a71cf5e59effb304c47897640b5a.zip
Bring STM3220G-EVAL board configurations to same level as STM3240G-EVAL
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4779 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/stm3220g-eval/Kconfig78
-rw-r--r--nuttx/configs/stm3220g-eval/README.txt485
-rw-r--r--nuttx/configs/stm3220g-eval/dhcpd/defconfig12
-rw-r--r--nuttx/configs/stm3220g-eval/dhcpd/ld.script3
-rw-r--r--nuttx/configs/stm3220g-eval/nettest/defconfig10
-rw-r--r--nuttx/configs/stm3220g-eval/nettest/ld.script3
-rw-r--r--nuttx/configs/stm3220g-eval/nsh/appconfig17
-rw-r--r--nuttx/configs/stm3220g-eval/nsh/defconfig438
-rw-r--r--nuttx/configs/stm3220g-eval/nsh/ld.script3
-rwxr-xr-xnuttx/configs/stm3220g-eval/nsh/setenv.sh2
-rw-r--r--nuttx/configs/stm3220g-eval/nsh2/appconfig4
-rw-r--r--nuttx/configs/stm3220g-eval/nsh2/defconfig12
-rw-r--r--nuttx/configs/stm3220g-eval/nsh2/ld.script3
-rwxr-xr-xnuttx/configs/stm3220g-eval/nsh2/setenv.sh2
-rw-r--r--nuttx/configs/stm3220g-eval/ostest/defconfig35
-rw-r--r--nuttx/configs/stm3220g-eval/ostest/ld.script4
-rwxr-xr-xnuttx/configs/stm3220g-eval/ostest/setenv.sh2
-rw-r--r--nuttx/configs/stm3220g-eval/src/Makefile6
-rw-r--r--nuttx/configs/stm3220g-eval/src/stm3220g-internal.h178
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_cxxinitialize.c155
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_deselectlcd.c98
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_deselectsram.c97
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_extmem.c188
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_lcd.c1210
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_selectlcd.c169
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_selectsram.c194
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_stmpe11.c353
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_usbdev.c103
-rw-r--r--nuttx/configs/stm3220g-eval/telnetd/defconfig9
-rw-r--r--nuttx/configs/stm3220g-eval/telnetd/ld.script3
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt82
-rw-r--r--nuttx/configs/stm3240g-eval/nsh/defconfig3
32 files changed, 3608 insertions, 353 deletions
diff --git a/nuttx/configs/stm3220g-eval/Kconfig b/nuttx/configs/stm3220g-eval/Kconfig
index 7ca890fe8..05f0cc5ea 100644
--- a/nuttx/configs/stm3220g-eval/Kconfig
+++ b/nuttx/configs/stm3220g-eval/Kconfig
@@ -16,4 +16,82 @@ config ARCH_BUTTONS
---help---
"Support interfaces to use buttons provided by the board."
+config STM3220G_LCD
+ bool "Select support for the STM3210E-EVAL LCD"
+ default y
+ depends on STM32_FSMC
+
+choice
+ prompt "STM3220G-EVAL LCD Orientation"
+ default LCD_LANDSCAPE
+ depends on STM3220G_LCD
+
+config LCD_LANDSCAPE
+ bool "320x240 landscape display"
+ ---help---
+ Define for 320x240 display "landscape" support. Default is this 320x240
+ "landscape" orientation.
+
+ For the STM3220G-EVAL board, the edge opposite from the row of buttons
+ is used as the top of the display in this orientation.
+
+config LCD_RLANDSCAPE
+ bool "320x240 reverse landscape display"
+ ---help---
+ Define for 320x240 display "reverse landscape" support. Default is this 320x240
+ "landscape" orientation.
+
+ For the STM3220G-EVAL board, the edge next to the row of buttons
+ is used as the top of the display in this orientation.
+
+config LCD_PORTRAIT
+ bool "240x320 portrait display"
+ ---help---
+ Define for 240x320 display "portrait" orientation support. In this
+ orientation, the STM3210E-EVAL's LCD ribbon cable is at the bottom of
+ the display. Default is 320x240 "landscape" orientation.
+
+ In this orientation, the top of the display is to the left
+ of the buttons (if the board is held so that the buttons are at the
+ botton of the board).
+
+config LCD_RPORTRAIT
+ bool "240x320 reverse portrait display"
+ ---help---
+ Define for 240x320 display "reverse portrait" orientation support. In
+ this orientation, the STM3210E-EVAL's LCD ribbon cable is at the top
+ of the display. Default is 320x240 "landscape" orientation.
+
+ In this orientation, the top of the display is to the right
+ of the buttons (if the board is held so that the buttons are at the
+ botton of the board).
+
+endchoice
+
+config LCD_RDSHIFT
+ int "LCD data shift"
+ default 5
+ depends on STM3220G_LCD
+ ---help---
+ When reading 16-bit gram data, there appears to be a shift in the returned
+ data. This value fixes the offset. Default 5.
+
+config CONFIG_STM32_ILI9320_DISABLE
+ bool "Disable LCD_ILI9320 (and LCD_ILI9321) support"
+ default n
+ depends on STM3220G_LCD
+ ---help---
+ The LCD driver dynamically selects the LCD based on the reported LCD
+ ID value. However, code size can be reduced by suppressing support for
+ individual LCDs using this option.
+
+config CONFIG_STM32_ILI9325_DISABLE
+ bool "Disable LCD_ILI9325 support"
+ default n
+ depends on STM3220G_LCD
+ ---help---
+ The LCD driver dynamically selects the LCD based on the reported LCD
+ ID value. However, code size can be reduced by suppressing support for
+ individual LCDs using this option
+
endif
diff --git a/nuttx/configs/stm3220g-eval/README.txt b/nuttx/configs/stm3220g-eval/README.txt
index 327280050..b8f4f7bf3 100644
--- a/nuttx/configs/stm3220g-eval/README.txt
+++ b/nuttx/configs/stm3220g-eval/README.txt
@@ -17,6 +17,7 @@ Contents
- PWM
- CAN
- FSMC SRAM
+ - I/O Expanders
- STM3220G-EVAL-specific Configuration Options
- Configurations
@@ -38,7 +39,7 @@ GNU Toolchain Options
toolchain options.
1. The CodeSourcery GNU toolchain,
- 2. The Atollic Toolchain,
+ 2. The Atollic Toolchain,
3. The devkitARM GNU toolchain,
4. Raisonance GNU toolchain, or
5. The NuttX buildroot Toolchain (see below).
@@ -120,7 +121,7 @@ GNU Toolchain Options
In order to compile successfully. Otherwise, you will get errors like:
"C++ Compiler only available in TrueSTUDIO Professional"
-
+
The make may then fail in some of the post link processing because of some of
the other missing tools. The Make.defs file replaces the ar and nm with
the default system x86 tool versions and these seem to work okay. Disable all
@@ -228,17 +229,17 @@ defined. In that case, the usage by the board port is defined in
include/board.h and src/up_leds.c. The LEDs are used to encode OS-related\
events as follows:
- SYMBOL Meaning LED1* LED2 LED3 LED4
- ------------------- ----------------------- ------- ------- ------- ------
- LED_STARTED NuttX has been started ON OFF OFF OFF
- LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
- LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
- LED_STACKCREATED Idle stack created OFF OFF ON OFF
- LED_INIRQ In an interrupt** ON N/C N/C OFF
- LED_SIGNAL In a signal handler*** N/C ON N/C OFF
- LED_ASSERTION An assertion failed ON ON N/C OFF
- LED_PANIC The system has crashed N/C N/C N/C ON
- LED_IDLE STM32 is is sleep mode (Optional, not used)
+ SYMBOL Meaning LED1* LED2 LED3 LED4
+ ------------------- ----------------------- ------- ------- ------- ------
+ LED_STARTED NuttX has been started ON OFF OFF OFF
+ LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
+ LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
+ LED_STACKCREATED Idle stack created OFF OFF ON OFF
+ LED_INIRQ In an interrupt** ON N/C N/C OFF
+ LED_SIGNAL In a signal handler*** N/C ON N/C OFF
+ LED_ASSERTION An assertion failed ON ON N/C OFF
+ LED_PANIC The system has crashed N/C N/C N/C ON
+ LED_IDLE STM32 is is sleep mode (Optional, not used)
* If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot
and these LEDs will give you some indication of where the failure was
@@ -331,64 +332,145 @@ Configuration Options:
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
dump of all CAN registers.
+FSMC SRAM
+=========
+
+On-board SRAM
+-------------
+
+A 16 Mbit SRAM is connected to the STM32F407IGH6 FSMC bus which shares the same
+I/Os with the CAN1 bus. Jumper settings:
+
+ JP1: Connect PE4 to SRAM as A20
+ JP2: onnect PE3 to SRAM as A19
+
+JP3 and JP10 must not be fitted for SRAM and LCD application. JP3 and JP10
+select CAN1 or CAN2 if fitted; neither if not fitted.
+
+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_MM_REGIONS=2
+
+Configuration Options
+---------------------
+
+Internal SRAM is available in all members of the STM32 family. In addition
+to internal SRAM, SRAM may also be available through the FSMC. In order to
+use FSMC SRAM, the following additional things need to be 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).
+ 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
+ CONFIG_MM_REGIONS : Must be set to a large enough value to
+ include the FSMC SRAM
+
+SRAM Configurations
+-------------------
+There are 2 possible SRAM configurations:
+
+ Configuration 1. System SRAM (only)
+ CONFIG_MM_REGIONS == 1
+ Configuration 2. System SRAM and FSMC SRAM
+ CONFIG_MM_REGIONS == 2
+ CONFIG_STM32_FSMC_SRAM defined
+
+I/O Expanders
+=============
+
+The STM3220G-EVAL has two STMPE11QTR I/O expanders on board both connected to
+the STM32 via I2C1. They share a common interrupt line: PI2.
+
+STMPE11 U24, I2C address 0x41 (7-bit)
+------ ---- ---------------- --------------------------------------------
+STPE11 PIN BOARD SIGNAL BOARD CONNECTION
+------ ---- ---------------- --------------------------------------------
+ Y- TouchScreen_Y- LCD Connector XL
+ X- TouchScreen_X- LCD Connector XR
+ Y+ TouchScreen_Y+ LCD Connector XD
+ X+ TouchScreen_X+ LCD Connector XU
+ IN3 EXP_IO9
+ IN2 EXP_IO10
+ IN1 EXP_IO11
+ IN0 EXP_IO12
+
+STMPE11 U29, I2C address 0x44 (7-bit)
+------ ---- ---------------- --------------------------------------------
+STPE11 PIN BOARD SIGNAL BOARD CONNECTION
+------ ---- ---------------- --------------------------------------------
+ Y- EXP_IO1
+ X- EXP_IO2
+ Y+ EXP_IO3
+ X+ EXP_IO4
+ IN3 EXP_IO5
+ IN2 EXP_IO6
+ IN1 EXP_IO7
+ IN0 EXP_IO8
+
STM3220G-EVAL-specific Configuration Options
============================================
- CONFIG_ARCH - Identifies the arch/ subdirectory. This should
- be set to:
+ CONFIG_ARCH - Identifies the arch/ subdirectory. This should
+ be set to:
- CONFIG_ARCH=arm
+ CONFIG_ARCH=arm
- CONFIG_ARCH_family - For use in C code:
+ CONFIG_ARCH_family - For use in C code:
- CONFIG_ARCH_ARM=y
+ CONFIG_ARCH_ARM=y
- CONFIG_ARCH_architecture - For use in C code:
+ CONFIG_ARCH_architecture - For use in C code:
- CONFIG_ARCH_CORTEXM3=y
+ CONFIG_ARCH_CORTEXM3=y
- CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+ CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
- CONFIG_ARCH_CHIP=stm32
+ CONFIG_ARCH_CHIP=stm32
- CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
- chip:
+ CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
+ chip:
- CONFIG_ARCH_CHIP_STM32F207IG=y
+ CONFIG_ARCH_CHIP_STM32F207IG=y
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock
configuration features.
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n
- CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
- hence, the board that supports the particular chip or SoC.
-
- CONFIG_ARCH_BOARD=stm3220g_eval (for the STM3220G-EVAL development board)
+ CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
+ hence, the board that supports the particular chip or SoC.
- CONFIG_ARCH_BOARD_name - For use in C code
+ CONFIG_ARCH_BOARD=stm3220g_eval (for the STM3220G-EVAL development board)
- CONFIG_ARCH_BOARD_STM3220G_EVAL=y
+ CONFIG_ARCH_BOARD_name - For use in C code
- CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
- of delay loops
+ CONFIG_ARCH_BOARD_STM3220G_EVAL=y
- CONFIG_ENDIAN_BIG - define if big endian (default is little
- endian)
+ CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
+ of delay loops
- CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case):
+ CONFIG_ENDIAN_BIG - define if big endian (default is little
+ endian)
- CONFIG_DRAM_SIZE=0x00010000 (64Kb)
+ CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case):
- CONFIG_DRAM_START - The start address of installed DRAM
+ CONFIG_DRAM_SIZE=0x00010000 (64Kb)
- CONFIG_DRAM_START=0x20000000
+ CONFIG_DRAM_START - The start address of installed DRAM
- CONFIG_DRAM_END - Last address+1 of installed RAM
+ CONFIG_DRAM_START=0x20000000
- CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
+ CONFIG_DRAM_END - Last address+1 of installed RAM
- CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP
+ CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
In addition to internal SRAM, SRAM may also be available through the FSMC.
In order to use FSMC SRAM, the following additional things need to be
@@ -405,92 +487,91 @@ STM3220G-EVAL-specific Configuration Options
CONFIG_ARCH_IRQPRIO=y
- CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
- have LEDs
+ CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
+ have LEDs
- CONFIG_ARCH_INTERRUPTSTACK - 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.
+ CONFIG_ARCH_INTERRUPTSTACK - 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.
- CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+ CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
- CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+ CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
- CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
- cause a 100 second delay during boot-up. This 100 second delay
- serves no purpose other than it allows you to calibratre
- CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure
- the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
- the delay actually is 100 seconds.
+ CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+ cause a 100 second delay during boot-up. This 100 second delay
+ serves no purpose other than it allows you to calibratre
+ CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure
+ the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
+ the delay actually is 100 seconds.
Individual subsystems can be enabled:
- AHB1
- ----
- CONFIG_STM32_CRC
- CONFIG_STM32_BKPSRAM
- CONFIG_STM32_CCMDATARAM
- CONFIG_STM32_DMA1
- CONFIG_STM32_DMA2
- CONFIG_STM32_ETHMAC
- CONFIG_STM32_OTGHS
-
- AHB2
- ----
- CONFIG_STM32_DCMI
- CONFIG_STM32_CRYP
- CONFIG_STM32_HASH
- CONFIG_STM32_RNG
- CONFIG_STM32_OTGFS
-
- AHB3
- ----
- CONFIG_STM32_FSMC
-
- APB1
- ----
- CONFIG_STM32_TIM2
- CONFIG_STM32_TIM3
- CONFIG_STM32_TIM4
- CONFIG_STM32_TIM5
- CONFIG_STM32_TIM6
- CONFIG_STM32_TIM7
- CONFIG_STM32_TIM12
- CONFIG_STM32_TIM13
- CONFIG_STM32_TIM14
- CONFIG_STM32_WWDG
- CONFIG_STM32_IWDG
- CONFIG_STM32_SPI2
- CONFIG_STM32_SPI3
- CONFIG_STM32_USART2
- CONFIG_STM32_USART3
- CONFIG_STM32_UART4
- CONFIG_STM32_UART5
- CONFIG_STM32_I2C1
- CONFIG_STM32_I2C2
- CONFIG_STM32_I2C3
- CONFIG_STM32_CAN1
- CONFIG_STM32_CAN2
- CONFIG_STM32_DAC1
- CONFIG_STM32_DAC2
- CONFIG_STM32_PWR -- Required for RTC
-
- APB2
- ----
- CONFIG_STM32_TIM1
- CONFIG_STM32_TIM8
- CONFIG_STM32_USART1
- CONFIG_STM32_USART6
- CONFIG_STM32_ADC1
- CONFIG_STM32_ADC2
- CONFIG_STM32_ADC3
- CONFIG_STM32_SDIO
- CONFIG_STM32_SPI1
- CONFIG_STM32_SYSCFG
- CONFIG_STM32_TIM9
- CONFIG_STM32_TIM10
- CONFIG_STM32_TIM11
+ AHB1
+ ----
+ CONFIG_STM32_CRC
+ CONFIG_STM32_BKPSRAM
+ CONFIG_STM32_DMA1
+ CONFIG_STM32_DMA2
+ CONFIG_STM32_ETHMAC
+ CONFIG_STM32_OTGHS
+
+ AHB2
+ ----
+ CONFIG_STM32_DCMI
+ CONFIG_STM32_CRYP
+ CONFIG_STM32_HASH
+ CONFIG_STM32_RNG
+ CONFIG_STM32_OTGFS
+
+ AHB3
+ ----
+ CONFIG_STM32_FSMC
+
+ APB1
+ ----
+ CONFIG_STM32_TIM2
+ CONFIG_STM32_TIM3
+ CONFIG_STM32_TIM4
+ CONFIG_STM32_TIM5
+ CONFIG_STM32_TIM6
+ CONFIG_STM32_TIM7
+ CONFIG_STM32_TIM12
+ CONFIG_STM32_TIM13
+ CONFIG_STM32_TIM14
+ CONFIG_STM32_WWDG
+ CONFIG_STM32_IWDG
+ CONFIG_STM32_SPI2
+ CONFIG_STM32_SPI3
+ CONFIG_STM32_USART2
+ CONFIG_STM32_USART3
+ CONFIG_STM32_UART4
+ CONFIG_STM32_UART5
+ CONFIG_STM32_I2C1
+ CONFIG_STM32_I2C2
+ CONFIG_STM32_I2C3
+ CONFIG_STM32_CAN1
+ CONFIG_STM32_CAN2
+ CONFIG_STM32_DAC1
+ CONFIG_STM32_DAC2
+ CONFIG_STM32_PWR -- Required for RTC
+
+ APB2
+ ----
+ CONFIG_STM32_TIM1
+ CONFIG_STM32_TIM8
+ CONFIG_STM32_USART1
+ CONFIG_STM32_USART6
+ CONFIG_STM32_ADC1
+ CONFIG_STM32_ADC2
+ CONFIG_STM32_ADC3
+ CONFIG_STM32_SDIO
+ CONFIG_STM32_SPI1
+ CONFIG_STM32_SYSCFG
+ CONFIG_STM32_TIM9
+ CONFIG_STM32_TIM10
+ CONFIG_STM32_TIM11
Timer and I2C devices may need to the following to force power to be applied
unconditionally at power up. (Otherwise, the device is powered when it is
@@ -506,16 +587,16 @@ STM3220G-EVAL-specific Configuration Options
to assign the timer (n) for used by the ADC or DAC, but then you also have to
configure which ADC or DAC (m) it is assigned to.
- CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,14
- CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,14
- CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,14, m=1,..,3
- CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,14
- CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,14, m=1,..,2
+ CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,14
+ CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,14
+ CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,14, m=1,..,3
+ CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,14
+ CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,14, m=1,..,2
For each timer that is enabled for PWM usage, we need the following additional
configuration settings:
- CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
+ CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
NOTE: The STM32 timers are each capable of generating different signals on
each of the four channels with different duty cycles. That capability is
@@ -523,78 +604,78 @@ STM3220G-EVAL-specific Configuration Options
JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
- CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
- CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
- but without JNTRST.
- CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+ CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+ CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+ but without JNTRST.
+ CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
STM3220xxx specific device driver settings
- CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART
+ CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART
m (m=4,5) for the console and ttys0 (default is the USART1).
- CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received.
- This specific the size of the receive buffer
- CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before
- being sent. This specific the size of the transmit buffer
- CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be
- CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8.
- CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
- CONFIG_U[S]ARTn_2STOP - Two stop bits
-
- CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI
- support. Non-interrupt-driven, poll-waiting is recommended if the
- interrupt rate would be to high in the interrupt driven case.
- CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance.
- Cannot be used with CONFIG_STM32_SPI_INTERRUPT.
-
- CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
- and CONFIG_STM32_DMA2.
- CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128
- CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
- Default: Medium
- CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
- 4-bit transfer mode.
-
- CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
- CONFIG_STM32_MII - Support Ethernet MII interface
- CONFIG_STM32_MII_MCO1 - Use MCO1 to clock the MII interface
- CONFIG_STM32_MII_MCO2 - Use MCO2 to clock the MII interface
- CONFIG_STM32_RMII - Support Ethernet RMII interface
- CONFIG_STM32_AUTONEG - Use PHY autonegotion to determine speed and mode
- CONFIG_STM32_ETHFD - If CONFIG_STM32_AUTONEG is not defined, then this
- may be defined to select full duplex mode. Default: half-duplex
- CONFIG_STM32_ETH100MBPS - If CONFIG_STM32_AUTONEG is not defined, then this
- may be defined to select 100 MBps speed. Default: 10 Mbps
- CONFIG_STM32_PHYSR - This must be provided if CONFIG_STM32_AUTONEG is
- defined. The PHY status register address may diff from PHY to PHY. This
- configuration sets the address of the PHY status register.
- CONFIG_STM32_PHYSR_SPEED - This must be provided if CONFIG_STM32_AUTONEG is
- defined. This provides bit mask indicating 10 or 100MBps speed.
- CONFIG_STM32_PHYSR_100MBPS - This must be provided if CONFIG_STM32_AUTONEG is
- defined. This provides the value of the speed bit(s) indicating 100MBps speed.
- CONFIG_STM32_PHYSR_MODE - This must be provided if CONFIG_STM32_AUTONEG is
- defined. This provide bit mask indicating full or half duplex modes.
- CONFIG_STM32_PHYSR_FULLDUPLEX - This must be provided if CONFIG_STM32_AUTONEG is
- defined. This provides the value of the mode bits indicating full duplex mode.
- CONFIG_STM32_ETH_PTP - Precision Time Protocol (PTP). Not supported
- but some hooks are indicated with this condition.
+ CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received.
+ This specific the size of the receive buffer
+ CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before
+ being sent. This specific the size of the transmit buffer
+ CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be
+ CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8.
+ CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+ CONFIG_U[S]ARTn_2STOP - Two stop bits
+
+ CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI
+ support. Non-interrupt-driven, poll-waiting is recommended if the
+ interrupt rate would be to high in the interrupt driven case.
+ CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance.
+ Cannot be used with CONFIG_STM32_SPI_INTERRUPT.
+
+ CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
+ and CONFIG_STM32_DMA2.
+ CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128
+ CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
+ Default: Medium
+ CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
+ 4-bit transfer mode.
+
+ CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
+ CONFIG_STM32_MII - Support Ethernet MII interface
+ CONFIG_STM32_MII_MCO1 - Use MCO1 to clock the MII interface
+ CONFIG_STM32_MII_MCO2 - Use MCO2 to clock the MII interface
+ CONFIG_STM32_RMII - Support Ethernet RMII interface
+ CONFIG_STM32_AUTONEG - Use PHY autonegotion to determine speed and mode
+ CONFIG_STM32_ETHFD - If CONFIG_STM32_AUTONEG is not defined, then this
+ may be defined to select full duplex mode. Default: half-duplex
+ CONFIG_STM32_ETH100MBPS - If CONFIG_STM32_AUTONEG is not defined, then this
+ may be defined to select 100 MBps speed. Default: 10 Mbps
+ CONFIG_STM32_PHYSR - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. The PHY status register address may diff from PHY to PHY. This
+ configuration sets the address of the PHY status register.
+ CONFIG_STM32_PHYSR_SPEED - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provides bit mask indicating 10 or 100MBps speed.
+ CONFIG_STM32_PHYSR_100MBPS - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provides the value of the speed bit(s) indicating 100MBps speed.
+ CONFIG_STM32_PHYSR_MODE - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provide bit mask indicating full or half duplex modes.
+ CONFIG_STM32_PHYSR_FULLDUPLEX - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provides the value of the mode bits indicating full duplex mode.
+ CONFIG_STM32_ETH_PTP - Precision Time Protocol (PTP). Not supported
+ but some hooks are indicated with this condition.
STM3220G-EVAL CAN Configuration
- CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
- CONFIG_STM32_CAN2 must also be defined)
- CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
- Default: 8
- CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
- Default: 4
- CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback
- mode for testing. The STM32 CAN driver does support loopback mode.
- CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
- CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
- CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
- CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
- CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
- dump of all CAN registers.
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+ CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback
+ mode for testing. The STM32 CAN driver does support loopback mode.
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+ CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
+ CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
+ CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
+ dump of all CAN registers.
STM3220G-EVAL LCD Hardware Configuration
@@ -604,10 +685,10 @@ Configurations
Each STM3220G-EVAL configuration is maintained in a sudirectory and
can be selected as follow:
- cd tools
- ./configure.sh stm3220g-eval/<subdir>
- cd -
- . ./setenv.sh
+ cd tools
+ ./configure.sh stm3220g-eval/<subdir>
+ cd -
+ . ./setenv.sh
Where <subdir> is one of the following:
@@ -777,17 +858,7 @@ Where <subdir> is one of the following:
3. This configuration requires that jumper JP22 be set to enable SDIO operation.
- 4. In order to use SDIO without overruns, DMA must be used. The STM32 F4
- has 192Kb of SRAM in two banks: 112Kb of "system" SRAM located at
- 0x2000:0000 and 64Kb of "CCM" SRAM located at 0x1000:0000. It appears
- that you cannot perform DMA from CCM SRAM. The work around that I have now
- is simply to omit the 64Kb of CCM SRAM from the heap so that all memory is
- allocated from System SRAM. This is done by setting:
-
- CONFIG_MM_REGIONS=1
-
- Then DMA works fine. The downside is, of course, is that we lose 64Kb
- of precious SRAM.
+ 4. In order to use SDIO without overruns, DMA must be used.
5. Another SDIO/DMA issue. This one is probably a software bug. This is
the bug as stated in the TODO list:
diff --git a/nuttx/configs/stm3220g-eval/dhcpd/defconfig b/nuttx/configs/stm3220g-eval/dhcpd/defconfig
index a054711c6..192628a5d 100644
--- a/nuttx/configs/stm3220g-eval/dhcpd/defconfig
+++ b/nuttx/configs/stm3220g-eval/dhcpd/defconfig
@@ -64,7 +64,7 @@
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
-# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
@@ -118,15 +118,6 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
-# On-chip CCM SRAM configuration
-#
-# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
-# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
-# being a part of the stack.
-#
-CONFIG_STM32_CCMEXCLUDE=y
-
-#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -148,7 +139,6 @@ CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
# AHB1:
CONFIG_STM32_CRC=n
CONFIG_STM32_BKPSRAM=n
-CONFIG_STM32_CCMDATARAM=n
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=n
CONFIG_STM32_ETHMAC=y
diff --git a/nuttx/configs/stm3220g-eval/dhcpd/ld.script b/nuttx/configs/stm3220g-eval/dhcpd/ld.script
index 2603253c8..a264f2442 100644
--- a/nuttx/configs/stm3220g-eval/dhcpd/ld.script
+++ b/nuttx/configs/stm3220g-eval/dhcpd/ld.script
@@ -34,11 +34,10 @@
****************************************************************************/
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
+ * 128Kb of SRAM. SRAM is split up into two blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
- * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
diff --git a/nuttx/configs/stm3220g-eval/nettest/defconfig b/nuttx/configs/stm3220g-eval/nettest/defconfig
index 21d673ab7..deee0e789 100644
--- a/nuttx/configs/stm3220g-eval/nettest/defconfig
+++ b/nuttx/configs/stm3220g-eval/nettest/defconfig
@@ -118,15 +118,6 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
-# On-chip CCM SRAM configuration
-#
-# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
-# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
-# being a part of the stack.
-#
-CONFIG_STM32_CCMEXCLUDE=y
-
-#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -148,7 +139,6 @@ CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
# AHB1:
CONFIG_STM32_CRC=n
CONFIG_STM32_BKPSRAM=n
-CONFIG_STM32_CCMDATARAM=n
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=n
CONFIG_STM32_ETHMAC=y
diff --git a/nuttx/configs/stm3220g-eval/nettest/ld.script b/nuttx/configs/stm3220g-eval/nettest/ld.script
index 5f5d84794..893ae1d66 100644
--- a/nuttx/configs/stm3220g-eval/nettest/ld.script
+++ b/nuttx/configs/stm3220g-eval/nettest/ld.script
@@ -34,11 +34,10 @@
****************************************************************************/
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
+ * 128Kb of SRAM. SRAM is split up into two blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
- * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
diff --git a/nuttx/configs/stm3220g-eval/nsh/appconfig b/nuttx/configs/stm3220g-eval/nsh/appconfig
index f5c37dfae..e74f5abc0 100644
--- a/nuttx/configs/stm3220g-eval/nsh/appconfig
+++ b/nuttx/configs/stm3220g-eval/nsh/appconfig
@@ -76,6 +76,14 @@ ifeq ($(CONFIG_I2C),y)
CONFIGURED_APPS += system/i2c
endif
+ifeq ($(CONFIG_WATCHDOG),y)
+CONFIGURED_APPS += examples/watchdog
+endif
+
+ifeq ($(CONFIG_INPUT_STMPE11),y)
+CONFIGURED_APPS += examples/touchscreen
+endif
+
# Uncomment examples/ftpc to include the FTP client example
# Uncomment examples/ftpd to include the FTP daemon example
@@ -83,3 +91,12 @@ ifeq ($(CONFIG_NET),y)
#CONFIGURED_APPS += examples/ftpc
#CONFIGURED_APPS += examples/ftpd
endif
+
+# Uncomment to select a graphics example
+
+ifeq ($(CONFIG_NX),y)
+#CONFIGURED_APPS += examples/nx
+#CONFIGURED_APPS += examples/nxhello
+#CONFIGURED_APPS += examples/nximage
+#CONFIGURED_APPS += examples/nxlines
+endif
diff --git a/nuttx/configs/stm3220g-eval/nsh/defconfig b/nuttx/configs/stm3220g-eval/nsh/defconfig
index e21453321..f226d0524 100644
--- a/nuttx/configs/stm3220g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3220g-eval/nsh/defconfig
@@ -64,7 +64,7 @@
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
-# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
@@ -118,15 +118,6 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
-# On-chip CCM SRAM configuration
-#
-# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
-# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
-# being a part of the stack.
-#
-CONFIG_STM32_CCMEXCLUDE=y
-
-#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -148,7 +139,6 @@ CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
# AHB1:
CONFIG_STM32_CRC=n
CONFIG_STM32_BKPSRAM=n
-CONFIG_STM32_CCMDATARAM=n
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=n
CONFIG_STM32_ETHMAC=y
@@ -512,9 +502,9 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
#
#CONFIG_APPS_DIR=
-CONFIG_DEBUG=y
-CONFIG_DEBUG_VERBOSE=y
-CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_DEBUG_SYMBOLS=n
CONFIG_DEBUG_FS=n
CONFIG_DEBUG_GRAPHICS=n
CONFIG_DEBUG_LCD=n
@@ -525,7 +515,9 @@ CONFIG_DEBUG_ANALOG=n
CONFIG_DEBUG_PWM=n
CONFIG_DEBUG_CAN=n
CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
CONFIG_DEBUG_DMA=n
+
CONFIG_HAVE_CXX=n
CONFIG_HAVE_CXXINITIALIZE=n
CONFIG_MM_REGIONS=1
@@ -550,7 +542,7 @@ CONFIG_SDCLONE_DISABLE=y
CONFIG_SCHED_WORKQUEUE=n
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=(50*1000)
-CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SCHED_WORKSTACKSIZE=2048
CONFIG_SIG_SIGWORK=4
CONFIG_SCHED_WAITPID=y
CONFIG_SCHED_ATEXIT=n
@@ -946,6 +938,74 @@ CONFIG_RTC_FREQUENCY=n
CONFIG_RTC_ALARM=n
#
+# Input device configuration
+#
+CONFIG_INPUT=n
+CONFIG_INPUT_TSC2007=n
+
+#
+# STMPE11 input device configuration
+#
+# Prerequisites: CONFIG_INPUT=y
+# Other settings that effect the driver: CONFIG_DISABLE_POLL
+#
+# CONFIG_INPUT_STMPE11
+# Enables support for the STMPE11 driver (Needs CONFIG_INPUT)
+# CONFIG_STMPE11_SPI
+# Enables support for the SPI interface (not currenly supported)
+# CONFIG_STMPE11_I2C
+# Enables support for the I2C interface
+# CONFIG_STMPE11_MULTIPLE
+# Can be defined to support multiple STMPE11 devices on board.
+# CONFIG_STMPE11_ACTIVELOW
+# Interrupt is generated by an active low signal (or falling edge).
+# CONFIG_STMPE11_EDGE
+# Interrupt is generated on an edge (vs. on the active level)
+# CONFIG_STMPE11_NPOLLWAITERS
+# Maximum number of threads that can be waiting on poll() (ignored if
+# CONFIG_DISABLE_POLL is set).
+# CONFIG_STMPE11_TSC_DISABLE
+# Disable driver touchscreen functionality.
+# CONFIG_STMPE11_ADC_DISABLE
+# Disable driver ADC functionality.
+# CONFIG_STMPE11_GPIO_DISABLE
+# Disable driver GPIO functionality.
+# CONFIG_STMPE11_GPIOINT_DISABLE
+# Disable driver GPIO interrupt functionality (ignored if GPIO functionality is
+# disabled).
+# CONFIG_STMPE11_SWAPXY
+# Reverse the meaning of X and Y to handle different LCD orientations.
+# For the STM3220G-EVAL, X and Y should be swapped in PORTRAIT modes
+# CONFIG_STMPE11_TEMP_DISABLE
+# Disable driver temperature sensor functionality.
+# CONFIG_STMPE11_REGDBUG
+# Enabled very low register-level debug output. Requires CONFIG_DEBUG.
+# CONFIG_STMPE11_THRESHX and CONFIG_STMPE11_THRESHY
+# STMPE11 touchscreen data comes in a a very high rate. New touch positions
+# will only be reported when the X or Y data changes by these thresholds.
+# This trades reduces data rate for some loss in dragging accuracy. The
+# STMPE11 is configure for 12-bit values so the raw ranges are 0-4095. So
+# for example, if your display is 320x240, then THRESHX=13 and THRESHY=17
+# would correspond to one pixel. Default: 12
+#
+CONFIG_INPUT_STMPE11=n
+CONFIG_STMPE11_SPI=n
+CONFIG_STMPE11_I2C=y
+CONFIG_STMPE11_MULTIPLE=y
+CONFIG_STMPE11_ACTIVELOW=y
+CONFIG_STMPE11_EDGE=y
+#CONFIG_STMPE11_NPOLLWAITERS
+CONFIG_STMPE11_TSC_DISABLE=n
+CONFIG_STMPE11_ADC_DISABLE=y
+CONFIG_STMPE11_GPIO_DISABLE=y
+CONFIG_STMPE11_GPIOINT_DISABLE=y
+CONFIG_STMPE11_SWAPXY=y
+CONFIG_STMPE11_TEMP_DISABLE=y
+CONFIG_STMPE11_REGDEBUG=n
+CONFIG_STMPE11_THRESHX=26
+CONFIG_STMPE11_THRESHY=34
+
+#
# USB Device Configuration
#
# CONFIG_USBDEV
@@ -1092,11 +1152,11 @@ CONFIG_WATCHDOG=n
# CONFIG_NXTK_BORDERWIDTH
# Specifies with with of the border (in pixels) used with
# framed windows. The default is 4.
-# CONFIG_NXTK_BORDERCOLOR1 and CONFIG_NXTK_BORDERCOLOR2
+# CONFIG_NXTK_BORDERCOLOR1, CONFIG_NXTK_BORDERCOLOR2, CONFIG_NXTK_BORDERCOLOR3
# Specify the colors of the border used with framed windows.
-# CONFIG_NXTK_BORDERCOLOR2 is the shadow side color and so
-# is normally darker. The default is medium and dark grey,
-# respectively
+# CONFIG_NXTK_BORDERCOLOR2 is the shadow side color and so is normally darker.
+# CONFIG_NXTK_BORDERCOLOR3 is the shiny side color and so is normally brighter.
+# The default is mediumdark grey, and light grey, respectively
# CONFIG_NXTK_AUTORAISE
# If set, a window will be raised to the top if the mouse position
# is over a visible portion of the window. Default: A mouse
@@ -1210,6 +1270,76 @@ CONFIG_NX_MXSERVERMSGS=32
CONFIG_NX_MXCLIENTMSGS=16
#
+# NxConsole Configuration Settings:
+#
+# CONFIG_NXCONSOLE
+# Enables building of the NxConsole driver.
+# CONFIG_NXCONSOLE_BPP
+# Currently, NxConsole supports only a single pixel depth. This
+# configuration setting must be provided to support that single pixel depth.
+# Default: The smallest enabled pixel depth. (see CONFIG_NX_DISABLE_*BPP)
+# CONFIG_NXCONSOLE_MXCHARS
+# NxConsole needs to remember every character written to the console so
+# that it can redraw the window. This setting determines the size of some
+# internal memory allocations used to hold the character data. Default: 128.
+# CONFIG_NXCONSOLE_CACHESIZE
+# NxConsole supports caching of rendered fonts. This font caching is required
+# for two reasons: (1) First, it improves text performance, but more
+# importantly (2) it preserves the font memory. Since the NX server runs on
+# a separate server thread, it requires that the rendered font memory persist
+# until the server has a chance to render the font. (NOTE: There is still
+# inherently a race condition in this!). Unfortunately, the font cache would
+# be quite large if all fonts were saved. The CONFIG_NXCONSOLE_CACHESIZE setting
+# will control the size of the font cache (in number of glyphs). Only that
+# number of the most recently used glyphs will be retained. Default: 16.
+# CONFIG_NXCONSOLE_LINESEPARATION
+# This the space (in rows) between each row of test. Default: 2
+# CONFIG_NXCONSOLE_NOWRAP
+# By default, lines will wrap when the test reaches the right hand side
+# of the window. This setting can be defining to change this behavior so
+# that the text is simply truncated until a new line is encountered.
+#
+CONFIG_NXCONSOLE=n
+CONFIG_NXCONSOLE_BPP=16
+CONFIG_NXCONSOLE_MXCHARS=256
+CONFIG_NXCONSOLE_CACHESIZE=32
+# CONFIG_NXCONSOLE_LINESEPARATION
+# CONFIG_NXCONSOLE_NOWRAP
+
+#
+# STM3220G-EVAL LCD Hardware Configuration
+#
+# CONFIG_LCD_NOGETRUN
+# NX components need to know if it can read from the LCD or not. If reading
+# from the LCD is supported, then NxConsole can do more efficient
+# scrolling. Default: Supported
+# CONFIG_LCD_LANDSCAPE - Define for 320x240 display "landscape"
+# support. Default is this 320x240 "landscape" orientation
+# CONFIG_LCD_RLANDSCAPE - Define for 320x240 display "reverse
+# landscape" support. Default is this 320x240 "landscape"
+# orientation
+# CONFIG_LCD_PORTRAIT - Define for 240x320 display "portrait"
+# orientation support. In this orientation, the STM3220G-EVAL's
+# LCD ribbon cable is at the bottom of the display. Default is
+# 320x240 "landscape" orientation.
+# CONFIG_LCD_RPORTRAIT - Define for 240x320 display "reverse
+# portrait" orientation support. In this orientation, the
+# STM3220G-EVAL's LCD ribbon cable is at the top of the display.
+# Default is 320x240 "landscape" orientation.
+#
+CONFIG_LCD_NOGETRUN=y
+CONFIG_LCD_LANDSCAPE=n
+CONFIG_LCD_RLANDSCAPE=n
+CONFIG_LCD_PORTRAIT=n
+CONFIG_LCD_RPORTRAIT=y
+
+#
+# STM3220G-EVAL specific LCD settings
+#
+CONFIG_STM32_ILI9320_DISABLE=n
+CONFIG_STM32_ILI9325_DISABLE=n
+
+#
# Settings for examples/uip
#
CONFIG_EXAMPLE_UIP_IPADDR==(192<<24|168<<16|21<<8|15)
@@ -1379,6 +1509,276 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
# indefinitely.
#
+# Settings for examples/nx
+#
+# CONFIG_EXAMPLES_NX_BUILTIN -- Build the NX example as a "built-in"
+# that can be executed from the NSH command line
+# CONFIG_EXAMPLES_NX_VPLANE -- The plane to select from the frame-
+# buffer driver for use in the test. Default: 0
+# CONFIG_EXAMPLES_NX_DEVNO - The LCD device to select from the LCD
+# driver for use in the test: Default: 0
+# CONFIG_EXAMPLES_NX_BGCOLOR -- The color of the background. Default depends on
+# CONFIG_EXAMPLES_NX_BPP.
+# CONFIG_EXAMPLES_NX_COLOR1 -- The color of window 1. Default depends on
+# CONFIG_EXAMPLES_NX_BPP.
+# CONFIG_EXAMPLES_NX_COLOR2 -- The color of window 2. Default depends on
+# CONFIG_EXAMPLES_NX_BPP.
+# CONFIG_EXAMPLES_NX_TBCOLOR -- The color of the toolbar. Default depends on
+# CONFIG_EXAMPLES_NX_BPP.
+# CONFIG_EXAMPLES_NX_FONTID - Selects the font (see font ID numbers in
+# include/nuttx/nx/nxfonts.h)
+# CONFIG_EXAMPLES_NX_FONTCOLOR -- The color of the toolbar. Default depends on
+# CONFIG_EXAMPLES_NX_BPP.
+# CONFIG_EXAMPLES_NX_BPP -- Pixels per pixel to use. Valid options
+# include 2, 4, 8, 16, 24, and 32. Default is 32.
+# CONFIG_EXAMPLES_NX_RAWWINDOWS -- Use raw windows; Default is to
+# use pretty, framed NXTK windows with toolbars.
+# CONFIG_EXAMPLES_NX_STACKSIZE -- The stacksize to use when creating
+# the NX server. Default 2048
+# CONFIG_EXAMPLES_NX_CLIENTPRIO -- The client priority. Default: 80
+# CONFIG_EXAMPLES_NX_SERVERPRIO -- The server priority. Default: 120
+# CONFIG_EXAMPLES_NX_NOTIFYSIGNO -- The signal number to use with
+# nx_eventnotify(). Default: 4
+#
+CONFIG_EXAMPLES_NX_BUILTIN=y
+CONFIG_EXAMPLES_NX_VPLANE=0
+CONFIG_EXAMPLES_NX_DEVNO=0
+CONFIG_EXAMPLES_NX_BGCOLOR=0x0011
+CONFIG_EXAMPLES_NX_COLOR1=0xaedc
+CONFIG_EXAMPLES_NX_COLOR2=0xe7ff
+CONFIG_EXAMPLES_NX_TBCOLOR=0xd69a
+CONFIG_EXAMPLES_NX_FONTID=0
+CONFIG_EXAMPLES_NX_FONTCOLOR=0x0000
+CONFIG_EXAMPLES_NX_BPP=16
+CONFIG_EXAMPLES_NX_RAWWINDOWS=n
+CONFIG_EXAMPLES_NX_STACKSIZE=2048
+CONFIG_EXAMPLES_NX_CLIENTPRIO=80
+CONFIG_EXAMPLES_NX_SERVERPRIO=120
+CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4
+CONFIG_EXAMPLES_NX_EXTERNINIT=n
+
+#
+# Settings for examples/nxhello
+#
+# CONFIG_EXAMPLES_NXHELLO_BUILTIN -- Build the NXHELLO example as a "built-in"
+# that can be executed from the NSH command line
+# CONFIG_EXAMPLES_NXHELLO_VPLANE -- The plane to select from the frame-
+# buffer driver for use in the test. Default: 0
+# CONFIG_EXAMPLES_NXHELLO_DEVNO - The LCD device to select from the LCD
+# driver for use in the test: Default: 0
+# CONFIG_EXAMPLES_NXHELLO_BGCOLOR -- The color of the background. Default
+# depends on CONFIG_EXAMPLES_NXHELLO_BPP.
+# CONFIG_EXAMPLES_NXHELLO_FONTID - Selects the font (see font ID numbers in
+# include/nuttx/nx/nxfonts.h)
+# CONFIG_EXAMPLES_NXHELLO_FONTCOLOR -- The color of the fonts used in the
+# background window. Default depends on CONFIG_EXAMPLES_NXHELLO_BPP.
+# CONFIG_EXAMPLES_NXHELLO_BPP -- Pixels per pixel to use. Valid options
+# include 2, 4, 8, 16, 24, and 32. Default is 32.
+# CONFIG_EXAMPLES_NXHELLO_EXTERNINIT - The driver for the graphics device on
+# this platform requires some unusual initialization. This is the
+# for, for example, SPI LCD/OLED devices. If this configuration is
+# selected, then the platform code must provide an LCD initialization
+# function.
+#
+CONFIG_EXAMPLES_NXHELLO_BUILTIN=y
+CONFIG_EXAMPLES_NXHELLO_VPLANE=0
+CONFIG_EXAMPLES_NXHELLO_DEVNO=0
+CONFIG_EXAMPLES_NXHELLO_BGCOLOR=0x0011
+CONFIG_EXAMPLES_NXHELLO_FONTID=6
+CONFIG_EXAMPLES_NXHELLO_FONTCOLOR=0xffdf
+CONFIG_EXAMPLES_NXHELLO_BPP=16
+CONFIG_EXAMPLES_NXHELLO_EXTERNINIT=n
+
+#
+# Settings for examples/nximage
+#
+# CONFIG_EXAMPLES_NXIMAGE_BUILTIN -- Build the NXIMAGE example as a "built-in"
+# that can be executed from the NSH command line
+# CONFIG_EXAMPLES_NXIMAGE_VPLANE -- The plane to select from the frame-
+# buffer driver for use in the test. Default: 0
+# CONFIG_EXAMPLES_NXIMAGE_DEVNO - The LCD device to select from the LCD
+# driver for use in the test: Default: 0
+# CONFIG_EXAMPLES_NXIMAGE_BPP -- Pixels per pixel to use. Valid options
+# include 8, 16, and 24. Default is 16.
+# CONFIG_EXAMPLES_NXIMAGE_XSCALEp5, CONFIG_EXAMPLES_NXIMAGE_XSCALE1p5,
+# CONFIG_EXAMPLES_NXIMAGE_XSCALE2p0 -- The logo image width is 160 columns.
+# One of these may be defined to rescale the image horizontally by .5, 1.5,
+# or 2.0.
+# CONFIG_EXAMPLES_NXIMAGE_YSCALEp5, CONFIG_EXAMPLES_NXIMAGE_YSCALE1p5,
+# CONFIG_EXAMPLES_NXIMAGE_YSCALE2p0 -- The logo image height is 160 rows.
+# One of these may be defined to rescale the image vertically by .5, 1.5,
+# or 2.0.
+# CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT - The driver for the graphics device on
+# this platform requires some unusual initialization. This is the
+# for, for example, SPI LCD/OLED devices. If this configuration is
+# selected, then the platform code must provide an LCD initialization
+# function.
+#
+CONFIG_EXAMPLES_NXIMAGE_BUILTIN=y
+CONFIG_EXAMPLES_NXIMAGE_VPLANE=0
+CONFIG_EXAMPLES_NXIMAGE_DEVNO=0
+CONFIG_EXAMPLES_NXIMAGE_BPP=16
+CONFIG_EXAMPLES_NXIMAGE_XSCALEp5=n
+CONFIG_EXAMPLES_NXIMAGE_XSCALE1p5=y
+CONFIG_EXAMPLES_NXIMAGE_XSCALE2p0=n
+CONFIG_EXAMPLES_NXIMAGE_YSCALEp5=n
+CONFIG_EXAMPLES_NXIMAGE_YSCALE1p5=y
+CONFIG_EXAMPLES_NXIMAGE_YSCALE2p0=n
+CONFIG_EXAMPLES_NXIMAGE_EXTERNINIT=n
+
+#
+# Settings for examples/nxlines
+#
+# CONFIG_EXAMPLES_NXLINES_BUILTIN -- Build the NXLINES example as a "built-in"
+# that can be executed from the NSH command line
+# CONFIG_EXAMPLES_NXLINES_VPLANE -- The plane to select from the frame-
+# buffer driver for use in the test. Default: 0
+# CONFIG_EXAMPLES_NXLINES_DEVNO - The LCD device to select from the LCD
+# driver for use in the test: Default: 0
+# CONFIG_EXAMPLES_NXLINES_BGCOLOR -- The color of the background. Default
+# depends on CONFIG_EXAMPLES_NXLINES_BPP.
+# CONFIG_EXAMPLES_NXLINES_LINEWIDTH - Selects the width of the lines in
+# pixels (default: 16)
+# CONFIG_EXAMPLES_NXLINES_LINECOLOR -- The color of the central lines drawn
+# in the background window. Default depends on CONFIG_EXAMPLES_NXLINES_BPP
+# (there really is no meaningful default).
+# CONFIG_EXAMPLES_NXLINES_BORDERWIDTH -- The width of the circular border
+# drawn in the background window. (default: 4).
+# CONFIG_EXAMPLES_NXLINES_BORDERCOLOR -- The color of the circular border
+# drawn in the background window. Default depends on CONFIG_EXAMPLES_NXLINES_BPP
+# (there really is no meaningful default).
+# CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR -- The color of the circular region
+# filled in the background window. Default depends on CONFIG_EXAMPLES_NXLINES_BPP
+# (there really is no meaningful default).
+# CONFIG_EXAMPLES_NXLINES_BPP -- Pixels per pixel to use. Valid options
+# include 2, 4, 8, 16, 24, and 32. Default is 16.
+# CONFIG_EXAMPLES_NXLINES_EXTERNINIT - The driver for the graphics device on
+# this platform requires some unusual initialization. This is the
+# for, for example, SPI LCD/OLED devices. If this configuration is
+# selected, then the platform code must provide an LCD initialization
+# function.
+#
+CONFIG_EXAMPLES_NXLINES_BUILTIN=n
+CONFIG_EXAMPLES_NXLINES_VPLANE=0
+CONFIG_EXAMPLES_NXLINES_DEVNO=0
+CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320
+CONFIG_EXAMPLES_NXLINES_LINEWIDTH=16
+CONFIG_EXAMPLES_NXLINES_LINECOLOR=0xffe0
+CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=4
+CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0xffe0
+CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0xf7bb
+CONFIG_EXAMPLES_NXLINES_BPP=16
+CONFIG_EXAMPLES_NXLINES_EXTERNINIT=n
+
+#
+# Settings for examples/touchscreen
+#
+# CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN - Build the touchscreen test as
+# an NSH built-in function. Default: Built as a standalone problem
+# CONFIG_EXAMPLES_TOUCHSCREEN_MINOR - The minor device number. Minor=N
+# correspnds to touchscreen device /dev/input0. Note this value must
+# with CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH. Default 0.
+# CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH - The path to the touchscreen
+# device. This must be consistent with CONFIG_EXAMPLES_TOUCHSCREEN_MINOR.
+# Default: "/dev/input0"
+# CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES - If CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN
+# is defined, then the number of samples is provided on the command line
+# and this value is ignored. Otherwise, this number of samples is
+# collected and the program terminates. Default: Samples are collected
+# indefinitely.
+#
+CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN=y
+CONFIG_EXAMPLES_TOUCHSCREEN_MINOR=0
+CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH="/dev/input0"
+CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25
+
+#
+# Settings for examples/usbstorage
+#
+# CONFIG_EXAMPLES_USBMSC_BUILTIN
+# This example can be built as two NSH "built-in" commands if this option
+# is selection: 'msconn' will connect the USB mass storage device; 'msdis'
+# will disconnect the USB storage device.
+# CONFIG_EXAMPLES_USBMSC_NLUNS
+# Defines the number of logical units (LUNs) exported by the USB storage
+# driver. Each LUN corresponds to one exported block driver (or partition
+# of a block driver). May be 1, 2, or 3. Default is 1.
+# CONFIG_EXAMPLES_USBMSC_DEVMINOR1
+# The minor device number of the block driver for the first LUN. For
+# example, N in /dev/mmcsdN. Used for registering the block driver. Default
+# is zero.
+# CONFIG_EXAMPLES_USBMSC_DEVPATH1
+# The full path to the registered block driver. Default is "/dev/mmcsd0"
+# CONFIG_EXAMPLES_USBMSC_DEVMINOR2 and CONFIG_EXAMPLES_USBMSC_DEVPATH2
+# Similar parameters that would have to be provided if CONFIG_EXAMPLES_USBMSC_NLUNS
+# is 2 or 3. No defaults.
+# CONFIG_EXAMPLES_USBMSC_DEVMINOR3 and CONFIG_EXAMPLES_USBMSC_DEVPATH3
+# Similar parameters that would have to be provided if CONFIG_EXAMPLES_USBMSC_NLUNS
+# is 3. No defaults.
+# CONFIG_EXAMPLES_USBMSC_DEBUGMM
+# Enables some debug tests to check for memory usage and memory leaks.
+#
+# If CONFIG_USBDEV_TRACE is enabled (or CONFIG_DEBUG and CONFIG_DEBUG_USB), then
+# the example code will also manage the USB trace output. The amount of trace output
+# can be controlled using:
+#
+# CONFIG_EXAMPLES_USBMSC_TRACEINIT
+# Show initialization events
+# CONFIG_EXAMPLES_USBMSC_TRACECLASS
+# Show class driver events
+# CONFIG_EXAMPLES_USBMSC_TRACETRANSFERS
+# Show data transfer events
+# CONFIG_EXAMPLES_USBMSC_TRACECONTROLLER
+# Show controller events
+# CONFIG_EXAMPLES_USBMSC_TRACEINTERRUPTS
+# Show interrupt-related events.
+#
+CONFIG_EXAMPLES_USBMSC_BUILTIN=y
+CONFIG_EXAMPLES_USBMSC_NLUNS=1
+CONFIG_EXAMPLES_USBMSC_DEVMINOR1=0
+CONFIG_EXAMPLES_USBMSC_DEVPATH1="/dev/mmcsd0"
+CONFIG_EXAMPLES_USBMSC_DEBUGMM=n
+CONFIG_EXAMPLES_USBMSC_TRACEINIT=n
+CONFIG_EXAMPLES_USBMSC_TRACECLASS=n
+CONFIG_EXAMPLES_USBMSC_TRACETRANSFERS=n
+CONFIG_EXAMPLES_USBMSC_TRACECONTROLLER=n
+CONFIG_EXAMPLES_USBMSC_TRACEINTERRUPTS=n
+
+#
+# Settings for examples/watchdog
+#
+# This test depends on these specific Watchdog/NSH configurations settings (your
+# specific watchdog hardware settings might require additional settings).
+#
+# CONFIG_WATCHDOG- Enables watchdog timer support support.
+# CONFIG_NSH_BUILTIN_APPS - Build the watchdog time test as an NSH
+# built-in function. Default: Not built! The example can only be used
+# as an NSH built-in application
+#
+# The STM32 also needs one of the following enabled:
+#
+# CONFIG_STM32_WWDG=y, OR
+# CONFIG_STM32_IWDG=y (but not both)
+#
+# Specific configuration options for this example include:
+#
+# CONFIG_EXAMPLES_WATCHDOG_DEVPATH - The path to the Watchdog device.
+# Default: /dev/watchdog0
+# CONFIG_EXAMPLES_WATCHDOG_PINGTIME - Time in milliseconds that the example
+# will ping the watchdog before letting the watchdog expire. Default: 5000
+# milliseconds
+# CONFIG_EXAMPLES_WATCHDOG_PINGDELAY - Time delay between pings in
+# milliseconds. Default: 500 milliseconds.
+# CONFIG_EXAMPLES_WATCHDOG_TIMEOUT - The watchdog timeout value in
+# milliseconds before the watchdog timer expires. Default: 2000
+# milliseconds.
+#
+# CONFIG_EXAMPLES_WATCHDOG_DEVPATH
+# CONFIG_EXAMPLES_WATCHDOG_PINGTIME
+# CONFIG_EXAMPLES_WATCHDOG_PINGDELAY
+# CONFIG_EXAMPLES_WATCHDOG_TIMEOUT
+
+#
# Settings for examples/pwm
#
# CONFIG_PWM - Enables PWM support.
diff --git a/nuttx/configs/stm3220g-eval/nsh/ld.script b/nuttx/configs/stm3220g-eval/nsh/ld.script
index a20a27500..dfa2b3ccd 100644
--- a/nuttx/configs/stm3220g-eval/nsh/ld.script
+++ b/nuttx/configs/stm3220g-eval/nsh/ld.script
@@ -34,11 +34,10 @@
****************************************************************************/
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
+ * 128Kb of SRAM. SRAM is split up into two blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
- * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
diff --git a/nuttx/configs/stm3220g-eval/nsh/setenv.sh b/nuttx/configs/stm3220g-eval/nsh/setenv.sh
index 7af999d69..618daf011 100755
--- a/nuttx/configs/stm3220g-eval/nsh/setenv.sh
+++ b/nuttx/configs/stm3220g-eval/nsh/setenv.sh
@@ -69,7 +69,7 @@ fi
# toolchain.
export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
-# Add the path to the toolchain to the PATH varialble
+# Add the path to the toolchain to the PATH variable
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/stm3220g-eval/nsh2/appconfig b/nuttx/configs/stm3220g-eval/nsh2/appconfig
index 6a13d0b27..35d687884 100644
--- a/nuttx/configs/stm3220g-eval/nsh2/appconfig
+++ b/nuttx/configs/stm3220g-eval/nsh2/appconfig
@@ -76,6 +76,10 @@ ifeq ($(CONFIG_I2C),y)
CONFIGURED_APPS += system/i2c
endif
+ifeq ($(CONFIG_WATCHDOG),y)
+CONFIGURED_APPS += examples/watchdog
+endif
+
# Uncomment examples/ftpc to include the FTP client example
# Uncomment examples/ftpd to include the FTP daemon example
diff --git a/nuttx/configs/stm3220g-eval/nsh2/defconfig b/nuttx/configs/stm3220g-eval/nsh2/defconfig
index 10457b077..7f5a7fd87 100644
--- a/nuttx/configs/stm3220g-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3220g-eval/nsh2/defconfig
@@ -65,7 +65,7 @@
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
-# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
@@ -119,15 +119,6 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
-# On-chip CCM SRAM configuration
-#
-# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
-# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
-# being a part of the stack.
-#
-CONFIG_STM32_CCMEXCLUDE=y
-
-#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -149,7 +140,6 @@ CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
# AHB1:
CONFIG_STM32_CRC=n
CONFIG_STM32_BKPSRAM=n
-CONFIG_STM32_CCMDATARAM=n
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=y
CONFIG_STM32_ETHMAC=y
diff --git a/nuttx/configs/stm3220g-eval/nsh2/ld.script b/nuttx/configs/stm3220g-eval/nsh2/ld.script
index f01dc2b83..e03a33dcb 100644
--- a/nuttx/configs/stm3220g-eval/nsh2/ld.script
+++ b/nuttx/configs/stm3220g-eval/nsh2/ld.script
@@ -34,11 +34,10 @@
****************************************************************************/
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
+ * 128Kb of SRAM. SRAM is split up into two blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
- * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
diff --git a/nuttx/configs/stm3220g-eval/nsh2/setenv.sh b/nuttx/configs/stm3220g-eval/nsh2/setenv.sh
index 1dc69bf42..5b6405fae 100755
--- a/nuttx/configs/stm3220g-eval/nsh2/setenv.sh
+++ b/nuttx/configs/stm3220g-eval/nsh2/setenv.sh
@@ -68,7 +68,7 @@ fi
# toolchain.
export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
-# Add the path to the toolchain to the PATH varialble
+# Add the path to the toolchain to the PATH variable
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/stm3220g-eval/ostest/defconfig b/nuttx/configs/stm3220g-eval/ostest/defconfig
index ba86a5488..184ca9e52 100644
--- a/nuttx/configs/stm3220g-eval/ostest/defconfig
+++ b/nuttx/configs/stm3220g-eval/ostest/defconfig
@@ -64,7 +64,7 @@
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
-# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
@@ -118,15 +118,6 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
-# On-chip CCM SRAM configuration
-#
-# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
-# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
-# being a part of the stack.
-#
-CONFIG_STM32_CCMEXCLUDE=y
-
-#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -148,7 +139,6 @@ CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
# AHB1:
CONFIG_STM32_CRC=n
CONFIG_STM32_BKPSRAM=n
-CONFIG_STM32_CCMDATARAM=n
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=n
CONFIG_STM32_ETHMAC=n
@@ -1106,7 +1096,9 @@ CONFIG_NXWIDGETS_DEFAULT_FONTID=5
#
# CONFIG_LCD_LANDSCAPE - Define for 320x240 display "landscape"
# support. Default is this 320x240 "landscape" orientation
-# (this setting is informative only... not used).
+# CONFIG_LCD_RLANDSCAPE - Define for 320x240 display "reverse
+# landscape" support. Default is this 320x240 "landscape"
+# orientation
# CONFIG_LCD_PORTRAIT - Define for 240x320 display "portrait"
# orientation support. In this orientation, the PT3's
# LCD ribbon cable is at the bottom of the display. Default is
@@ -1115,22 +1107,17 @@ CONFIG_NXWIDGETS_DEFAULT_FONTID=5
# portrait" orientation support. In this orientation, the
# STM3220G-EVAL's LCD ribbon cable is at the top of the display.
# Default is 320x240 "landscape" orientation.
-# CONFIG_LCD_BACKLIGHT - Define to support a backlight.
-# CONFIG_LCD_PWM - If CONFIG_STM32_TIM1 is also defined, then an
-# adjustable backlight will be provided using timer 1 to generate
-# various pulse widthes. The granularity of the settings is
-# determined by CONFIG_LCD_MAXPOWER. If CONFIG_LCD_PWM (or
-# CONFIG_STM32_TIM1) is not defined, then a simple on/off backlight
-# is provided.
#
CONFIG_LCD_LANDSCAPE=n
+CONFIG_LCD_RLANDSCAPE=n
CONFIG_LCD_PORTRAIT=n
CONFIG_LCD_RPORTRAIT=y
-CONFIG_LCD_BACKLIGHT=y
-CONFIG_LCD_PWM=n
-CONFIG_STM32_AM240320_DISABLE=y
-CONFIG_STM32_SPFD5408B_DISABLE=n
-CONFIG_STM32_R61580_DISABLE=n
+
+#
+# STM3220G-EVAL specific LCD settings
+#
+CONFIG_STM32_ILI9320_DISABLE=n
+CONFIG_STM32_ILI9325_DISABLE=n
#
# Settings for examples/uip
diff --git a/nuttx/configs/stm3220g-eval/ostest/ld.script b/nuttx/configs/stm3220g-eval/ostest/ld.script
index 46681c4c4..17428ea85 100644
--- a/nuttx/configs/stm3220g-eval/ostest/ld.script
+++ b/nuttx/configs/stm3220g-eval/ostest/ld.script
@@ -33,12 +33,10 @@
*
****************************************************************************/
-/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
+/* The STM32F207IGH6U has 1024Kb of FLASH two blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
- * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
diff --git a/nuttx/configs/stm3220g-eval/ostest/setenv.sh b/nuttx/configs/stm3220g-eval/ostest/setenv.sh
index c408a0b7c..2b8e7daa7 100755
--- a/nuttx/configs/stm3220g-eval/ostest/setenv.sh
+++ b/nuttx/configs/stm3220g-eval/ostest/setenv.sh
@@ -69,7 +69,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++
# toolchain.
#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-# Add the path to the toolchain to the PATH varialble
+# Add the path to the toolchain to the PATH variable
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/stm3220g-eval/src/Makefile b/nuttx/configs/stm3220g-eval/src/Makefile
index af845744b..44cc7f1d1 100644
--- a/nuttx/configs/stm3220g-eval/src/Makefile
+++ b/nuttx/configs/stm3220g-eval/src/Makefile
@@ -61,7 +61,7 @@ CSRCS += up_usbdev.c
endif
ifeq ($(CONFIG_STM32_FSMC),y)
-CSRCS += up_extmem.c up_selectsram.c up_deselectsram.c
+CSRCS += up_lcd.c up_selectlcd.c up_deselectlcd.c up_selectsram.c up_deselectsram.c up_extmem.c
endif
ifeq ($(CONFIG_ADC),y)
@@ -84,6 +84,10 @@ ifeq ($(CONFIG_WATCHDOG),y)
CSRCS += up_watchdog.c
endif
+ifeq ($(CONFIG_INPUT_STMPE11),y)
+CSRCS += up_stmpe11.c
+endif
+
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/stm3220g-eval/src/stm3220g-internal.h b/nuttx/configs/stm3220g-eval/src/stm3220g-internal.h
index 187040ed5..dcb7c7e1b 100644
--- a/nuttx/configs/stm3220g-eval/src/stm3220g-internal.h
+++ b/nuttx/configs/stm3220g-eval/src/stm3220g-internal.h
@@ -127,9 +127,51 @@
# endif
#endif
-/****************************************************************************************************
- * Public Types
- ****************************************************************************************************/
+/* USB OTG FS
+ *
+ * PA9 VBUS_FS
+ * PH5 OTG_FS_PowerSwitchOn
+ * PF11 OTG_FS_Overcurrent
+ */
+
+#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
+#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN5)
+#define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN11)
+
+/* The STM3220G-EVAL has two STMPE11QTR I/O expanders on board both connected
+ * to the STM32 via I2C1. They share a common interrupt line: PI2.
+ *
+ * STMPE11 U24, I2C address 0x41 (7-bit)
+ * ------ ---- ---------------- --------------------------------------------
+ * STPE11 PIN BOARD SIGNAL BOARD CONNECTION
+ * ------ ---- ---------------- --------------------------------------------
+ * Y- TouchScreen_Y- LCD Connector XL
+ * X- TouchScreen_X- LCD Connector XR
+ * Y+ TouchScreen_Y+ LCD Connector XD
+ * X+ TouchScreen_X+ LCD Connector XU
+ * IN3 EXP_IO9
+ * IN2 EXP_IO10
+ * IN1 EXP_IO11
+ * IN0 EXP_IO12
+ *
+ * STMPE11 U29, I2C address 0x44 (7-bit)
+ * ------ ---- ---------------- --------------------------------------------
+ * STPE11 PIN BOARD SIGNAL BOARD CONNECTION
+ * ------ ---- ---------------- --------------------------------------------
+ * Y- EXP_IO1
+ * X- EXP_IO2
+ * Y+ EXP_IO3
+ * X+ EXP_IO4
+ * IN3 EXP_IO5
+ * IN2 EXP_IO6
+ * IN1 EXP_IO7
+ * IN0 EXP_IO8
+ */
+
+#define STMPE11_ADDR1 0x41
+#define STMPE11_ADDR2 0x44
+
+#define GPIO_IO_EXPANDER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN2)
/* GPIO settings that will be altered when external memory is selected:
*
@@ -147,6 +189,10 @@
*/
/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
* Public data
****************************************************************************************************/
@@ -176,6 +222,132 @@ void weak_function stm32_spiinitialize(void);
void weak_function stm32_usbinitialize(void);
+/************************************************************************************
+ * Name: stm32_extmemgpios
+ *
+ * Description:
+ * Initialize GPIOs for external memory usage
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_extmemgpios(const uint32_t *gpios, int ngpios);
+#endif
+
+/************************************************************************************
+ * Name: stm32_extmemaddr
+ *
+ * Description:
+ * Initialize adress line GPIOs for external memory access
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_extmemaddr(int naddrs);
+#endif
+
+/************************************************************************************
+ * Name: stm32_extmemdata
+ *
+ * Description:
+ * Initialize data line GPIOs for external memory access
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_extmemdata(int ndata);
+#endif
+
+/************************************************************************************
+ * Name: stm32_enablefsmc
+ *
+ * Description:
+ * enable clocking to the FSMC module
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_enablefsmc(void);
+#endif
+
+/************************************************************************************
+ * Name: stm32_disablefsmc
+ *
+ * Description:
+ * enable clocking to the FSMC module
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_disablefsmc(void);
+#endif
+
+/************************************************************************************
+ * Name: stm32_selectsram
+ *
+ * Description:
+ * Initialize to access external SRAM. SRAM will be visible at the FSMC Bank
+ * NOR/SRAM2 base address (0x64000000)
+ *
+ * General transaction rules. The requested AHB transaction data size can be 8-,
+ * 16- or 32-bit wide whereas the SRAM has a fixed 16-bit data width. Some simple
+ * transaction rules must be followed:
+ *
+ * Case 1: AHB transaction width and SRAM data width are equal
+ * There is no issue in this case.
+ * Case 2: AHB transaction size is greater than the memory size
+ * In this case, the FSMC splits the AHB transaction into smaller consecutive
+ * memory accesses in order to meet the external data width.
+ * Case 3: AHB transaction size is smaller than the memory size.
+ * SRAM supports the byte select feature.
+ * a) FSMC allows write transactions accessing the right data through its
+ * byte lanes (NBL[1:0])
+ * b) Read transactions are allowed (the controller reads the entire memory
+ * word and uses the needed byte only). The NBL[1:0] are always kept low
+ * during read transactions.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_selectsram(void);
+#endif
+
+/************************************************************************************
+ * Name: stm32_deselectsram
+ *
+ * Description:
+ * Disable SRAM
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_deselectsram(void);
+#endif
+
+/************************************************************************************
+ * Name: stm32_selectlcd
+ *
+ * Description:
+ * Initialize to the LCD
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_selectlcd(void);
+#endif
+
+/************************************************************************************
+ * Name: stm32_deselectlcd
+ *
+ * Description:
+ * Disable the LCD
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_FSMC
+void stm32_deselectlcd(void);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_STM3220G_EVAL_SRC_STM3220G_INTERNAL_H */
diff --git a/nuttx/configs/stm3220g-eval/src/up_cxxinitialize.c b/nuttx/configs/stm3220g-eval/src/up_cxxinitialize.c
new file mode 100644
index 000000000..ad226f486
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_cxxinitialize.c
@@ -0,0 +1,155 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_cxxinitialize.c
+ * arch/arm/src/board/up_cxxinitialize.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include <arch/stm32/chip.h>
+#include "chip.h"
+
+#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Debug ****************************************************************************/
+/* Non-standard debug that may be enabled just for testing the static constructors */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_CXX
+#endif
+
+#ifdef CONFIG_DEBUG_CXX
+# define cxxdbg dbg
+# define cxxlldbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define cxxvdbg vdbg
+# define cxxllvdbg llvdbg
+# else
+# define cxxvdbg(x...)
+# define cxxllvdbg(x...)
+# endif
+#else
+# define cxxdbg(x...)
+# define cxxlldbg(x...)
+# define cxxvdbg(x...)
+# define cxxllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+/* This type defines one entry in initialization array */
+
+typedef void (*initializer_t)(void);
+
+/************************************************************************************
+ * External references
+ ************************************************************************************/
+/* _sinit and _einit are symbols exported by the linker script that mark the
+ * beginning and the end of the C++ initialization section.
+ */
+
+extern initializer_t _sinit;
+extern initializer_t _einit;
+
+/* _stext and _etext are symbols exported by the linker script that mark the
+ * beginning and the end of text.
+ */
+
+extern uint32_t _stext;
+extern uint32_t _etext;
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: up_cxxinitialize
+ *
+ * Description:
+ * If C++ and C++ static constructors are supported, then this function
+ * must be provided by board-specific logic in order to perform
+ * initialization of the static C++ class instances.
+ *
+ * This function should then be called in the application-specific
+ * user_start logic in order to perform the C++ initialization. NOTE
+ * that no component of the core NuttX RTOS logic is involved; This
+ * function defintion only provides the 'contract' between application
+ * specific C++ code and platform-specific toolchain support
+ *
+ ***************************************************************************/
+
+void up_cxxinitialize(void)
+{
+ initializer_t *initp;
+
+ cxxdbg("_sinit: %p _einit: %p _stext: %p _etext: %p\n",
+ &_sinit, &_einit, &_stext, &_etext);
+
+ /* Visit each entry in the initialzation table */
+
+ for (initp = &_sinit; initp != &_einit; initp++)
+ {
+ initializer_t initializer = *initp;
+ cxxdbg("initp: %p initializer: %p\n", initp, initializer);
+
+ /* Make sure that the address is non-NULL and lies in the text region
+ * defined by the linker script. Some toolchains may put NULL values
+ * or counts in the initialization table
+ */
+
+ if ((void*)initializer > (void*)&_stext && (void*)initializer < (void*)&_etext)
+ {
+ cxxdbg("Calling %p\n", initializer);
+ initializer();
+ }
+ }
+}
+
+#endif /* CONFIG_HAVE_CXX && CONFIG_HAVE_CXXINITIALIZE */
+
diff --git a/nuttx/configs/stm3220g-eval/src/up_deselectlcd.c b/nuttx/configs/stm3220g-eval/src/up_deselectlcd.c
new file mode 100644
index 000000000..d1befac71
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_deselectlcd.c
@@ -0,0 +1,98 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_deselectlcd.c
+ * arch/arm/src/board/up_deselectlcd.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
+ * Diego Sanchez <dsanchez@nx-engineering.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include "up_arch.h"
+#include "stm32_fsmc.h"
+#include "stm3220g-internal.h"
+
+#ifdef CONFIG_STM32_FSMC
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_deselectlcd
+ *
+ * Description:
+ * Disable the LCD
+ *
+ ************************************************************************************/
+
+void stm32_deselectlcd(void)
+{
+ /* Restore registers to their power up settings */
+
+ putreg32(0xffffffff, STM32_FSMC_BCR4);
+
+ /* Bank1 NOR/SRAM timing register configuration */
+
+ putreg32(0x0fffffff, STM32_FSMC_BTR4);
+
+ /* Disable AHB clocking to the FSMC */
+
+ stm32_disablefsmc();
+}
+
+#endif /* CONFIG_STM32_FSMC */
+
+
+
diff --git a/nuttx/configs/stm3220g-eval/src/up_deselectsram.c b/nuttx/configs/stm3220g-eval/src/up_deselectsram.c
new file mode 100644
index 000000000..3dd59ab41
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_deselectsram.c
@@ -0,0 +1,97 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_deselectsram.c
+ * arch/arm/src/board/up_deselectsram.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include "up_arch.h"
+#include "stm32_fsmc.h"
+#include "stm3220g-internal.h"
+
+#ifdef CONFIG_STM32_FSMC
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_deselectsram
+ *
+ * Description:
+ * Disable SRAM
+ *
+ ************************************************************************************/
+
+void stm32_deselectsram(void)
+{
+ /* Restore registers to their power up settings */
+
+ putreg32(FSMC_BCR_RSTVALUE, STM32_FSMC_BCR2);
+
+ /* Bank1 NOR/SRAM timing register configuration */
+
+ putreg32(FSMC_BTR_RSTVALUE, STM32_FSMC_BTR2);
+
+ /* Disable AHB clocking to the FSMC */
+
+ stm32_disablefsmc();
+}
+
+#endif /* CONFIG_STM32_FSMC */
+
+
+
diff --git a/nuttx/configs/stm3220g-eval/src/up_extmem.c b/nuttx/configs/stm3220g-eval/src/up_extmem.c
new file mode 100644
index 000000000..179d28f11
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_extmem.c
@@ -0,0 +1,188 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_extmem.c
+ * arch/arm/src/board/up_extmem.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32_fsmc.h"
+#include "stm32_gpio.h"
+#include "stm32_internal.h"
+#include "stm3220g-internal.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+#ifndef CONFIG_STM32_FSMC
+# warning "FSMC is not enabled"
+#endif
+
+#if STM32_NGPIO_PORTS < 6
+# error "Required GPIO ports not enabled"
+#endif
+
+#define STM32_FSMC_NADDRCONFIGS 26
+#define STM32_FSMC_NDATACONFIGS 16
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/* GPIO configurations common to most external memories */
+
+static const uint32_t g_addressconfig[STM32_FSMC_NADDRCONFIGS] =
+{
+ GPIO_FSMC_A0, GPIO_FSMC_A1 , GPIO_FSMC_A2, GPIO_FSMC_A3, GPIO_FSMC_A4 , GPIO_FSMC_A5,
+ GPIO_FSMC_A6, GPIO_FSMC_A7, GPIO_FSMC_A8, GPIO_FSMC_A9, GPIO_FSMC_A10, GPIO_FSMC_A11,
+ GPIO_FSMC_A12, GPIO_FSMC_A13, GPIO_FSMC_A14, GPIO_FSMC_A15, GPIO_FSMC_A16, GPIO_FSMC_A17,
+ GPIO_FSMC_A18, GPIO_FSMC_A19, GPIO_FSMC_A20, GPIO_FSMC_A21, GPIO_FSMC_A22, GPIO_FSMC_A23,
+ GPIO_FSMC_A24, GPIO_FSMC_A25
+};
+
+static const uint32_t g_dataconfig[STM32_FSMC_NDATACONFIGS] =
+{
+ GPIO_FSMC_D0, GPIO_FSMC_D1 , GPIO_FSMC_D2, GPIO_FSMC_D3, GPIO_FSMC_D4 , GPIO_FSMC_D5,
+ GPIO_FSMC_D6, GPIO_FSMC_D7, GPIO_FSMC_D8, GPIO_FSMC_D9, GPIO_FSMC_D10, GPIO_FSMC_D11,
+ GPIO_FSMC_D12, GPIO_FSMC_D13, GPIO_FSMC_D14, GPIO_FSMC_D15
+};
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_extmemgpios
+ *
+ * Description:
+ * Initialize GPIOs for external memory usage
+ *
+ ************************************************************************************/
+
+void stm32_extmemgpios(const uint32_t *gpios, int ngpios)
+{
+ int i;
+
+ /* Configure GPIOs */
+
+ for (i = 0; i < ngpios; i++)
+ {
+ stm32_configgpio(gpios[i]);
+ }
+}
+
+/************************************************************************************
+ * Name: stm32_extmemaddr
+ *
+ * Description:
+ * Initialize adress line GPIOs for external memory access
+ *
+ ************************************************************************************/
+
+void stm32_extmemaddr(int naddrs)
+{
+ stm32_extmemgpios(g_addressconfig, naddrs);
+}
+
+/************************************************************************************
+ * Name: stm32_extmemdata
+ *
+ * Description:
+ * Initialize data line GPIOs for external memory access
+ *
+ ************************************************************************************/
+
+void stm32_extmemdata(int ndata)
+{
+ stm32_extmemgpios(g_dataconfig, ndata);
+}
+
+/************************************************************************************
+ * Name: stm32_enablefsmc
+ *
+ * Description:
+ * enable clocking to the FSMC module
+ *
+ ************************************************************************************/
+
+void stm32_enablefsmc(void)
+{
+ uint32_t regval;
+
+ /* Enable AHB clocking to the FSMC */
+
+ regval = getreg32( STM32_RCC_AHB3ENR);
+ regval |= RCC_AHB3ENR_FSMCEN;
+ putreg32(regval, STM32_RCC_AHB3ENR);
+}
+
+/************************************************************************************
+ * Name: stm32_disablefsmc
+ *
+ * Description:
+ * enable clocking to the FSMC module
+ *
+ ************************************************************************************/
+
+void stm32_disablefsmc(void)
+{
+ uint32_t regval;
+
+ /* Disable AHB clocking to the FSMC */
+
+ regval = getreg32(STM32_RCC_AHB3ENR);
+ regval &= ~RCC_AHB3ENR_FSMCEN;
+ putreg32(regval, STM32_RCC_AHB3ENR);
+}
diff --git a/nuttx/configs/stm3220g-eval/src/up_lcd.c b/nuttx/configs/stm3220g-eval/src/up_lcd.c
new file mode 100644
index 000000000..a1fcceef7
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_lcd.c
@@ -0,0 +1,1210 @@
+/**************************************************************************************
+ * configs/stm3220g-eval/src/up_lcd.c
+ * arch/arm/src/board/up_lcd.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
+ * Diego Sanchez <dsanchez@nx-engineering.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************************/
+/* This driver supports the following LCDs on the STM324xG_EVAL board:
+ *
+ * AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) OR
+ * AM-240320D5TOQW01H (LCD_ILI9325)
+ */
+
+/**************************************************************************************
+ * Included Files
+ **************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/lcd/lcd.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "stm32.h"
+#include "stm32_internal.h"
+#include "stm3220g-internal.h"
+
+#if !defined(CONFIG_STM32_ILI9320_DISABLE) || !defined(CONFIG_STM32_ILI9325_DISABLE)
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+/* Configuration **********************************************************************/
+/* CONFIG_STM32_ILI9320_DISABLE may be defined to disabled the AM-240320L8TNQW00H
+ * (LCD_ILI9320 or LCD_ILI9321)
+ * CONFIG_STM32_ILI9325_DISABLE may be defined to disabled the AM-240320D5TOQW01H
+ * (LCD_ILI9325)
+ */
+
+/* Check contrast selection */
+
+#if !defined(CONFIG_LCD_MAXCONTRAST)
+# define CONFIG_LCD_MAXCONTRAST 1
+#endif
+
+/* Check power setting */
+
+#if !defined(CONFIG_LCD_MAXPOWER) || CONFIG_LCD_MAXPOWER < 1
+# define CONFIG_LCD_MAXPOWER 1
+#endif
+
+#if CONFIG_LCD_MAXPOWER > 255
+# error "CONFIG_LCD_MAXPOWER must be less than 256 to fit in uint8_t"
+#endif
+
+/* Check orientation */
+
+#if defined(CONFIG_LCD_PORTRAIT)
+# if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE) || defined(CONFIG_LCD_RPORTRAIT)
+# error "Cannot define both portrait and any other orientations"
+# endif
+#elif defined(CONFIG_LCD_RPORTRAIT)
+# if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE)
+# error "Cannot define both rportrait and any other orientations"
+# endif
+#elif defined(CONFIG_LCD_LANDSCAPE)
+# ifdef CONFIG_LCD_RLANDSCAPE
+# error "Cannot define both landscape and any other orientations"
+# endif
+#elif !defined(CONFIG_LCD_RLANDSCAPE)
+# define CONFIG_LCD_LANDSCAPE 1
+#endif
+
+/* Define CONFIG_DEBUG_LCD to enable detailed LCD debug output. Verbose debug must
+ * also be enabled.
+ */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_VERBOSE
+# undef CONFIG_DEBUG_GRAPHICS
+# undef CONFIG_DEBUG_LCD
+#endif
+
+#ifndef CONFIG_DEBUG_VERBOSE
+# undef CONFIG_DEBUG_LCD
+#endif
+
+/* Display/Color Properties ***********************************************************/
+/* Display Resolution */
+
+#if defined(CONFIG_LCD_LANDSCAPE) || defined(CONFIG_LCD_RLANDSCAPE)
+# define STM3220G_XRES 320
+# define STM3220G_YRES 240
+#else
+# define STM3220G_XRES 240
+# define STM3220G_YRES 320
+#endif
+
+/* Color depth and format */
+
+#define STM3220G_BPP 16
+#define STM3220G_COLORFMT FB_FMT_RGB16_565
+
+/* STM3220G-EVAL LCD Hardware Definitions *********************************************/
+/* LCD /CS is CE4, Bank 3 of NOR/SRAM Bank 1~4 */
+
+#define STM3220G_LCDBASE ((uintptr_t)(0x60000000 | 0x08000000))
+#define LCD ((struct lcd_regs_s *)STM3220G_LCDBASE)
+
+#define LCD_REG_0 0x00
+#define LCD_REG_1 0x01
+#define LCD_REG_2 0x02
+#define LCD_REG_3 0x03
+#define LCD_REG_4 0x04
+#define LCD_REG_5 0x05
+#define LCD_REG_6 0x06
+#define LCD_REG_7 0x07
+#define LCD_REG_8 0x08
+#define LCD_REG_9 0x09
+#define LCD_REG_10 0x0a
+#define LCD_REG_12 0x0c
+#define LCD_REG_13 0x0d
+#define LCD_REG_14 0x0e
+#define LCD_REG_15 0x0f
+#define LCD_REG_16 0x10
+#define LCD_REG_17 0x11
+#define LCD_REG_18 0x12
+#define LCD_REG_19 0x13
+#define LCD_REG_20 0x14
+#define LCD_REG_21 0x15
+#define LCD_REG_22 0x16
+#define LCD_REG_23 0x17
+#define LCD_REG_24 0x18
+#define LCD_REG_25 0x19
+#define LCD_REG_26 0x1a
+#define LCD_REG_27 0x1b
+#define LCD_REG_28 0x1c
+#define LCD_REG_29 0x1d
+#define LCD_REG_30 0x1e
+#define LCD_REG_31 0x1f
+#define LCD_REG_32 0x20
+#define LCD_REG_33 0x21
+#define LCD_REG_34 0x22
+#define LCD_REG_36 0x24
+#define LCD_REG_37 0x25
+#define LCD_REG_40 0x28
+#define LCD_REG_41 0x29
+#define LCD_REG_43 0x2b
+#define LCD_REG_45 0x2d
+#define LCD_REG_48 0x30
+#define LCD_REG_49 0x31
+#define LCD_REG_50 0x32
+#define LCD_REG_51 0x33
+#define LCD_REG_52 0x34
+#define LCD_REG_53 0x35
+#define LCD_REG_54 0x36
+#define LCD_REG_55 0x37
+#define LCD_REG_56 0x38
+#define LCD_REG_57 0x39
+#define LCD_REG_58 0x3a
+#define LCD_REG_59 0x3b
+#define LCD_REG_60 0x3c
+#define LCD_REG_61 0x3d
+#define LCD_REG_62 0x3e
+#define LCD_REG_63 0x3f
+#define LCD_REG_64 0x40
+#define LCD_REG_65 0x41
+#define LCD_REG_66 0x42
+#define LCD_REG_67 0x43
+#define LCD_REG_68 0x44
+#define LCD_REG_69 0x45
+#define LCD_REG_70 0x46
+#define LCD_REG_71 0x47
+#define LCD_REG_72 0x48
+#define LCD_REG_73 0x49
+#define LCD_REG_74 0x4a
+#define LCD_REG_75 0x4b
+#define LCD_REG_76 0x4c
+#define LCD_REG_77 0x4d
+#define LCD_REG_78 0x4e
+#define LCD_REG_79 0x4f
+#define LCD_REG_80 0x50
+#define LCD_REG_81 0x51
+#define LCD_REG_82 0x52
+#define LCD_REG_83 0x53
+#define LCD_REG_96 0x60
+#define LCD_REG_97 0x61
+#define LCD_REG_106 0x6a
+#define LCD_REG_118 0x76
+#define LCD_REG_128 0x80
+#define LCD_REG_129 0x81
+#define LCD_REG_130 0x82
+#define LCD_REG_131 0x83
+#define LCD_REG_132 0x84
+#define LCD_REG_133 0x85
+#define LCD_REG_134 0x86
+#define LCD_REG_135 0x87
+#define LCD_REG_136 0x88
+#define LCD_REG_137 0x89
+#define LCD_REG_139 0x8b
+#define LCD_REG_140 0x8c
+#define LCD_REG_141 0x8d
+#define LCD_REG_143 0x8f
+#define LCD_REG_144 0x90
+#define LCD_REG_145 0x91
+#define LCD_REG_146 0x92
+#define LCD_REG_147 0x93
+#define LCD_REG_148 0x94
+#define LCD_REG_149 0x95
+#define LCD_REG_150 0x96
+#define LCD_REG_151 0x97
+#define LCD_REG_152 0x98
+#define LCD_REG_153 0x99
+#define LCD_REG_154 0x9a
+#define LCD_REG_157 0x9d
+#define LCD_REG_164 0xa4
+#define LCD_REG_192 0xc0
+#define LCD_REG_193 0xc1
+#define LCD_REG_229 0xe5
+
+/* LCD IDs */
+
+#define ILI9320_ID 0x9320
+#define ILI9321_ID 0x9321
+#define ILI9325_ID 0x9325
+
+/* Debug ******************************************************************************/
+
+#ifdef CONFIG_DEBUG_LCD
+# define lcddbg dbg
+# define lcdvdbg vdbg
+#else
+# define lcddbg(x...)
+# define lcdvdbg(x...)
+#endif
+
+/**************************************************************************************
+ * Private Type Definition
+ **************************************************************************************/
+
+/* LCD type */
+
+enum lcd_type_e
+{
+ LCD_TYPE_UNKNOWN = 0,
+ LCD_TYPE_ILI9320,
+ LCD_TYPE_ILI9325
+};
+
+/* This structure describes the LCD registers */
+
+struct lcd_regs_s
+{
+ volatile uint16_t address;
+ volatile uint16_t value;
+};
+
+/* This structure describes the state of this driver */
+
+struct stm3220g_dev_s
+{
+ /* Publically visible device structure */
+
+ struct lcd_dev_s dev;
+
+ /* Private LCD-specific information follows */
+
+ uint8_t type; /* LCD type. See enum lcd_type_e */
+ uint8_t power; /* Current power setting */
+};
+
+/**************************************************************************************
+ * Private Function Protototypes
+ **************************************************************************************/
+/* Low Level LCD access */
+
+static void stm3220g_writereg(uint8_t regaddr, uint16_t regval);
+static uint16_t stm3220g_readreg(uint8_t regaddr);
+static inline void stm3220g_gramselect(void);
+static inline void stm3220g_writegram(uint16_t rgbval);
+static void stm3220g_readnosetup(FAR uint16_t *accum);
+static uint16_t stm3220g_readnoshift(FAR uint16_t *accum);
+static void stm3220g_setcursor(uint16_t col, uint16_t row);
+
+/* LCD Data Transfer Methods */
+
+static int stm3220g_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
+ size_t npixels);
+static int stm3220g_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+ size_t npixels);
+
+/* LCD Configuration */
+
+static int stm3220g_getvideoinfo(FAR struct lcd_dev_s *dev,
+ FAR struct fb_videoinfo_s *vinfo);
+static int stm3220g_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
+ FAR struct lcd_planeinfo_s *pinfo);
+
+/* LCD RGB Mapping */
+
+#ifdef CONFIG_FB_CMAP
+# error "RGB color mapping not supported by this driver"
+#endif
+
+/* Cursor Controls */
+
+#ifdef CONFIG_FB_HWCURSOR
+# error "Cursor control not supported by this driver"
+#endif
+
+/* LCD Specific Controls */
+
+static int stm3220g_getpower(struct lcd_dev_s *dev);
+static int stm3220g_setpower(struct lcd_dev_s *dev, int power);
+static int stm3220g_getcontrast(struct lcd_dev_s *dev);
+static int stm3220g_setcontrast(struct lcd_dev_s *dev, unsigned int contrast);
+
+/* Initialization */
+
+static inline void stm3220g_lcdinitialize(void);
+
+/**************************************************************************************
+ * Private Data
+ **************************************************************************************/
+
+/* This is working memory allocated by the LCD driver for each LCD device
+ * and for each color plane. This memory will hold one raster line of data.
+ * The size of the allocated run buffer must therefore be at least
+ * (bpp * xres / 8). Actual alignment of the buffer must conform to the
+ * bitwidth of the underlying pixel type.
+ *
+ * If there are multiple planes, they may share the same working buffer
+ * because different planes will not be operate on concurrently. However,
+ * if there are multiple LCD devices, they must each have unique run buffers.
+ */
+
+static uint16_t g_runbuffer[STM3220G_XRES];
+
+/* This structure describes the overall LCD video controller */
+
+static const struct fb_videoinfo_s g_videoinfo =
+{
+ .fmt = STM3220G_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */
+ .xres = STM3220G_XRES, /* Horizontal resolution in pixel columns */
+ .yres = STM3220G_YRES, /* Vertical resolution in pixel rows */
+ .nplanes = 1, /* Number of color planes supported */
+};
+
+/* This is the standard, NuttX Plane information object */
+
+static const struct lcd_planeinfo_s g_planeinfo =
+{
+ .putrun = stm3220g_putrun, /* Put a run into LCD memory */
+ .getrun = stm3220g_getrun, /* Get a run from LCD memory */
+ .buffer = (uint8_t*)g_runbuffer, /* Run scratch buffer */
+ .bpp = STM3220G_BPP, /* Bits-per-pixel */
+};
+
+/* This is the standard, NuttX LCD driver object */
+
+static struct stm3220g_dev_s g_lcddev =
+{
+ .dev =
+ {
+ /* LCD Configuration */
+
+ .getvideoinfo = stm3220g_getvideoinfo,
+ .getplaneinfo = stm3220g_getplaneinfo,
+
+ /* LCD RGB Mapping -- Not supported */
+ /* Cursor Controls -- Not supported */
+
+ /* LCD Specific Controls */
+
+ .getpower = stm3220g_getpower,
+ .setpower = stm3220g_setpower,
+ .getcontrast = stm3220g_getcontrast,
+ .setcontrast = stm3220g_setcontrast,
+ },
+};
+
+/**************************************************************************************
+ * Private Functions
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: stm3220g_writereg
+ *
+ * Description:
+ * Write to an LCD register
+ *
+ **************************************************************************************/
+
+static void stm3220g_writereg(uint8_t regaddr, uint16_t regval)
+{
+ /* Write the register address then write the register value */
+
+ LCD->address = regaddr;
+ LCD->value = regval;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_readreg
+ *
+ * Description:
+ * Read from an LCD register
+ *
+ **************************************************************************************/
+
+static uint16_t stm3220g_readreg(uint8_t regaddr)
+{
+ /* Write the register address then read the register value */
+
+ LCD->address = regaddr;
+ return LCD->value;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_gramselect
+ *
+ * Description:
+ * Setup to read or write multiple pixels to the GRAM memory
+ *
+ **************************************************************************************/
+
+static inline void stm3220g_gramselect(void)
+{
+ LCD->address = LCD_REG_34;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_writegram
+ *
+ * Description:
+ * Write one pixel to the GRAM memory
+ *
+ **************************************************************************************/
+
+static inline void stm3220g_writegram(uint16_t rgbval)
+{
+ /* Write the value (GRAM register already selected) */
+
+ LCD->value = rgbval;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_readnosetup
+ *
+ * Description:
+ * Prime the operation by reading one pixel from the GRAM memory if necessary for
+ * this LCD type. When reading 16-bit gram data, there may be some shifts in the
+ * returned data:
+ *
+ * - ILI932x: Discard first dummy read; no shift in the return data
+ *
+ **************************************************************************************/
+
+static void stm3220g_readnosetup(FAR uint16_t *accum)
+{
+ /* Read-ahead one pixel */
+
+ *accum = LCD->value;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_readnoshift
+ *
+ * Description:
+ * Read one correctly aligned pixel from the GRAM memory. Possibly shifting the
+ * data and possibly swapping red and green components.
+ *
+ * - ILI932x: Unknown -- assuming colors are in the color order
+ *
+ **************************************************************************************/
+
+static uint16_t stm3220g_readnoshift(FAR uint16_t *accum)
+{
+ /* Read the value (GRAM register already selected) */
+
+ return LCD->value;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_setcursor
+ *
+ * Description:
+ * Set the cursor position. In landscape mode, the "column" is actually the physical
+ * Y position and the "row" is the physical X position.
+ *
+ **************************************************************************************/
+
+static void stm3220g_setcursor(uint16_t col, uint16_t row)
+{
+ stm3220g_writereg(LCD_REG_32, row); /* GRAM horizontal address */
+ stm3220g_writereg(LCD_REG_33, col); /* GRAM vertical address */
+}
+
+/**************************************************************************************
+ * Name: stm3220g_dumprun
+ *
+ * Description:
+ * Dump the contexts of the run buffer:
+ *
+ * run - The buffer in containing the run read to be dumped
+ * npixels - The number of pixels to dump
+ *
+ **************************************************************************************/
+
+#if 0 /* Sometimes useful */
+static void stm3220g_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixels)
+{
+ int i, j;
+
+ lib_rawprintf("\n%s:\n", msg);
+ for (i = 0; i < npixels; i += 16)
+ {
+ up_putc(' ');
+ lib_rawprintf(" ");
+ for (j = 0; j < 16; j++)
+ {
+ lib_rawprintf(" %04x", *run++);
+ }
+ up_putc('\n');
+ }
+}
+#endif
+
+/**************************************************************************************
+ * Name: stm3220g_putrun
+ *
+ * Description:
+ * This method can be used to write a partial raster line to the LCD:
+ *
+ * row - Starting row to write to (range: 0 <= row < yres)
+ * col - Starting column to write to (range: 0 <= col <= xres-npixels)
+ * buffer - The buffer containing the run to be written to the LCD
+ * npixels - The number of pixels to write to the LCD
+ * (range: 0 < npixels <= xres-col)
+ *
+ **************************************************************************************/
+
+static int stm3220g_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
+ size_t npixels)
+{
+ FAR const uint16_t *src = (FAR const uint16_t*)buffer;
+ int i;
+
+ /* Buffer must be provided and aligned to a 16-bit address boundary */
+
+ lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels);
+ DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0);
+
+ /* Write the run to GRAM. */
+
+#ifdef CONFIG_LCD_LANDSCAPE
+ /* Convert coordinates -- Here the edge away from the row of buttons on
+ * the STM3220G-EVAL is used as the top.
+ */
+
+ /* Write the GRAM data, manually incrementing X */
+
+ for (i = 0; i < npixels; i++)
+ {
+ /* Write the next pixel to this position */
+
+ stm3220g_setcursor(col, row);
+ stm3220g_gramselect();
+ stm3220g_writegram(*src++);
+
+ /* Increment to next column */
+
+ col++;
+ }
+#elif defined(CONFIG_LCD_RLANDSCAPE)
+ /* Convert coordinates -- Here the edge next to the row of buttons on
+ * the STM3220G-EVAL is used as the top.
+ */
+
+ col = (STM3220G_XRES-1) - col;
+ row = (STM3220G_YRES-1) - row;
+
+ /* Set the cursor position */
+
+ stm3220g_setcursor(col, row);
+
+ /* Then write the GRAM data, auto-decrementing X */
+
+ stm3220g_gramselect();
+ for (i = 0; i < npixels; i++)
+ {
+ /* Write the next pixel to this position (auto-decrements to the next column) */
+
+ stm3220g_writegram(*src++);
+ }
+#elif defined(CONFIG_LCD_PORTRAIT)
+ /* Convert coordinates. In this configuration, the top of the display is to the left
+ * of the buttons (if the board is held so that the buttons are at the botton of the
+ * board).
+ */
+
+ col = (STM3220G_XRES-1) - col;
+
+ /* Then write the GRAM data, manually incrementing Y (which is col) */
+
+ for (i = 0; i < npixels; i++)
+ {
+ /* Write the next pixel to this position */
+
+ stm3220g_setcursor(row, col);
+ stm3220g_gramselect();
+ stm3220g_writegram(*src++);
+
+ /* Increment to next column */
+
+ col--;
+ }
+#else /* CONFIG_LCD_RPORTRAIT */
+ /* Convert coordinates. In this configuration, the top of the display is to the right
+ * of the buttons (if the board is held so that the buttons are at the botton of the
+ * board).
+ */
+
+ row = (STM3220G_YRES-1) - row;
+
+ /* Then write the GRAM data, manually incrementing Y (which is col) */
+
+ for (i = 0; i < npixels; i++)
+ {
+ /* Write the next pixel to this position */
+
+ stm3220g_setcursor(row, col);
+ stm3220g_gramselect();
+ stm3220g_writegram(*src++);
+
+ /* Decrement to next column */
+
+ col++;
+ }
+#endif
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_getrun
+ *
+ * Description:
+ * This method can be used to read a partial raster line from the LCD:
+ *
+ * row - Starting row to read from (range: 0 <= row < yres)
+ * col - Starting column to read read (range: 0 <= col <= xres-npixels)
+ * buffer - The buffer in which to return the run read from the LCD
+ * npixels - The number of pixels to read from the LCD
+ * (range: 0 < npixels <= xres-col)
+ *
+ **************************************************************************************/
+
+static int stm3220g_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+ size_t npixels)
+{
+ FAR uint16_t *dest = (FAR uint16_t*)buffer;
+ void (*readsetup)(FAR uint16_t *accum);
+ uint16_t (*readgram)(FAR uint16_t *accum);
+ uint16_t accum;
+ int i;
+
+ /* Buffer must be provided and aligned to a 16-bit address boundary */
+
+ lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels);
+ DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0);
+
+ /* Configure according to the LCD type. Kind of silly with only one LCD type. */
+
+ switch (g_lcddev.type)
+ {
+ case LCD_TYPE_ILI9320:
+ case LCD_TYPE_ILI9325:
+ readsetup = stm3220g_readnosetup;
+ readgram = stm3220g_readnoshift;
+ break;
+
+ default: /* Shouldn't happen */
+ return -ENOSYS;
+ }
+
+ /* Read the run from GRAM. */
+
+#ifdef CONFIG_LCD_LANDSCAPE
+ /* Convert coordinates -- Here the edge away from the row of buttons on
+ * the STM3220G-EVAL is used as the top.
+ */
+
+ for (i = 0; i < npixels; i++)
+ {
+ /* Read the next pixel from this position */
+
+ stm3220g_setcursor(row, col);
+ stm3220g_gramselect();
+ readsetup(&accum);
+ *dest++ = readgram(&accum);
+
+ /* Increment to next column */
+
+ col++;
+ }
+#elif defined(CONFIG_LCD_RLANDSCAPE)
+ /* Convert coordinates -- Here the edge next to the row of buttons on
+ * the STM3220G-EVAL is used as the top.
+ */
+
+ col = (STM3220G_XRES-1) - col;
+ row = (STM3220G_YRES-1) - row;
+
+ /* Set the cursor position */
+
+ stm3220g_setcursor(col, row);
+
+ /* Then read the GRAM data, auto-decrementing Y */
+
+ stm3220g_gramselect();
+
+ /* Prime the pump for unaligned read data */
+
+ readsetup(&accum);
+
+ for (i = 0; i < npixels; i++)
+ {
+ /* Read the next pixel from this position (autoincrements to the next row) */
+
+ *dest++ = readgram(&accum);
+ }
+#elif defined(CONFIG_LCD_PORTRAIT)
+ /* Convert coordinates. In this configuration, the top of the display is to the left
+ * of the buttons (if the board is held so that the buttons are at the botton of the
+ * board).
+ */
+
+ col = (STM3220G_XRES-1) - col;
+
+ /* Then read the GRAM data, manually incrementing Y (which is col) */
+
+ for (i = 0; i < npixels; i++)
+ {
+ /* Read the next pixel from this position */
+
+ stm3220g_setcursor(row, col);
+ stm3220g_gramselect();
+ readsetup(&accum);
+ *dest++ = readgram(&accum);
+
+ /* Increment to next column */
+
+ col--;
+ }
+#else /* CONFIG_LCD_RPORTRAIT */
+ /* Convert coordinates. In this configuration, the top of the display is to the right
+ * of the buttons (if the board is held so that the buttons are at the botton of the
+ * board).
+ */
+
+ row = (STM3220G_YRES-1) - row;
+
+ /* Then write the GRAM data, manually incrementing Y (which is col) */
+
+ for (i = 0; i < npixels; i++)
+ {
+ /* Write the next pixel to this position */
+
+ stm3220g_setcursor(row, col);
+ stm3220g_gramselect();
+ readsetup(&accum);
+ *dest++ = readgram(&accum);
+
+ /* Decrement to next column */
+
+ col++;
+ }
+#endif
+
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_getvideoinfo
+ *
+ * Description:
+ * Get information about the LCD video controller configuration.
+ *
+ **************************************************************************************/
+
+static int stm3220g_getvideoinfo(FAR struct lcd_dev_s *dev,
+ FAR struct fb_videoinfo_s *vinfo)
+{
+ DEBUGASSERT(dev && vinfo);
+ lcdvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n",
+ g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes);
+ memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s));
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_getplaneinfo
+ *
+ * Description:
+ * Get information about the configuration of each LCD color plane.
+ *
+ **************************************************************************************/
+
+static int stm3220g_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
+ FAR struct lcd_planeinfo_s *pinfo)
+{
+ DEBUGASSERT(dev && pinfo && planeno == 0);
+ lcdvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp);
+ memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s));
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_getpower
+ *
+ * Description:
+ * Get the LCD panel power status (0: full off - CONFIG_LCD_MAXPOWER: full on). On
+ * backlit LCDs, this setting may correspond to the backlight setting.
+ *
+ **************************************************************************************/
+
+static int stm3220g_getpower(struct lcd_dev_s *dev)
+{
+ lcdvdbg("power: %d\n", 0);
+ return g_lcddev.power;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_poweroff
+ *
+ * Description:
+ * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on). On
+ * backlit LCDs, this setting may correspond to the backlight setting.
+ *
+ **************************************************************************************/
+
+static int stm3220g_poweroff(void)
+{
+ /* Turn the display off */
+
+ stm3220g_writereg(LCD_REG_7, 0);
+
+ /* Remember the power off state */
+
+ g_lcddev.power = 0;
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_setpower
+ *
+ * Description:
+ * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on). On
+ * backlit LCDs, this setting may correspond to the backlight setting.
+ *
+ **************************************************************************************/
+
+static int stm3220g_setpower(struct lcd_dev_s *dev, int power)
+{
+ lcdvdbg("power: %d\n", power);
+ DEBUGASSERT((unsigned)power <= CONFIG_LCD_MAXPOWER);
+
+ /* Set new power level */
+
+ if (power > 0)
+ {
+ /* Then turn the display on */
+
+#if !defined(CONFIG_STM32_ILI9320_DISABLE) || !defined(CONFIG_STM32_ILI9325_DISABLE)
+ stm3220g_writereg(LCD_REG_7, 0x0173);
+#endif
+ g_lcddev.power = power;
+ }
+ else
+ {
+ /* Turn the display off */
+
+ stm3220g_poweroff();
+ }
+
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_getcontrast
+ *
+ * Description:
+ * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+
+static int stm3220g_getcontrast(struct lcd_dev_s *dev)
+{
+ lcdvdbg("Not implemented\n");
+ return -ENOSYS;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_setcontrast
+ *
+ * Description:
+ * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+
+static int stm3220g_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
+{
+ lcdvdbg("contrast: %d\n", contrast);
+ return -ENOSYS;
+}
+
+/**************************************************************************************
+ * Name: stm3220g_lcdinitialize
+ *
+ * Description:
+ * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST).
+ *
+ **************************************************************************************/
+
+static inline void stm3220g_lcdinitialize(void)
+{
+ uint16_t id;
+
+ /* Check LCD ID */
+
+ id = stm3220g_readreg(LCD_REG_0);
+ lcddbg("LCD ID: %04x\n", id);
+
+ /* Check if the ID is for the STM32_ILI9320 (or ILI9321) or STM32_ILI9325 */
+
+#if !defined(CONFIG_STM32_ILI9320_DISABLE) && !defined(CONFIG_STM32_ILI9325_DISABLE)
+ if (id == ILI9320_ID || id == ILI9321_ID || id == ILI9325_ID)
+#elif !defined(CONFIG_STM32_ILI9320_DISABLE) && defined(CONFIG_STM32_ILI9325_DISABLE)
+ if (id == ILI9320_ID || id == ILI9321_ID)
+#else /* if defined(CONFIG_STM32_ILI9320_DISABLE) && !defined(CONFIG_STM32_ILI9325_DISABLE)) */
+ if (id == ILI9325_ID)
+#endif
+ {
+ /* Save the LCD type (not actually used at for anything important) */
+
+#if !defined(CONFIG_STM32_ILI9320_DISABLE)
+# if !defined(CONFIG_STM32_ILI9325_DISABLE)
+ if (id == ILI9325_ID)
+ {
+ g_lcddev.type = LCD_TYPE_ILI9325;
+ }
+ else
+# endif
+ {
+ g_lcddev.type = LCD_TYPE_ILI9320;
+ stm3220g_writereg(LCD_REG_229, 0x8000); /* Set the internal vcore voltage */
+ }
+#else /* if !defined(CONFIG_STM32_ILI9325_DISABLE) */
+ g_lcddev.type = LCD_TYPE_ILI9325;
+#endif
+ lcddbg("LCD type: %d\n", g_lcddev.type);
+
+ /* Start Initial Sequence */
+
+ stm3220g_writereg(LCD_REG_0, 0x0001); /* Start internal OSC. */
+ stm3220g_writereg(LCD_REG_1, 0x0100); /* Set SS and SM bit */
+ stm3220g_writereg(LCD_REG_2, 0x0700); /* Set 1 line inversion */
+ stm3220g_writereg(LCD_REG_3, 0x1030); /* Set GRAM write direction and BGR=1. */
+ //stm3220g_writereg(LCD_REG_3, 0x1018); /* Set GRAM write direction and BGR=1. */
+ stm3220g_writereg(LCD_REG_4, 0x0000); /* Resize register */
+ stm3220g_writereg(LCD_REG_8, 0x0202); /* Set the back porch and front porch */
+ stm3220g_writereg(LCD_REG_9, 0x0000); /* Set non-display area refresh cycle ISC[3:0] */
+ stm3220g_writereg(LCD_REG_10, 0x0000); /* FMARK function */
+ stm3220g_writereg(LCD_REG_12, 0x0000); /* RGB interface setting */
+ stm3220g_writereg(LCD_REG_13, 0x0000); /* Frame marker Position */
+ stm3220g_writereg(LCD_REG_15, 0x0000); /* RGB interface polarity */
+
+ /* Power On sequence */
+
+ stm3220g_writereg(LCD_REG_16, 0x0000); /* SAP, BT[3:0], AP, DSTB, SLP, STB */
+ stm3220g_writereg(LCD_REG_17, 0x0000); /* DC1[2:0], DC0[2:0], VC[2:0] */
+ stm3220g_writereg(LCD_REG_18, 0x0000); /* VREG1OUT voltage */
+ stm3220g_writereg(LCD_REG_19, 0x0000); /* VDV[4:0] for VCOM amplitude */
+ up_mdelay(200); /* Dis-charge capacitor power voltage (200ms) */
+
+ stm3220g_writereg(LCD_REG_16, 0x17b0); /* SAP, BT[3:0], AP, DSTB, SLP, STB */
+ stm3220g_writereg(LCD_REG_17, 0x0137); /* DC1[2:0], DC0[2:0], VC[2:0] */
+ up_mdelay(50);
+
+ stm3220g_writereg(LCD_REG_18, 0x0139); /* VREG1OUT voltage */
+ up_mdelay(50);
+
+ stm3220g_writereg(LCD_REG_19, 0x1d00); /* VDV[4:0] for VCOM amplitude */
+ stm3220g_writereg(LCD_REG_41, 0x0013); /* VCM[4:0] for VCOMH */
+ up_mdelay(50);
+
+ stm3220g_writereg(LCD_REG_32, 0x0000); /* GRAM horizontal Address */
+ stm3220g_writereg(LCD_REG_33, 0x0000); /* GRAM Vertical Address */
+
+ /* Adjust the Gamma Curve (ILI9320/1) */
+
+#if !defined(CONFIG_STM32_ILI9320_DISABLE)
+# if !defined(CONFIG_STM32_ILI9325_DISABLE)
+ if (g_lcddev.type == LCD_TYPE_ILI9320)
+# endif
+ {
+ stm3220g_writereg(LCD_REG_48, 0x0006);
+ stm3220g_writereg(LCD_REG_49, 0x0101);
+ stm3220g_writereg(LCD_REG_50, 0x0003);
+ stm3220g_writereg(LCD_REG_53, 0x0106);
+ stm3220g_writereg(LCD_REG_54, 0x0b02);
+ stm3220g_writereg(LCD_REG_55, 0x0302);
+ stm3220g_writereg(LCD_REG_56, 0x0707);
+ stm3220g_writereg(LCD_REG_57, 0x0007);
+ stm3220g_writereg(LCD_REG_60, 0x0600);
+ stm3220g_writereg(LCD_REG_61, 0x020b);
+ }
+#endif
+ /* Adjust the Gamma Curve (ILI9325) */
+
+#if !defined(CONFIG_STM32_ILI9325_DISABLE)
+# if !defined(CONFIG_STM32_ILI9320_DISABLE)
+ else
+# endif
+ {
+ stm3220g_writereg(LCD_REG_48, 0x0007);
+ stm3220g_writereg(LCD_REG_49, 0x0302);
+ stm3220g_writereg(LCD_REG_50, 0x0105);
+ stm3220g_writereg(LCD_REG_53, 0x0206);
+ stm3220g_writereg(LCD_REG_54, 0x0808);
+ stm3220g_writereg(LCD_REG_55, 0x0206);
+ stm3220g_writereg(LCD_REG_56, 0x0504);
+ stm3220g_writereg(LCD_REG_57, 0x0007);
+ stm3220g_writereg(LCD_REG_60, 0x0105);
+ stm3220g_writereg(LCD_REG_61, 0x0808);
+ }
+#endif
+
+ /* Set GRAM area */
+
+ stm3220g_writereg(LCD_REG_80, 0x0000); /* Horizontal GRAM Start Address */
+ stm3220g_writereg(LCD_REG_81, 0x00ef); /* Horizontal GRAM End Address */
+ stm3220g_writereg(LCD_REG_82, 0x0000); /* Vertical GRAM Start Address */
+ stm3220g_writereg(LCD_REG_83, 0x013f); /* Vertical GRAM End Address */
+ stm3220g_writereg(LCD_REG_96, 0x2700); /* Gate Scan Line */
+ //stm3220g_writereg(LCD_REG_96, 0xa700); /* Gate Scan Line(GS=1, scan direction is G320~G1) */
+ stm3220g_writereg(LCD_REG_97, 0x0001); /* NDL,VLE, REV */
+ stm3220g_writereg(LCD_REG_106, 0x0000); /* Set scrolling line */
+
+ /* Partial Display Control */
+
+ stm3220g_writereg(LCD_REG_128, 0x0000);
+ stm3220g_writereg(LCD_REG_129, 0x0000);
+ stm3220g_writereg(LCD_REG_130, 0x0000);
+ stm3220g_writereg(LCD_REG_131, 0x0000);
+ stm3220g_writereg(LCD_REG_132, 0x0000);
+ stm3220g_writereg(LCD_REG_133, 0x0000);
+
+ /* Panel Control */
+
+ stm3220g_writereg(LCD_REG_144, 0x0010);
+ stm3220g_writereg(LCD_REG_146, 0x0000);
+ stm3220g_writereg(LCD_REG_147, 0x0003);
+ stm3220g_writereg(LCD_REG_149, 0x0110);
+ stm3220g_writereg(LCD_REG_151, 0x0000);
+ stm3220g_writereg(LCD_REG_152, 0x0000);
+
+ /* Set GRAM write direction and BGR = 1
+ *
+ * I/D=01 (Horizontal : increment, Vertical : decrement)
+ * AM=1 (address is updated in vertical writing direction)
+ */
+
+ stm3220g_writereg(LCD_REG_3, 0x1018);
+ stm3220g_writereg(LCD_REG_7, 0); /* Display off */
+ }
+ else
+ {
+ lcddbg("Unsupported LCD type\n");
+ }
+}
+
+ /**************************************************************************************
+ * Public Functions
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: up_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD video hardware. The initial state of the LCD is fully
+ * initialized, display memory cleared, and the LCD ready to use, but with the power
+ * setting at 0 (full off).
+ *
+ **************************************************************************************/
+
+int up_lcdinitialize(void)
+{
+ lcdvdbg("Initializing\n");
+
+ /* Configure GPIO pins and configure the FSMC to support the LCD */
+
+ stm32_selectlcd();
+
+ /* Configure and enable LCD */
+
+ up_mdelay(50);
+ stm3220g_lcdinitialize();
+
+ /* Clear the display (setting it to the color 0=black) */
+
+ stm3220g_lcdclear(0);
+
+ /* Turn the display off */
+
+ stm3220g_poweroff();
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: up_lcdgetdev
+ *
+ * Description:
+ * Return a a reference to the LCD object for the specified LCD. This allows support
+ * for multiple LCD devices.
+ *
+ **************************************************************************************/
+
+FAR struct lcd_dev_s *up_lcdgetdev(int lcddev)
+{
+ DEBUGASSERT(lcddev == 0);
+ return &g_lcddev.dev;
+}
+
+/**************************************************************************************
+ * Name: up_lcduninitialize
+ *
+ * Description:
+ * Unitialize the LCD support
+ *
+ **************************************************************************************/
+
+void up_lcduninitialize(void)
+{
+ stm3220g_poweroff();
+ stm32_deselectlcd();
+}
+
+/**************************************************************************************
+ * Name: stm3220g_lcdclear
+ *
+ * Description:
+ * This is a non-standard LCD interface just for the stm3220g-EVAL board. Because
+ * of the various rotations, clearing the display in the normal way by writing a
+ * sequences of runs that covers the entire display can be very slow. Here the
+ * display is cleared by simply setting all GRAM memory to the specified color.
+ *
+ **************************************************************************************/
+
+void stm3220g_lcdclear(uint16_t color)
+{
+ uint32_t i = 0;
+
+ stm3220g_setcursor(0, STM3220G_XRES-1);
+ stm3220g_gramselect();
+ for (i = 0; i < STM3220G_XRES * STM3220G_YRES; i++)
+ {
+ LCD->value = color;
+ }
+}
+
+#endif /* !CONFIG_STM32_ILI9320_DISABLE || !CONFIG_STM32_ILI9325_DISABLE */
diff --git a/nuttx/configs/stm3220g-eval/src/up_selectlcd.c b/nuttx/configs/stm3220g-eval/src/up_selectlcd.c
new file mode 100644
index 000000000..e8ab375ce
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_selectlcd.c
@@ -0,0 +1,169 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_selectlcd.c
+ * arch/arm/src/board/up_selectlcd.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Diego Sanchez <dsanchez@nx-engineering.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <debug.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm3220g-internal.h"
+
+#ifdef CONFIG_STM32_FSMC
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+#if STM32_NGPIO_PORTS < 6
+# error "Required GPIO ports not enabled"
+#endif
+
+/* SRAM pin definitions */
+
+#define LCD_NADDRLINES 1
+#define LCD_NDATALINES 16
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/* Pin Usage (per schematic)
+ * SRAM LCD
+ * D[0..15] [0..15] [0..15]
+ * A[0..25] [0..22] [0] RS
+ * FSMC_NBL0 PE0 OUT --- ---
+ * FSMC_NBL1 PE1 OUT --- ---
+ * FSMC_NE2 PG9 OUT --- ---
+ * FSMC_NE3 PG10 OUT --- ~CS
+ * FSMC_NE4 PG12 OUT --- ---
+ * FSMC_NWE PD5 OUT --- ~WR/SCL
+ * FSMC_NOE PD4 OUT --- ~RD
+ * FSMC_NWAIT PD6 IN --- ---
+ * FSMC_INT2 PG6* IN --- ---
+ * FSMC_INT3
+ * FSMC_INTR
+ * FSMC_CD
+ * FSMC_CLK
+ * FSMC_NCE2
+ * FSMC_NCE3
+ * FSMC_NCE4_1
+ * FSMC_NCE4_2
+ * FSMC_NIORD
+ * FSMC_NIOWR
+ * FSMC_NL
+ * FSMC_NREG
+ */
+
+/* GPIO configurations unique to the LCD */
+
+static const uint32_t g_lcdconfig[] =
+{
+ /* NOE, NWE, and NE3 */
+
+ GPIO_FSMC_NOE, GPIO_FSMC_NWE, GPIO_FSMC_NE3
+};
+#define NLCD_CONFIG (sizeof(g_lcdconfig)/sizeof(uint32_t))
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_selectlcd
+ *
+ * Description:
+ * Initialize to the LCD
+ *
+ ************************************************************************************/
+
+void stm32_selectlcd(void)
+{
+ /* Configure new GPIO pins */
+
+ stm32_extmemaddr(LCD_NADDRLINES); /* Common address lines: A0 */
+ stm32_extmemdata(LCD_NDATALINES); /* Common data lines: D0-D15 */
+ stm32_extmemgpios(g_lcdconfig, NLCD_CONFIG); /* LCD-specific control lines */
+
+ /* Enable AHB clocking to the FSMC */
+
+ stm32_enablefsmc();
+
+ /* Color LCD configuration (LCD configured as follow):
+ *
+ * - Data/Address MUX = Disable "FSMC_BCR_MUXEN" just not enable it.
+ * - Extended Mode = Disable "FSMC_BCR_EXTMOD"
+ * - Memory Type = SRAM "FSMC_BCR_SRAM"
+ * - Data Width = 16bit "FSMC_BCR_MWID16"
+ * - Write Operation = Enable "FSMC_BCR_WREN"
+ * - Asynchronous Wait = Disable
+ */
+
+ /* Bank3 NOR/SRAM control register configuration */
+
+ putreg32(FSMC_BCR_SRAM | FSMC_BCR_MWID16 | FSMC_BCR_WREN, STM32_FSMC_BCR3);
+
+ /* Bank3 NOR/SRAM timing register configuration */
+
+ putreg32(FSMC_BTR_ADDSET(5) | FSMC_BTR_ADDHLD(0) | FSMC_BTR_DATAST(9) | FSMC_BTR_BUSTRUN(0) |
+ FSMC_BTR_CLKDIV(0) | FSMC_BTR_DATLAT(0) | FSMC_BTR_ACCMODA, STM32_FSMC_BTR3);
+
+ putreg32(0xffffffff, STM32_FSMC_BWTR3);
+
+ /* Enable the bank by setting the MBKEN bit */
+
+ putreg32(FSMC_BCR_MBKEN | FSMC_BCR_SRAM | FSMC_BCR_MWID16 | FSMC_BCR_WREN, STM32_FSMC_BCR3);
+}
+
+#endif /* CONFIG_STM32_FSMC */
+
+
diff --git a/nuttx/configs/stm3220g-eval/src/up_selectsram.c b/nuttx/configs/stm3220g-eval/src/up_selectsram.c
new file mode 100644
index 000000000..8f351223d
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_selectsram.c
@@ -0,0 +1,194 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_selectsram.c
+ * arch/arm/src/board/up_selectsram.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <debug.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm3220g-internal.h"
+
+#ifdef CONFIG_STM32_FSMC
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+#if STM32_NGPIO_PORTS < 6
+# error "Required GPIO ports not enabled"
+#endif
+
+/* SRAM Timing */
+
+#define SRAM_ADDRESS_SETUP_TIME 3
+#define SRAM_ADDRESS_HOLD_TIME 0
+#define SRAM_DATA_SETUP_TIME 6
+#define SRAM_BUS_TURNAROUND_DURATION 1
+#define SRAM_CLK_DIVISION 0
+#define SRAM_DATA_LATENCY 0
+
+/* SRAM pin definitions */
+
+#define SRAM_NADDRLINES 21
+#define SRAM_NDATALINES 16
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+/* GPIOs Configuration **************************************************************
+ * PD0 <-> FSMC_D2 PE0 <-> FSMC_NBL0 PF0 <-> FSMC_A0 PG0 <-> FSMC_A10
+ * PD1 <-> FSMC_D3 PE1 <-> FSMC_NBL1 PF1 <-> FSMC_A1 PG1 <-> FSMC_A11
+ * PD4 <-> FSMC_NOE PE3 <-> FSMC_A19 PF2 <-> FSMC_A2 PG2 <-> FSMC_A12
+ * PD5 <-> FSMC_NWE PE4 <-> FSMC_A20 PF3 <-> FSMC_A3 PG3 <-> FSMC_A13
+ * PD8 <-> FSMC_D13 PE7 <-> FSMC_D4 PF4 <-> FSMC_A4 PG4 <-> FSMC_A14
+ * PD9 <-> FSMC_D14 PE8 <-> FSMC_D5 PF5 <-> FSMC_A5 PG5 <-> FSMC_A15
+ * PD10 <-> FSMC_D15 PE9 <-> FSMC_D6 PF12 <-> FSMC_A6 PG9 <-> FSMC_NE2
+ * PD11 <-> FSMC_A16 PE10 <-> FSMC_D7 PF13 <-> FSMC_A7
+ * PD12 <-> FSMC_A17 PE11 <-> FSMC_D8 PF14 <-> FSMC_A8
+ * PD13 <-> FSMC_A18 PE12 <-> FSMC_D9 PF15 <-> FSMC_A9
+ * PD14 <-> FSMC_D0 PE13 <-> FSMC_D10
+ * PD15 <-> FSMC_D1 PE14 <-> FSMC_D11
+ * PE15 <-> FSMC_D12
+ */
+
+/* GPIO configurations unique to SRAM */
+
+static const uint32_t g_sramconfig[] =
+{
+ /* NE3, NBL0, NBL1, */
+
+ GPIO_FSMC_NOE, GPIO_FSMC_NWE, GPIO_FSMC_NBL0, GPIO_FSMC_NBL1, GPIO_FSMC_NE2
+};
+#define NSRAM_CONFIG (sizeof(g_sramconfig)/sizeof(uint32_t))
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_selectsram
+ *
+ * Description:
+ * Initialize to access external SRAM. SRAM will be visible at the FSMC Bank
+ * NOR/SRAM2 base address (0x64000000)
+ *
+ * General transaction rules. The requested AHB transaction data size can be 8-,
+ * 16- or 32-bit wide whereas the SRAM has a fixed 16-bit data width. Some simple
+ * transaction rules must be followed:
+ *
+ * Case 1: AHB transaction width and SRAM data width are equal
+ * There is no issue in this case.
+ * Case 2: AHB transaction size is greater than the memory size
+ * In this case, the FSMC splits the AHB transaction into smaller consecutive
+ * memory accesses in order to meet the external data width.
+ * Case 3: AHB transaction size is smaller than the memory size.
+ * SRAM supports the byte select feature.
+ * a) FSMC allows write transactions accessing the right data through its
+ * byte lanes (NBL[1:0])
+ * b) Read transactions are allowed (the controller reads the entire memory
+ * word and uses the needed byte only). The NBL[1:0] are always kept low
+ * during read transactions.
+ *
+ ************************************************************************************/
+
+void stm32_selectsram(void)
+{
+ /* Configure new GPIO pins */
+
+ stm32_extmemaddr(SRAM_NADDRLINES); /* Common address lines: A0-A20 */
+ stm32_extmemdata(SRAM_NDATALINES); /* Common data lines: D0-D15 */
+ stm32_extmemgpios(g_sramconfig, NSRAM_CONFIG); /* SRAM-specific control lines */
+
+ /* Enable AHB clocking to the FSMC */
+
+ stm32_enablefsmc();
+
+ /* Bank1 NOR/SRAM control register configuration
+ *
+ * Bank enable : Not yet
+ * Data address mux : Disabled
+ * Memory Type : PSRAM
+ * Data bus width : 16-bits
+ * Flash access : Disabled
+ * Burst access mode : Disabled
+ * Polarity : Low
+ * Wrapped burst mode : Disabled
+ * Write timing : Before state
+ * Write enable : Yes
+ * Wait signal : Disabled
+ * Extended mode : Disabled
+ * Asynchronous wait : Disabled
+ * Write burst : Disabled
+ */
+
+ putreg32((FSMC_BCR_PSRAM | FSMC_BCR_MWID16 | FSMC_BCR_WREN), STM32_FSMC_BCR2);
+
+ /* Bank1 NOR/SRAM timing register configuration */
+
+ putreg32((FSMC_BTR_ADDSET(SRAM_ADDRESS_SETUP_TIME) | FSMC_BTR_ADDHLD(SRAM_ADDRESS_HOLD_TIME) |
+ FSMC_BTR_DATAST(SRAM_DATA_SETUP_TIME) | FSMC_BTR_BUSTRUN(SRAM_BUS_TURNAROUND_DURATION) |
+ FSMC_BTR_CLKDIV(SRAM_CLK_DIVISION) | FSMC_BTR_DATLAT(SRAM_DATA_LATENCY) |
+ FSMC_BTR_ACCMODA),
+ STM32_FSMC_BTR2);
+
+ /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */
+
+ putreg32(0xffffffff, STM32_FSMC_BWTR2); /* Extended mode not used */
+
+ /* Enable the bank */
+
+ putreg32((FSMC_BCR_MBKEN | FSMC_BCR_PSRAM | FSMC_BCR_MWID16 | FSMC_BCR_WREN), STM32_FSMC_BCR2);
+}
+
+#endif /* CONFIG_STM32_FSMC */
+
+
diff --git a/nuttx/configs/stm3220g-eval/src/up_stmpe11.c b/nuttx/configs/stm3220g-eval/src/up_stmpe11.c
new file mode 100644
index 000000000..eee765364
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_stmpe11.c
@@ -0,0 +1,353 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_touchscreen.c
+ * arch/arm/src/board/up_touchscreen.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/i2c.h>
+#include <nuttx/input/touchscreen.h>
+#include <nuttx/input/stmpe11.h>
+
+#include <arch/irq.h>
+
+#include "stm32_internal.h"
+#include "stm3220g-internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifdef CONFIG_INPUT_STMPE11
+#ifndef CONFIG_INPUT
+# error "STMPE11 support requires CONFIG_INPUT"
+#endif
+
+#ifndef CONFIG_STM32_I2C1
+# error "STMPE11 support requires CONFIG_STM32_I2C1"
+#endif
+
+#ifndef CONFIG_STMPE11_I2C
+# error "Only the STMPE11 I2C interface is supported"
+#endif
+
+#ifdef CONFIG_STMPE11_SPI
+# error "Only the STMPE11 SPI interface is supported"
+#endif
+
+#ifndef CONFIG_STMPE11_FREQUENCY
+# define CONFIG_STMPE11_FREQUENCY 100000
+#endif
+
+#ifndef CONFIG_STMPE11_I2CDEV
+# define CONFIG_STMPE11_I2CDEV 1
+#endif
+
+#if CONFIG_STMPE11_I2CDEV != 1
+# error "CONFIG_STMPE11_I2CDEV must be one"
+#endif
+
+#ifndef CONFIG_STMPE11_DEVMINOR
+# define CONFIG_STMPE11_DEVMINOR 0
+#endif
+
+/* Board definitions ********************************************************/
+/* The STM3220G-EVAL has two STMPE11QTR I/O expanders on board both connected
+ * to the STM32 via I2C1. They share a common interrupt line: PI2.
+ *
+ * STMPE11 U24, I2C address 0x41 (7-bit)
+ * ------ ---- ---------------- --------------------------------------------
+ * STPE11 PIN BOARD SIGNAL BOARD CONNECTION
+ * ------ ---- ---------------- --------------------------------------------
+ * Y- TouchScreen_Y- LCD Connector XL
+ * X- TouchScreen_X- LCD Connector XR
+ * Y+ TouchScreen_Y+ LCD Connector XD
+ * X+ TouchScreen_X+ LCD Connector XU
+ * IN3 EXP_IO9
+ * IN2 EXP_IO10
+ * IN1 EXP_IO11
+ * IN0 EXP_IO12
+ *
+ * STMPE11 U29, I2C address 0x44 (7-bit)
+ * ------ ---- ---------------- --------------------------------------------
+ * STPE11 PIN BOARD SIGNAL BOARD CONNECTION
+ * ------ ---- ---------------- --------------------------------------------
+ * Y- EXP_IO1
+ * X- EXP_IO2
+ * Y+ EXP_IO3
+ * X+ EXP_IO4
+ * IN3 EXP_IO5
+ * IN2 EXP_IO6
+ * IN1 EXP_IO7
+ * IN0 EXP_IO8
+ */
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct stm32_stmpe11config_s
+{
+ /* Configuration structure as seen by the STMPE11 driver */
+
+ struct stmpe11_config_s config;
+
+ /* Additional private definitions only known to this driver */
+
+ STMPE11_HANDLE handle; /* The STMPE11 driver handle */
+ xcpt_t handler; /* The STMPE11 interrupt handler */
+};
+
+/****************************************************************************
+ * Static Function Prototypes
+ ****************************************************************************/
+
+/* IRQ/GPIO access callbacks. These operations all hidden behind callbacks
+ * to isolate the STMPE11 driver from differences in GPIO
+ * interrupt handling by varying boards and MCUs.* so that contact and loss-of-contact events can be detected.
+ *
+ * attach - Attach the STMPE11 interrupt handler to the GPIO interrupt
+ * enable - Enable or disable the GPIO interrupt
+ * clear - Acknowledge/clear any pending GPIO interrupt
+ */
+
+static int stmpe11_attach(FAR struct stmpe11_config_s *state, xcpt_t isr);
+static void stmpe11_enable(FAR struct stmpe11_config_s *state, bool enable);
+static void stmpe11_clear(FAR struct stmpe11_config_s *state);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* A reference to a structure of this type must be passed to the STMPE11
+ * driver. This structure provides information about the configuration
+ * of the STMPE11 and provides some board-specific hooks.
+ *
+ * Memory for this structure is provided by the caller. It is not copied
+ * by the driver and is presumed to persist while the driver is active. The
+ * memory must be writable because, under certain circumstances, the driver
+ * may modify frequency or X plate resistance values.
+ */
+
+#ifndef CONFIG_STMPE11_TSC_DISABLE
+static struct stm32_stmpe11config_s g_stmpe11config =
+{
+ .config =
+ {
+#ifdef CONFIG_STMPE11_I2C
+ .address = STMPE11_ADDR1,
+#endif
+ .frequency = CONFIG_STMPE11_FREQUENCY,
+
+#ifdef CONFIG_STMPE11_MULTIPLE
+ .irq = STM32_IRQ_EXTI2,
+#endif
+ .ctrl1 = (ADC_CTRL1_SAMPLE_TIME_80 | ADC_CTRL1_MOD_12B),
+ .ctrl2 = ADC_CTRL2_ADC_FREQ_3p25,
+
+ .attach = stmpe11_attach,
+ .enable = stmpe11_enable,
+ .clear = stmpe11_clear,
+ },
+ .handler = NULL,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/* IRQ/GPIO access callbacks. These operations all hidden behind
+ * callbacks to isolate the STMPE11 driver from differences in GPIO
+ * interrupt handling by varying boards and MCUs.
+ *
+ * attach - Attach the STMPE11 interrupt handler to the GPIO interrupt
+ * enable - Enable or disable the GPIO interrupt
+ * clear - Acknowledge/clear any pending GPIO interrupt
+ */
+
+static int stmpe11_attach(FAR struct stmpe11_config_s *state, xcpt_t isr)
+{
+ FAR struct stm32_stmpe11config_s *priv = (FAR struct stm32_stmpe11config_s *)state;
+
+ ivdbg("Saving handler %p\n", isr);
+ DEBUGASSERT(priv);
+
+ /* Just save the handler. We will use it when EXTI interruptsare enabled */
+
+ priv->handler = isr;
+ return OK;
+}
+
+static void stmpe11_enable(FAR struct stmpe11_config_s *state, bool enable)
+{
+ FAR struct stm32_stmpe11config_s *priv = (FAR struct stm32_stmpe11config_s *)state;
+ irqstate_t flags;
+
+ /* Attach and enable, or detach and disable. Enabling and disabling GPIO
+ * interrupts is a multi-step process so the safest thing is to keep
+ * interrupts disabled during the reconfiguratino.
+ */
+
+ flags = irqsave();
+ if (enable)
+ {
+ /* Configure the EXTI interrupt using the SAVED handler */
+
+ (void)stm32_gpiosetevent(GPIO_IO_EXPANDER, true, true, true, priv->handler);
+ }
+ else
+ {
+ /* Configure the EXTI interrupt with a NULL handler to disable it */
+
+ (void)stm32_gpiosetevent(GPIO_IO_EXPANDER, false, false, false, NULL);
+ }
+ irqrestore(flags);
+}
+
+static void stmpe11_clear(FAR struct stmpe11_config_s *state)
+{
+ /* Does nothing */
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: arch_tcinitialize
+ *
+ * Description:
+ * Each board that supports a touchscreen device must provide this function.
+ * This function is called by application-specific, setup logic to
+ * configure the touchscreen device. This function will register the driver
+ * as /dev/inputN where N is the minor device number.
+ *
+ * Input Parameters:
+ * minor - The input device minor number
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+int arch_tcinitialize(int minor)
+{
+#ifndef CONFIG_STMPE11_TSC_DISABLE
+ FAR struct i2c_dev_s *dev;
+ int ret;
+
+ idbg("minor %d\n", minor);
+ DEBUGASSERT(minor == 0);
+
+ /* Check if we are already initialized */
+
+ if (!g_stmpe11config.handle)
+ {
+ ivdbg("Initializing\n");
+
+ /* Configure the STMPE11 interrupt pin as an input */
+
+ (void)stm32_configgpio(GPIO_IO_EXPANDER);
+
+ /* Get an instance of the I2C interface */
+
+ dev = up_i2cinitialize(CONFIG_STMPE11_I2CDEV);
+ if (!dev)
+ {
+ idbg("Failed to initialize I2C bus %d\n", CONFIG_STMPE11_I2CDEV);
+ return -ENODEV;
+ }
+
+ /* Instantiate the STMPE11 driver */
+
+ g_stmpe11config.handle =
+ stmpe11_instantiate(dev, (FAR struct stmpe11_config_s *)&g_stmpe11config);
+ if (!g_stmpe11config.handle)
+ {
+ idbg("Failed to instantiate the STMPE11 driver\n");
+ return -ENODEV;
+ }
+
+ /* Initialize and register the I2C touchscreen device */
+
+ ret = stmpe11_register(g_stmpe11config.handle, CONFIG_STMPE11_DEVMINOR);
+ if (ret < 0)
+ {
+ idbg("Failed to register STMPE driver: %d\n", ret);
+ /* up_i2cuninitialize(dev); */
+ return -ENODEV;
+ }
+ }
+
+ return OK;
+#else
+ return -ENOSYS;
+#endif
+}
+
+/****************************************************************************
+ * Name: arch_tcuninitialize
+ *
+ * Description:
+ * Each board that supports a touchscreen device must provide this function.
+ * This function is called by application-specific, setup logic to
+ * uninitialize the touchscreen device.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void arch_tcuninitialize(void)
+{
+ /* No support for un-initializing the touchscreen STMPE11 device yet */
+}
+
+#endif /* CONFIG_INPUT_STMPE11 */
+
diff --git a/nuttx/configs/stm3220g-eval/src/up_usbdev.c b/nuttx/configs/stm3220g-eval/src/up_usbdev.c
new file mode 100644
index 000000000..10d99571c
--- /dev/null
+++ b/nuttx/configs/stm3220g-eval/src/up_usbdev.c
@@ -0,0 +1,103 @@
+/************************************************************************************
+ * configs/stm3220g-eval/src/up_usbdev.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "up_arch.h"
+#include "stm32_internal.h"
+#include "stm3220g-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the STM3210E-EVAL board.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void)
+{
+ /* The OTG FS has an internal soft pull-up */
+
+ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
+
+#ifdef CONFIG_STM32_OTGFS
+ stm32_configgpio(GPIO_OTGFS_VBUS);
+ stm32_configgpio(GPIO_OTGFS_PWRON);
+ stm32_configgpio(GPIO_OTGFS_OVER);
+#endif
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+
diff --git a/nuttx/configs/stm3220g-eval/telnetd/defconfig b/nuttx/configs/stm3220g-eval/telnetd/defconfig
index 5490234ec..0a526bd92 100644
--- a/nuttx/configs/stm3220g-eval/telnetd/defconfig
+++ b/nuttx/configs/stm3220g-eval/telnetd/defconfig
@@ -118,14 +118,6 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
-# On-chip CCM SRAM configuration
-#
-# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
-# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
-# being a part of the stack.
-#
-
-#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -147,7 +139,6 @@ CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
# AHB1:
CONFIG_STM32_CRC=n
CONFIG_STM32_BKPSRAM=n
-CONFIG_STM32_CCMDATARAM=n
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=n
CONFIG_STM32_ETHMAC=y
diff --git a/nuttx/configs/stm3220g-eval/telnetd/ld.script b/nuttx/configs/stm3220g-eval/telnetd/ld.script
index 40ab6eada..f4ecb084a 100644
--- a/nuttx/configs/stm3220g-eval/telnetd/ld.script
+++ b/nuttx/configs/stm3220g-eval/telnetd/ld.script
@@ -34,11 +34,10 @@
****************************************************************************/
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
+ * 128Kb of SRAM. SRAM is split up into two blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
- * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index 1c15be2ca..64d5608f3 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -18,7 +18,7 @@ Contents
- CAN
- FPU
- FSMC SRAM
- - I/O Exanders
+ - I/O Expanders
- STM3240G-EVAL-specific Configuration Options
- Configurations
@@ -40,7 +40,7 @@ GNU Toolchain Options
toolchain options.
1. The CodeSourcery GNU toolchain,
- 2. The Atollic Toolchain,
+ 2. The Atollic Toolchain,
3. The devkitARM GNU toolchain,
4. Raisonance GNU toolchain, or
5. The NuttX buildroot Toolchain (see below).
@@ -128,7 +128,7 @@ GNU Toolchain Options
In order to compile successfully. Otherwise, you will get errors like:
"C++ Compiler only available in TrueSTUDIO Professional"
-
+
The make may then fail in some of the post link processing because of some of
the other missing tools. The Make.defs file replaces the ar and nm with
the default system x86 tool versions and these seem to work okay. Disable all
@@ -150,7 +150,7 @@ IDEs
NuttX is built using command-line make. It can be used with an IDE, but some
effort will be required to create the project.
-
+
Makefile Build
--------------
Under Eclipse, it is pretty easy to set up an "empty makefile project" and
@@ -236,17 +236,17 @@ defined. In that case, the usage by the board port is defined in
include/board.h and src/up_leds.c. The LEDs are used to encode OS-related\
events as follows:
- SYMBOL Meaning LED1* LED2 LED3 LED4
- ------------------- ----------------------- ------- ------- ------- ------
- LED_STARTED NuttX has been started ON OFF OFF OFF
- LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
- LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
- LED_STACKCREATED Idle stack created OFF OFF ON OFF
- LED_INIRQ In an interrupt** ON N/C N/C OFF
- LED_SIGNAL In a signal handler*** N/C ON N/C OFF
- LED_ASSERTION An assertion failed ON ON N/C OFF
- LED_PANIC The system has crashed N/C N/C N/C ON
- LED_IDLE STM32 is is sleep mode (Optional, not used)
+ SYMBOL Meaning LED1* LED2 LED3 LED4
+ ------------------- ----------------------- ------- ------- ------- ------
+ LED_STARTED NuttX has been started ON OFF OFF OFF
+ LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
+ LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
+ LED_STACKCREATED Idle stack created OFF OFF ON OFF
+ LED_INIRQ In an interrupt** ON N/C N/C OFF
+ LED_SIGNAL In a signal handler*** N/C ON N/C OFF
+ LED_ASSERTION An assertion failed ON ON N/C OFF
+ LED_PANIC The system has crashed N/C N/C N/C ON
+ LED_IDLE STM32 is is sleep mode (Optional, not used)
* If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot
and these LEDs will give you some indication of where the failure was
@@ -269,7 +269,7 @@ not enabled, then FSMC_A18 will not be used (and will be tri-stated from
the LCD).
CONFIGURATION:
-
+
CONFIG_STM32_TIM4=y
CONFIG_PWM=n
CONFIG_PWM_PULSECOUNT=n
@@ -287,7 +287,7 @@ TIM8 CH4: Pin PC9 is used by the microSD card (MicroSDCard_D1) and I2S
(I2S_CKIN) but can be completely disconnected from both by opening JP16.
CONFIGURATION:
-
+
CONFIG_STM32_TIM8=y
CONFIG_PWM=n
CONFIG_PWM_PULSECOUNT=y
@@ -314,8 +314,8 @@ CAN signals are then available on CN10 pins:
Mapping to STM32 GPIO pins:
- PD0 = FSMC_D2 & CAN1_RX
- PD1 = FSMC_D3 & CAN1_TX
+ PD0 = FSMC_D2 & CAN1_RX
+ PD1 = FSMC_D3 & CAN1_TX
PB13 = ULPI_D6 & CAN2_TX
PB5 = ULPI_D7 & CAN2_RX
@@ -396,7 +396,7 @@ the following lines in each Make.defs file:
If you are using a toolchain other than the Atollic toolchain, then to use the FPU
you will also have to modify the CFLAGS to enable compiler support for the ARMv7-M
FPU. As of this writing, there are not many GCC toolchains that will support the
-ARMv7-M FPU.
+ARMv7-M FPU.
As a minimum you will need to add CFLAG options to (1) enable hardware floating point
code generation, and to (2) select the FPU implementation. You might try the same
@@ -469,13 +469,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
+ address space
CONFIG_HEAP2_END : The end (+1) of the SRAM in the FSMC
- address space
+ address space
CONFIG_MM_REGIONS : Must be set to a large enough value to
- include the FSMC SRAM
+ include the FSMC SRAM
SRAM Configurations
-------------------
@@ -497,8 +497,8 @@ There are 4 possible SRAM configurations:
CONFIG_MM_REGIONS == 3
CONFIG_STM32_FSMC_SRAM defined
CONFIG_STM32_CCMEXCLUDE NOT defined
-I/O Exanders
-============
+I/O Expanders
+=============
The STM3240G-EVAL has two STMPE11QTR I/O expanders on board both connected to
the STM32 via I2C1. They share a common interrupt line: PI2.
@@ -558,7 +558,7 @@ STM3240G-EVAL-specific Configuration Options
configuration features.
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n
-
+
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
hence, the board that supports the particular chip or SoC.
@@ -718,7 +718,7 @@ STM3240G-EVAL-specific Configuration Options
configuration settings:
CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
-
+
NOTE: The STM32 timers are each capable of generating different signals on
each of the four channels with different duty cycles. That capability is
not supported by this driver: Only one output channel per timer.
@@ -752,7 +752,7 @@ STM3240G-EVAL-specific Configuration Options
CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
and CONFIG_STM32_DMA2.
CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128
- CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
+ CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
Default: Medium
CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
4-bit transfer mode.
@@ -802,7 +802,7 @@ STM3240G-EVAL-specific Configuration Options
The LCD driver supports the following LCDs on the STM324xG_EVAL board:
- AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) OR
+ AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) OR
AM-240320D5TOQW01H (LCD_ILI9325)
Configuration options.
@@ -920,7 +920,7 @@ Where <subdir> is one of the following:
CONFIG_STM32_TIM4=y : Enable TIM4
CONFIG_STM32_TIM4_PWM=y : Use TIM4 to generate PWM output
CONFIG_STM32_TIM4_CHANNEL=2 : Select output on TIM4, channel 2
-
+
If CONFIG_STM32_FSMC is disabled, output will appear on CN3, pin 32.
Ground is available on CN3, pin1.
@@ -950,7 +950,7 @@ Where <subdir> is one of the following:
CONFIG_CAN_LOOPBACK=y : Enable CAN loopback mode
See also apps/examples/README.txt
-
+
Special CAN-only debug options:
CONFIG_DEBUG_CAN
@@ -991,7 +991,7 @@ Where <subdir> is one of the following:
The IWDG timer has a range of about 35 seconds and should not be an issue.
7. Adding LCD and graphics support:
-
+
appconfig (apps/.config): Enable the application configurations that you
want to use. Asexamples:
@@ -1000,8 +1000,8 @@ Where <subdir> is one of the following:
CONFIGURED_APPS += examples/nximage :
CONFIGURED_APPS += examples/nxlines :
- defconfig (nuttx/.config):
-
+ defconfig (nuttx/.config):
+
CONFIG_STM32_FSMC=y : FSMC support is required for the LCD
CONFIG_NX=y : Enable graphics suppport
CONFIG_MM_REGIONS=3 : When FSMC is enabled, so is the on-board SRAM memory region
@@ -1024,8 +1024,8 @@ Where <subdir> is one of the following:
Logically, these are the only differences: This configuration has SDIO (and
the SD card) enabled and the serial console disabled. There is ONLY a
Telnet console!.
-
- There are some special settings to make life with only a Telnet
+
+ There are some special settings to make life with only a Telnet
CONFIG_SYSLOG=y - Enables the System Logging feature.
CONFIG_RAMLOG=y - Enable the RAM-based logging feature.
@@ -1058,8 +1058,8 @@ Where <subdir> is one of the following:
0x2000:0000 and 64Kb of "CCM" SRAM located at 0x1000:0000. It appears
that you cannot perform DMA from CCM SRAM. The work around that I have now
is simply to omit the 64Kb of CCM SRAM from the heap so that all memory is
- allocated from System SRAM. This is done by setting:
-
+ allocated from System SRAM. This is done by setting:
+
CONFIG_MM_REGIONS=1
Then DMA works fine. The downside is, of course, is that we lose 64Kb
@@ -1099,7 +1099,7 @@ Where <subdir> is one of the following:
CONFG_NX_MULTIUSER=y
CONFIG_DISABLE_MQUEUE=n
-
+
The following definition in the defconfig file to enables the NxConsole
driver:
@@ -1164,7 +1164,7 @@ Where <subdir> is one of the following:
bytes (see arch/arm/include/armv7-m/irq_lazyfpu.h):
+CONFIG_EXAMPLES_OSTEST_FPUSIZE=(4*33)
-
+
telnetd:
--------
diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig
index 0d298f520..26b29a51d 100644
--- a/nuttx/configs/stm3240g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh/defconfig
@@ -1014,6 +1014,7 @@ CONFIG_STMPE11_TEMP_DISABLE=y
CONFIG_STMPE11_REGDEBUG=n
CONFIG_STMPE11_THRESHX=26
CONFIG_STMPE11_THRESHY=34
+
#
# USB Device Configuration
#
@@ -1688,7 +1689,7 @@ CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN=y
CONFIG_EXAMPLES_TOUCHSCREEN_MINOR=0
CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH="/dev/input0"
CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25
-
+
#
# Settings for examples/usbstorage
#