summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-11-21 14:25:38 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-11-21 14:25:38 +0000
commitc0a3967f7a05e6bef02a3277d4f4f0ffe2128514 (patch)
tree12eacbc8ff5ef3be916bb71b319d397bb0e436fe /nuttx/arch
parent725c73be041790f7010e1e947cec6a504afbf952 (diff)
downloadpx4-nuttx-c0a3967f7a05e6bef02a3277d4f4f0ffe2128514.tar.gz
px4-nuttx-c0a3967f7a05e6bef02a3277d4f4f0ffe2128514.tar.bz2
px4-nuttx-c0a3967f7a05e6bef02a3277d4f4f0ffe2128514.zip
More STM3240 header file changes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4109 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_flash.h145
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_i2c.h12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_flash.c17
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_flash.h4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_fsmc.h23
5 files changed, 146 insertions, 55 deletions
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_flash.h b/nuttx/arch/arm/src/stm32/chip/stm32_flash.h
index 018d3e8ab..8f60234ae 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_flash.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_flash.h
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/chip/stm32_flash.h
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -40,18 +40,21 @@
* Pre-processor Definitions
************************************************************************************/
-#ifdef CONFIG_STM32_LOWDENSITY
+#ifdef defined(CONFIG_STM32_LOWDENSITY)
# define STM32_FLASH_NPAGES 32
# define STM32_FLASH_PAGESIZE 1024
-#elif CONFIG_STM32_MEDIUMDENSITY
+#elif defined(CONFIG_STM32_MEDIUMDENSITY)
# define STM32_FLASH_NPAGES 128
# define STM32_FLASH_PAGESIZE 1024
-#elif CONFIG_STM32_CONNECTIVITYLINE
+#elif defined(CONFIG_STM32_CONNECTIVITYLINE)
# define STM32_FLASH_NPAGES 128
# define STM32_FLASH_PAGESIZE 2048
-#elif CONFIG_STM32_HIGHDENSITY
+#elif defined(CONFIG_STM32_HIGHDENSITY)
# define STM32_FLASH_NPAGES 256
# define STM32_FLASH_PAGESIZE 2048
+#elif defined(CONFIG_STM32_STM32F40XX)
+# define STM32_FLASH_NPAGES 8
+# define CONFIG_STM32_STM32F40XX (128*1024)
#endif
#define STM32_FLASH_SIZE (STM32_FLASH_NPAGES * STM32_FLASH_PAGESIZE)
@@ -63,9 +66,14 @@
#define STM32_FLASH_OPTKEYR_OFFSET 0x0008
#define STM32_FLASH_SR_OFFSET 0x000c
#define STM32_FLASH_CR_OFFSET 0x0010
-#define STM32_FLASH_AR_OFFSET 0x0014
-#define STM32_FLASH_OBR_OFFSET 0x001c
-#define STM32_FLASH_WRPR_OFFSET 0x0020
+
+#if defined(CONFIG_STM32_STM32F10XX)
+# define STM32_FLASH_AR_OFFSET 0x0014
+# define STM32_FLASH_OBR_OFFSET 0x001c
+# define STM32_FLASH_WRPR_OFFSET 0x0020
+#elif defined(CONFIG_STM32_STM32F40XX)
+# define STM32_FLASH_OPTCR_OFFSET 0x0014
+#endif
/* Register Addresses ***************************************************************/
@@ -74,42 +82,109 @@
#define STM32_FLASH_OPTKEYR (STM32_FLASHIF_BASE+STM32_FLASH_OPTKEYR_OFFSET)
#define STM32_FLASH_SR (STM32_FLASHIF_BASE+STM32_FLASH_SR_OFFSET)
#define STM32_FLASH_CR (STM32_FLASHIF_BASE+STM32_FLASH_CR_OFFSET)
-#define STM32_FLASH_AR (STM32_FLASHIF_BASE+STM32_FLASH_AR_OFFSET)
-#define STM32_FLASH_OBR (STM32_FLASHIF_BASE+STM32_FLASH_OBR_OFFSET)
-#define STM32_FLASH_WRPR (STM32_FLASHIF_BASE+STM32_FLASH_WRPR_OFFSET)
+
+#if defined(CONFIG_STM32_STM32F10XX)
+# define STM32_FLASH_AR (STM32_FLASHIF_BASE+STM32_FLASH_AR_OFFSET)
+# define STM32_FLASH_OBR (STM32_FLASHIF_BASE+STM32_FLASH_OBR_OFFSET)
+# define STM32_FLASH_WRPR (STM32_FLASHIF_BASE+STM32_FLASH_WRPR_OFFSET)
+#elif defined(CONFIG_STM32_STM32F40XX)
+# define STM32_FLASH_OPTCR (STM32_FLASHIF_BASE+STM32_FLASH_OPTCR_OFFSET)
+#endif
/* Register Bitfield Definitions ****************************************************/
-/* TODO: Complete FLASH details from the STM32F10xxx Flash programming manual. */
+/* Flash Access Control Register (ACR) */
+
+#define FLASH_ACR_LATENCY_SHIFT (0)
+#define FLASH_ACR_LATENCY_MASK (7 << FLASH_ACR_LATENCY_SHIFT)
+# define FLASH_ACR_LATENCY(n) ((n) << FLASH_ACR_LATENCY_SHIFT) /* n wait states */
+# define FLASH_ACR_LATENCY_0 (0 << FLASH_ACR_LATENCY_SHIFT) /* 000: Zero wait states */
+# define FLASH_ACR_LATENCY_1 (1 << FLASH_ACR_LATENCY_SHIFT) /* 001: One wait state */
+# define FLASH_ACR_LATENCY_2 (2 << FLASH_ACR_LATENCY_SHIFT) /* 010: Two wait states */
+# define FLASH_ACR_LATENCY_3 (3 << FLASH_ACR_LATENCY_SHIFT) /* 011: Three wait states */
+# define FLASH_ACR_LATENCY_4 (4 << FLASH_ACR_LATENCY_SHIFT) /* 100: Four wait states */
+# define FLASH_ACR_LATENCY_5 (5 << FLASH_ACR_LATENCY_SHIFT) /* 101: Five wait states */
+# define FLASH_ACR_LATENCY_6 (6 << FLASH_ACR_LATENCY_SHIFT) /* 110: Six wait states */
+# define FLASH_ACR_LATENCY_7 (7 << FLASH_ACR_LATENCY_SHIFT) /* 111: Seven wait states */
+
+#if defined(CONFIG_STM32_STM32F10XX)
+# define FLASH_ACR_HLFCYA (1 << 3) /* FLASH half cycle access */
+# define FLASH_ACR_PRTFBE (1 << 4) /* FLASH prefetch enable */
+#elif defined(CONFIG_STM32_STM32F40XX)
+# define FLASH_ACR_ICEN (1 << 9) /* Bit 9: Instruction cache enable */
+# define FLASH_ACR_DCEN (1 << 10) /* Bit 10: Data cache enable */
+# define FLASH_ACR_ICRST (1 << 11) /* Bit 11: Instruction cache reset */
+# define FLASH_ACR_DCRST (1 << 12) /* Bit 12: Data cache reset */
+#endif
/* Flash Status Register (SR) */
-#define FLASH_SR_BSY (1 << 0) /* Busy */
-#define FLASH_SR_PGERR (1 << 2) /* Programming Error */
-#define FLASH_SR_WRPRT_ERR (1 << 4) /* Write Protection Error */
-#define FLASH_SR_EOP (1 << 5) /* End of Operation */
+#if defined(CONFIG_STM32_STM32F10XX)
+# define FLASH_SR_BSY (1 << 0) /* Busy */
+# define FLASH_SR_PGERR (1 << 2) /* Programming Error */
+# define FLASH_SR_WRPRT_ERR (1 << 4) /* Write Protection Error */
+# define FLASH_SR_EOP (1 << 5) /* End of Operation */
+#elif defined(CONFIG_STM32_STM32F40XX)
+# define FLASH_SR_EOP (1 << 0) /* Bit 0: End of operation */
+# define FLASH_SR_OPERR (1 << 1) /* Bit 1: Operation error */
+# define FLASH_SR_WRPERR (1 << 4) /* Bit 4: Write protection error */
+# define FLASH_SR_PGAERR (1 << 5) /* Bit 5: Programming alignment error */
+# define FLASH_SR_PGPERR (1 << 6) /* Bit 6: Programming parallelism error */
+# define FLASH_SR_PGSERR (1 << 7) /* Bit 7: Programming sequence error */
+# define FLASH_SR_BSY (1 << 16) /* Bit 16: Busy */
+#endif
/* Flash Control Register (CR) */
-#define FLASH_CR_PG (1 << 0) /* Program Page */
-#define FLASH_CR_PER (1 << 1) /* Page Erase */
-#define FLASH_CR_MER (1 << 2) /* Mass Erase */
-#define FLASH_CR_OPTPG (1 << 4) /* Option Byte Programming */
-#define FLASH_CR_OPTER (1 << 5) /* Option Byte Erase */
-#define FLASH_CR_STRT (1 << 6) /* Start Erase */
-#define FLASH_CR_LOCK (1 << 7) /* Page Locked or Lock Page */
-#define FLASH_CR_OPTWRE (1 << 9) /* Option Bytes Write Enable */
-#define FLASH_CR_ERRIE (1 << 10) /* Error Interrupt Enable */
-#define FLASH_CR_EOPIE (1 << 12) /* End of Program Interrupt Enable */
-
-/* Flash Access Control Register (ACR) */
+#if defined(CONFIG_STM32_STM32F10XX)
+# define FLASH_CR_PG (1 << 0) /* Program Page */
+# define FLASH_CR_PER (1 << 1) /* Page Erase */
+# define FLASH_CR_MER (1 << 2) /* Mass Erase */
+# define FLASH_CR_OPTPG (1 << 4) /* Option Byte Programming */
+# define FLASH_CR_OPTER (1 << 5) /* Option Byte Erase */
+# define FLASH_CR_STRT (1 << 6) /* Start Erase */
+# define FLASH_CR_LOCK (1 << 7) /* Page Locked or Lock Page */
+# define FLASH_CR_OPTWRE (1 << 9) /* Option Bytes Write Enable */
+# define FLASH_CR_ERRIE (1 << 10) /* Error Interrupt Enable */
+# define FLASH_CR_EOPIE (1 << 12) /* End of Program Interrupt Enable */
+#elif defined(CONFIG_STM32_STM32F40XX)
+# define FLASH_CR_PG (1 << 0) /* Bit 0: Programming */
+# define FLASH_CR_SER (1 << 1) /* Bit 1: Sector Erase */
+# define FLASH_CR_MER (1 << 2) /* Bit 2: Mass Erase */
+# define FLASH_CR_SNB_SHIFT (3) /* Bits 3-6: Sector number */
+# define FLASH_CR_SNB_MASK (15 << FLASH_CR_SNB_SHIFT)
+# define FLASH_CR_SNB(n) ((n) << FLASH_CR_SNB_SHIFT) /* Sector n, n=0..11 */
+# define FLASH_CR_PSIZE_SHIFT (8) /* Bits 8-9: Program size */
+# define FLASH_CR_PSIZE_MASK (3 << FLASH_CR_PSIZE_SHIFT)
+# define FLASH_CR_PSIZE_X8 (0 << FLASH_CR_PSIZE_SHIFT) /* 00 program x8 */
+# define FLASH_CR_PSIZE_X16 (1 << FLASH_CR_PSIZE_SHIFT) /* 01 program x16 */
+# define FLASH_CR_PSIZE_X32 (2 << FLASH_CR_PSIZE_SHIFT) /* 10 program x32 */
+# define FLASH_CR_PSIZE_X64 (3 << FLASH_CR_PSIZE_SHIFT) /* 11 program x64 */
+# define FLASH_CR_EOPIE (1 << 24) /* Bit 24: End of operation interrupt enable */
+# define FLASH_CR_ERRIE (1 << 25) /* Bit 25: Error interrupt enable */
+# define FLASH_CR_LOCK (1 << 31) /* Bit 31: Lock */
+#endif
-#define FLASH_ACR_LATENCY_SHIFT (0)
-#define FLASH_ACR_LATENCY_MASK (7 << FLASH_ACR_LATENCY_SHIFT)
-# define FLASH_ACR_LATENCY_0 (0 << FLASH_ACR_LATENCY_SHIFT) /* FLASH Zero Latency cycle */
-# define FLASH_ACR_LATENCY_1 (1 << FLASH_ACR_LATENCY_SHIFT) /* FLASH One Latency cycle */
-# define FLASH_ACR_LATENCY_2 (2 << FLASH_ACR_LATENCY_SHIFT) /* FLASH Two Latency cycles */
-#define FLASH_ACR_HLFCYA (1 << 3) /* FLASH half cycle access */
-#define FLASH_ACR_PRTFBE (1 << 4) /* FLASH prefetch enable */
+/* Flash Option Control Register (OPTCR) */
+
+#if defined(CONFIG_STM32_STM32F40XX)
+# define FLASH_OPTCR_OPTLOCK (1 << 0) /* Bit 0: Option lock */
+# define FLASH_OPTCR_OPTSTRT (1 << 1) /* Bit 1: Option start */
+# define FLASH_OPTCR_BORLEV_SHIFT (2) /* Bits 2-3: BOR reset Level */
+# define FLASH_OPTCR_BORLEV_MASK (3 << FLASH_OPTCR_BORLEV_SHIFT)
+# define FLASH_OPTCR_VBOR3 (0 << FLASH_OPTCR_BORLEV_SHIFT) /* 00: BOR Level 3 */
+# define FLASH_OPTCR_VBOR2 (1 << FLASH_OPTCR_BORLEV_SHIFT) /* 01: BOR Level 2 */
+# define FLASH_OPTCR_VBOR1 (2 << FLASH_OPTCR_BORLEV_SHIFT) /* 10: BOR Level 1 */
+# define FLASH_OPTCR_VBOR0 (3 << FLASH_OPTCR_BORLEV_SHIFT) /* 11: BOR off */
+# define FLASH_OPTCR_USER_SHIFT (5) /* Bits 5-7: User option bytes */
+# define FLASH_OPTCR_USER_MASK (7 << FLASH_OPTCR_USER_SHIFT)
+# define FLASH_OPTCR_NRST_STDBY (1 << 7) /* Bit 7: nRST_STDBY */
+# define FLASH_OPTCR_NRST_STOP (1 << 6) /* Bit 6: nRST_STOP */
+# define FLASH_OPTCR_WDG_SW (1 << 5) /* Bit 5: WDG_SW */
+# define FLASH_OPTCR_RDP_SHIFT (8) /* Bits 8-15: Read protect */
+# define FLASH_OPTCR_RDP_MASK (0xff << FLASH_OPTCR_RDP_SHIFT)
+# define FLASH_OPTCR_NWRP_SHIFT (16) /* Bits 16-27: Not write protect */
+# define FLASH_OPTCR_NWRP_MASK (0xfff << FLASH_OPTCR_NWRP_SHIFT)
+#endif
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_FLASH_H */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h b/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h
index e53482b9d..f481245e0 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h
@@ -78,6 +78,18 @@
# define STM32_I2C2_TRISE (STM32_I2C2_BASE+STM32_I2C_TRISE_OFFSET)
#endif
+#if STM32_NI2C > 2
+# define STM32_I2C3_CR1 (STM32_I2C3_BASE+STM32_I2C_CR1_OFFSET)
+# define STM32_I2C3_CR2 (STM32_I2C3_BASE+STM32_I2C_CR2_OFFSET)
+# define STM32_I2C3_OAR1 (STM32_I2C3_BASE+STM32_I2C_OAR1_OFFSET)
+# define STM32_I2C3_OAR2 (STM32_I2C3_BASE+STM32_I2C_OAR2_OFFSET)
+# define STM32_I2C3_DR (STM32_I2C3_BASE+STM32_I2C_DR_OFFSET)
+# define STM32_I2C3_SR1 (STM32_I2C3_BASE+STM32_I2C_SR1_OFFSET)
+# define STM32_I2C3_SR2 (STM32_I2C3_BASE+STM32_I2C_SR2_OFFSET)
+# define STM32_I2C3_CCR (STM32_I2C3_BASE+STM32_I2C_CCR_OFFSET)
+# define STM32_I2C3_TRISE (STM32_I2C3_BASE+STM32_I2C_TRISE_OFFSET)
+#endif
+
/* Register Bitfield Definitions ****************************************************/
/* Control register 1 */
diff --git a/nuttx/arch/arm/src/stm32/stm32_flash.c b/nuttx/arch/arm/src/stm32/stm32_flash.c
index 416facc16..924cd014c 100644
--- a/nuttx/arch/arm/src/stm32/stm32_flash.c
+++ b/nuttx/arch/arm/src/stm32/stm32_flash.c
@@ -33,19 +33,18 @@
*
************************************************************************************/
-/** \file
- * \author Uros Platise
- * \brief STM32 Flash - Program and Data Memory
- *
- * Provides standard flash access functions, to be used also by the
- * drivers/mtd/progmem.c program memory flash mtd driver.
+/* Provides standard flash access functions, to be used by the flash mtd driver.
* The interface is defined in the include/nuttx/progmem.h
*
* Requirements during write/erase operations on FLASH:
* - HSI must be ON.
* - Low Power Modes are not permitted during write/erase
*/
-
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <errno.h>
@@ -55,15 +54,13 @@
#include "stm32_waste.h"
#include "up_arch.h"
-
/************************************************************************************
- * Declarations
+ * Pre-processor Definitions
************************************************************************************/
#define FLASH_KEY1 0x45670123
#define FLASH_KEY2 0xCDEF89AB
-
/************************************************************************************
* Private Functions
************************************************************************************/
diff --git a/nuttx/arch/arm/src/stm32/stm32_flash.h b/nuttx/arch/arm/src/stm32/stm32_flash.h
index 6f286bf2c..10c5cc189 100644
--- a/nuttx/arch/arm/src/stm32/stm32_flash.h
+++ b/nuttx/arch/arm/src/stm32/stm32_flash.h
@@ -36,6 +36,10 @@
#ifndef __ARCH_ARM_SRC_STM32_STM32_FLASH_H
#define __ARCH_ARM_SRC_STM32_STM32_FLASH_H
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
#include <nuttx/config.h>
#include <nuttx/progmem.h>
diff --git a/nuttx/arch/arm/src/stm32/stm32_fsmc.h b/nuttx/arch/arm/src/stm32/stm32_fsmc.h
index ff0bba2ef..2b02d637f 100644
--- a/nuttx/arch/arm/src/stm32/stm32_fsmc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_fsmc.h
@@ -1,8 +1,8 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_fsmc.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -96,47 +96,47 @@
/* Register Addresses ***************************************************************/
-#define STM32_FSMC_BCR(n) (STM32_FSMC_BASE+STM32_FSMC_BCR_OFFSET (n))
+#define STM32_FSMC_BCR(n) (STM32_FSMC_BASE+STM32_FSMC_BCR_OFFSET(n))
#define STM32_FSMC_BCR1 (STM32_FSMC_BASE+STM32_FSMC_BCR1_OFFSET )
#define STM32_FSMC_BCR2 (STM32_FSMC_BASE+STM32_FSMC_BCR2_OFFSET )
#define STM32_FSMC_BCR3 (STM32_FSMC_BASE+STM32_FSMC_BCR3_OFFSET )
#define STM32_FSMC_BCR4 (STM32_FSMC_BASE+STM32_FSMC_BCR4_OFFSET )
-#define STM32_FSMC_BTR(n) (STM32_FSMC_BASE+STM32_FSMC_BTR_OFFSET (n))
+#define STM32_FSMC_BTR(n) (STM32_FSMC_BASE+STM32_FSMC_BTR_OFFSET(n))
#define STM32_FSMC_BTR1 (STM32_FSMC_BASE+STM32_FSMC_BTR1_OFFSET )
#define STM32_FSMC_BTR2 (STM32_FSMC_BASE+STM32_FSMC_BTR2_OFFSET )
#define STM32_FSMC_BTR3 (STM32_FSMC_BASE+STM32_FSMC_BTR3_OFFSET )
#define STM32_FSMC_BTR4 (STM32_FSMC_BASE+STM32_FSMC_BTR4_OFFSET )
-#define STM32_FSMC_BWTR(n) (STM32_FSMC_BASE+STM32_FSMC_BWTR_OFFSET (n))
+#define STM32_FSMC_BWTR(n) (STM32_FSMC_BASE+STM32_FSMC_BWTR_OFFSET(n))
#define STM32_FSMC_BWTR1 (STM32_FSMC_BASE+STM32_FSMC_BWTR1_OFFSET )
#define STM32_FSMC_BWTR2 (STM32_FSMC_BASE+STM32_FSMC_BWTR2_OFFSET )
#define STM32_FSMC_BWTR3 (STM32_FSMC_BASE+STM32_FSMC_BWTR3_OFFSET )
#define STM32_FSMC_BWTR4 (STM32_FSMC_BASE+STM32_FSMC_BWTR4_OFFSET )
-#define STM32_FSMC_PCR(n) (STM32_FSMC_BASE+STM32_FSMC_PCR_OFFSET (n))
+#define STM32_FSMC_PCR(n) (STM32_FSMC_BASE+STM32_FSMC_PCR_OFFSET(n))
#define STM32_FSMC_PCR2 (STM32_FSMC_BASE+STM32_FSMC_PCR2_OFFSET )
#define STM32_FSMC_PCR3 (STM32_FSMC_BASE+STM32_FSMC_PCR3_OFFSET )
#define STM32_FSMC_PCR4 (STM32_FSMC_BASE+STM32_FSMC_PCR4_OFFSET )
-#define STM32_FSMC_SR(n) (STM32_FSMC_BASE+STM32_FSMC_SR_OFFSET (n))
+#define STM32_FSMC_SR(n) (STM32_FSMC_BASE+STM32_FSMC_SR_OFFSET(n))
#define STM32_FSMC_SR2 (STM32_FSMC_BASE+STM32_FSMC_SR2_OFFSET )
#define STM32_FSMC_SR3 (STM32_FSMC_BASE+STM32_FSMC_SR3_OFFSET )
#define STM32_FSMC_SR4 (STM32_FSMC_BASE+STM32_FSMC_SR4_OFFSET )
-#define STM32_FSMC_PMEM(n) (STM32_FSMC_BASE+STM32_FSMC_PMEM_OFFSET (n))
+#define STM32_FSMC_PMEM(n) (STM32_FSMC_BASE+STM32_FSMC_PMEM_OFFSET(n))
#define STM32_FSMC_PMEM2 (STM32_FSMC_BASE+STM32_FSMC_PMEM2_OFFSET )
#define STM32_FSMC_PMEM3 (STM32_FSMC_BASE+STM32_FSMC_PMEM3_OFFSET )
#define STM32_FSMC_PMEM4 (STM32_FSMC_BASE+STM32_FSMC_PMEM4_OFFSET )
-#define STM32_FSMC_PATT(n) (STM32_FSMC_BASE+STM32_FSMC_PATT_OFFSET (n))
+#define STM32_FSMC_PATT(n) (STM32_FSMC_BASE+STM32_FSMC_PATT_OFFSET(n))
#define STM32_FSMC_PATT2 (STM32_FSMC_BASE+STM32_FSMC_PATT2_OFFSET )
#define STM32_FSMC_PATT3 (STM32_FSMC_BASE+STM32_FSMC_PATT3_OFFSET )
#define STM32_FSMC_PATT4 (STM32_FSMC_BASE+STM32_FSMC_PATT4_OFFSET )
#define STM32_PIO4 (STM32_FSMC_BASE+STM32_FSMC_PIO4_OFFSET )
-#define STM32_FSMC_ECCR(n) (STM32_FSMC_BASE+STM32_FSMC_ECCR_OFFSET (n))
+#define STM32_FSMC_ECCR(n) (STM32_FSMC_BASE+STM32_FSMC_ECCR_OFFSET(n))
#define STM32_FSMC_ECCR2 (STM32_FSMC_BASE+STM32_FSMC_ECCR2_OFFSET )
#define STM32_FSMC_ECCR3 (STM32_FSMC_BASE+STM32_FSMC_ECCR3_OFFSET )
@@ -163,6 +163,9 @@
#define FSMC_BCR_WREN (1 << 12) /* Write enable bit */
#define FSMC_BCR_WAITEN (1 << 13) /* Wait enable bit */
#define FSMC_BCR_EXTMOD (1 << 14) /* Extended mode enable */
+#ifdef CONFIG_STM32_STM32F40XX
+# define FSMC_BCR_ASYNCWAIT (1 << 15) /* Wait signal during asynchronous transfers */
+#endif
#define FSMC_BCR_CBURSTRW (1 << 19) /* Write burst enable */
#define FSMC_BTR_ADDSET_SHIFT (0) /* Address setup phase duration */