Hand-merge F427 patches.

This commit is contained in:
px4dev 2013-03-31 20:56:43 -07:00
parent 8224adf52a
commit f82af140ae
20 changed files with 1172 additions and 26 deletions

View File

@ -688,6 +688,103 @@
# define STM32_NRNG 1 /* Random number generator (RNG) */
# define STM32_NDCMI 1 /* Digital camera interface (DCMI) */
#elif defined(CONFIG_ARCH_CHIP_STM32F427I) /* BGA176; LQFP176 1024/2048KiB flash 256KiB SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
# undef CONFIG_STM32_VALUELINE /* STM32F100x */
# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
# undef CONFIG_STM32_STM32F30XX /* STM32F30xxx family */
# define CONFIG_STM32_STM32F40XX 1 /* STM32F405xx, STM32407xx and STM32F427/437 */
# define STM32_NFSMC 1 /* FSMC */
# define STM32_NATIM 2 /* Two advanced timers TIM1 and 8 */
# define STM32_NGTIM 4 /* 16-bit general timers TIM3 and 4 with DMA
* 32-bit general timers TIM2 and 5 with DMA */
# define STM32_NGTIMNDMA 6 /* 16-bit general timers TIM9-14 without DMA */
# define STM32_NBTIM 2 /* Two basic timers, TIM6-7 */
# define STM32_NDMA 2 /* DMA1-2 */
# define STM32_NSPI 6 /* SPI1-6 */
# define STM32_NI2S 2 /* I2S1-2 (multiplexed with SPI2-3) */
# define STM32_NUSART 8 /* USART1-3 and 6, UART 4-5 and 7-8 */
# define STM32_NI2C 3 /* I2C1-3 */
# define STM32_NCAN 2 /* CAN1-2 */
# define STM32_NSDIO 1 /* SDIO */
# define STM32_NUSBOTG 1 /* USB OTG FS/HS */
# define STM32_NGPIO 139 /* GPIOA-I */
# define STM32_NADC 3 /* 12-bit ADC1-3, 24 channels */
# define STM32_NDAC 2 /* 12-bit DAC1-2 */
# define STM32_NCRC 1 /* CRC */
# define STM32_NETHERNET 1 /* 100/100 Ethernet MAC */
# define STM32_NRNG 1 /* Random number generator (RNG) */
# define STM32_NDCMI 1 /* Digital camera interface (DCMI) */
#elif defined(CONFIG_ARCH_CHIP_STM32F427Z) /* LQFP144 1024/2048KiB flash 256KiB SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
# undef CONFIG_STM32_VALUELINE /* STM32F100x */
# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
# undef CONFIG_STM32_STM32F30XX /* STM32F30xxx family */
# define CONFIG_STM32_STM32F40XX 1 /* STM32F405xx, STM32407xx and STM32F427/437 */
# define STM32_NFSMC 1 /* FSMC */
# define STM32_NATIM 2 /* Two advanced timers TIM1 and 8 */
# define STM32_NGTIM 4 /* 16-bit general timers TIM3 and 4 with DMA
* 32-bit general timers TIM2 and 5 with DMA */
# define STM32_NGTIMNDMA 6 /* 16-bit general timers TIM9-14 without DMA */
# define STM32_NBTIM 2 /* Two basic timers, TIM6-7 */
# define STM32_NDMA 2 /* DMA1-2 */
# define STM32_NSPI 6 /* SPI1-6 */
# define STM32_NI2S 2 /* I2S1-2 (multiplexed with SPI2-3) */
# define STM32_NUSART 8 /* USART1-3 and 6, UART 4-5 and 7-8 */
# define STM32_NI2C 3 /* I2C1-3 */
# define STM32_NCAN 2 /* CAN1-2 */
# define STM32_NSDIO 1 /* SDIO */
# define STM32_NUSBOTG 1 /* USB OTG FS/HS */
# define STM32_NGPIO 139 /* GPIOA-I */
# define STM32_NADC 3 /* 12-bit ADC1-3, 24 channels */
# define STM32_NDAC 2 /* 12-bit DAC1-2 */
# define STM32_NCRC 1 /* CRC */
# define STM32_NETHERNET 1 /* 100/100 Ethernet MAC */
# define STM32_NRNG 1 /* Random number generator (RNG) */
# define STM32_NDCMI 1 /* Digital camera interface (DCMI) */
#elif defined(CONFIG_ARCH_CHIP_STM32F427V) /* LQFP100 1024/2048KiB flash 256KiB SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
# undef CONFIG_STM32_VALUELINE /* STM32F100x */
# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
# undef CONFIG_STM32_STM32F30XX /* STM32F30xxx family */
# define CONFIG_STM32_STM32F40XX 1 /* STM32F405xx, STM32407xx and STM32F427/437 */
# define STM32_NFSMC 1 /* FSMC */
# define STM32_NATIM 2 /* Two advanced timers TIM1 and 8 */
# define STM32_NGTIM 4 /* 16-bit general timers TIM3 and 4 with DMA
* 32-bit general timers TIM2 and 5 with DMA */
# define STM32_NGTIMNDMA 6 /* 16-bit general timers TIM9-14 without DMA */
# define STM32_NBTIM 2 /* Two basic timers, TIM6-7 */
# define STM32_NDMA 2 /* DMA1-2 */
# define STM32_NSPI 4 /* SPI1-4 */
# define STM32_NI2S 2 /* I2S1-2 (multiplexed with SPI2-3) */
# define STM32_NUSART 8 /* USART1-3 and 6, UART 4-5 and 7-8 */
# define STM32_NI2C 3 /* I2C1-3 */
# define STM32_NCAN 2 /* CAN1-2 */
# define STM32_NSDIO 1 /* SDIO */
# define STM32_NUSBOTG 1 /* USB OTG FS/HS */
# define STM32_NGPIO 139 /* GPIOA-I */
# define STM32_NADC 3 /* 12-bit ADC1-3, 24 channels */
# define STM32_NDAC 2 /* 12-bit DAC1-2 */
# define STM32_NCRC 1 /* CRC */
# define STM32_NETHERNET 1 /* 100/100 Ethernet MAC */
# define STM32_NRNG 1 /* Random number generator (RNG) */
# define STM32_NDCMI 1 /* Digital camera interface (DCMI) */
#else
# error "Unsupported STM32 chip"
#endif

View File

@ -153,7 +153,16 @@
#define STM32_IRQ_RNG (STM32_IRQ_INTERRUPTS+80) /* 80: Hash and Rng global interrupt */
#define STM32_IRQ_FPU (STM32_IRQ_INTERRUPTS+81) /* 81: FPU global interrupt */
#define NR_IRQS (STM32_IRQ_INTERRUPTS+82)
#ifndef CONFIG_STM32_STM32F427
# define NR_IRQS (STM32_IRQ_INTERRUPTS+87)
#else
# define STM32_IRQ_UART7 (STM32_IRQ_INTERRUPTS+82) /* 82: UART7 interrupt */
# define STM32_IRQ_UART8 (STM32_IRQ_INTERRUPTS+83) /* 83: UART8 interrupt */
# define STM32_IRQ_SPI4 (STM32_IRQ_INTERRUPTS+84) /* 84: SPI4 interrupt */
# define STM32_IRQ_SPI5 (STM32_IRQ_INTERRUPTS+85) /* 85: SPI5 interrupt */
# define STM32_IRQ_SPI6 (STM32_IRQ_INTERRUPTS+86) /* 86: SPI6 interrupt */
# define NR_IRQS (STM32_IRQ_INTERRUPTS+87)
#endif
/****************************************************************************************************
* Public Types

View File

@ -173,6 +173,24 @@ config ARCH_CHIP_STM32F407IG
select ARCH_CORTEXM4
select STM32_STM32F40XX
config ARCH_CHIP_STM32F427V
bool "STM32F427V"
select ARCH_CORTEXM4
select STM32_STM32F40XX
select STM32_STM32F427
config ARCH_CHIP_STM32F427Z
bool "STM32F427Z"
select ARCH_CORTEXM4
select STM32_STM32F40XX
select STM32_STM32F427
config ARCH_CHIP_STM32F427I
bool "STM32F427I"
select ARCH_CORTEXM4
select STM32_STM32F40XX
select STM32_STM32F427
endchoice
config STM32_STM32F10XX
@ -193,6 +211,10 @@ config STM32_STM32F20XX
config STM32_STM32F40XX
bool
# This is really 427/437, but we treat the two the same.
config STM32_STM32F427
bool
config STM32_DFU
bool "DFU bootloader"
default n
@ -370,6 +392,27 @@ config STM32_SPI3
select SPI
select STM32_SPI
config STM32_SPI4
bool "SPI4"
default n
depends on STM32_STM32F427
select SPI
select STM32_SPI
config STM32_SPI5
bool "SPI5"
default n
depends on STM32_STM32F427
select SPI
select STM32_SPI
config STM32_SPI6
bool "SPI6"
default n
depends on STM32_STM32F427
select SPI
select STM32_SPI
config STM32_SYSCFG
bool "SYSCFG"
default y
@ -490,6 +533,20 @@ config STM32_USART6
select ARCH_HAVE_USART6
select STM32_USART
config STM32_UART7
bool "UART7"
default n
depends on STM32_STM32F427
select ARCH_HAVE_UART7
select STM32_USART
config STM32_UART8
bool "UART8"
default n
depends on STM32_STM32F427
select ARCH_HAVE_UART8
select STM32_USART
config STM32_USB
bool "USB Device"
default n
@ -698,6 +755,7 @@ endmenu
config STM32_FLASH_PREFETCH
bool "Enable FLASH Pre-fetch"
depends on STM32_STM32F20XX || STM32_STM32F40XX
default y if STM32_STM32F427
default n
---help---
Enable FLASH prefetch and F2 and F4 parts (FLASH pre-fetch is always enabled
@ -1966,9 +2024,59 @@ config USART6_RXDMA
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
config USART7_RS485
bool "RS-485 on USART7"
default n
depends on STM32_USART7
---help---
Enable RS-485 interface on USART7. Your board config will have to
provide GPIO_USART7_RS485_DIR pin definition. Currently it cannot be
used with USART7_RXDMA.
config USART7_RS485_DIR_POLARITY
int "USART7 RS-485 DIR pin polarity"
default 1
range 0 1
depends on USART7_RS485
---help---
Polarity of DIR pin for RS-485 on USART7. Set to state on DIR pin which
enables TX (0 - low / nTXEN, 1 - high / TXEN).
config USART7_RXDMA
bool "USART7 Rx DMA"
default n
depends on STM32_STM32F40XX && STM32_DMA2
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
config USART8_RS485
bool "RS-485 on USART8"
default n
depends on STM32_USART8
---help---
Enable RS-485 interface on USART8. Your board config will have to
provide GPIO_USART8_RS485_DIR pin definition. Currently it cannot be
used with USART8_RXDMA.
config USART8_RS485_DIR_POLARITY
int "USART8 RS-485 DIR pin polarity"
default 1
range 0 1
depends on USART8_RS485
---help---
Polarity of DIR pin for RS-485 on USART8. Set to state on DIR pin which
enables TX (0 - low / nTXEN, 1 - high / TXEN).
config USART8_RXDMA
bool "USART8 Rx DMA"
default n
depends on STM32_STM32F40XX && STM32_DMA2
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
config SERIAL_TERMIOS
bool "Serial driver TERMIOS supported"
depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_UART4 || STM32_UART5 || STM32_USART6
depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_UART4 || STM32_UART5 || STM32_USART6 || STM32_USART7 || STM32_USART8
default n
---help---
Serial driver supports termios.h interfaces (tcsetattr, tcflush, etc.).

View File

@ -55,6 +55,7 @@
#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define STM32_FLASH_NPAGES 8
# define STM32_FLASH_PAGESIZE (128*1024)
/* XXX this is wrong for 427, and not really right for 40x due to mixed page sizes */
#endif
#define STM32_FLASH_SIZE (STM32_FLASH_NPAGES * STM32_FLASH_PAGESIZE)
@ -74,6 +75,9 @@
#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define STM32_FLASH_OPTCR_OFFSET 0x0014
#endif
#if defined(CONFIG_STM32_STM32F427)
# define STM32_FLASH_OPTCR1_OFFSET 0x0018
#endif
/* Register Addresses ***************************************************************/
@ -90,6 +94,9 @@
#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define STM32_FLASH_OPTCR (STM32_FLASHIF_BASE+STM32_FLASH_OPTCR_OFFSET)
#endif
#if defined(CONFIG_STM32_STM32F427)
# define STM32_FLASH_OPTCR1 (STM32_FLASHIF_BASE+STM32_FLASH_OPTCR1_OFFSET)
#endif
/* Register Bitfield Definitions ****************************************************/
/* Flash Access Control Register (ACR) */
@ -150,10 +157,14 @@
#elif defined(CONFIG_STM32_STM32F20XX) || 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_MER (1 << 2) /* Bit 2: Mass Erase sectors 0..11 */
# define FLASH_CR_SNB_SHIFT (3) /* Bits 3-6: Sector number */
# define FLASH_CR_SNB_MASK (15 << FLASH_CR_SNB_SHIFT)
#if defined(CONFIG_STM32_STM32F427)
# define FLASH_CR_SNB(n) (((n % 12) << FLASH_CR_SNB_SHIFT) | ((n / 12) << 7)) /* Sector n, n=0..23 */
#else
# define FLASH_CR_SNB(n) ((n) << FLASH_CR_SNB_SHIFT) /* Sector n, n=0..11 */
#endif
# 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 */
@ -164,6 +175,9 @@
# define FLASH_CR_ERRIE (1 << 25) /* Bit 25: Error interrupt enable */
# define FLASH_CR_LOCK (1 << 31) /* Bit 31: Lock */
#endif
#if defined(CONFIG_STM32_STM32F427)
# define FLASH_CR_MER1 (1 << 15) /* Bit 15: Mass Erase sectors 12..23 */
#endif
/* Flash Option Control Register (OPTCR) */
@ -187,5 +201,12 @@
# define FLASH_OPTCR_NWRP_MASK (0xfff << FLASH_OPTCR_NWRP_SHIFT)
#endif
/* Flash Option Control Register (OPTCR1) */
#if defined(CONFIG_STM32_STM32F427)
# define FLASH_OPTCR1_NWRP_SHIFT (16) /* Bits 16-27: Not write protect (high bank) */
# define FLASH_OPTCR1_NWRP_MASK (0xfff << FLASH_OPTCR_NWRP_SHIFT)
#endif
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_FLASH_H */

View File

@ -51,6 +51,9 @@
#define STM32_I2C_SR2_OFFSET 0x0018 /* Status register 2 (16-bit) */
#define STM32_I2C_CCR_OFFSET 0x001c /* Clock control register (16-bit) */
#define STM32_I2C_TRISE_OFFSET 0x0020 /* TRISE Register (16-bit) */
#ifdef CONFIG_STM32_STM32F427
# define STM32_I2C_FLTR_OFFSET 0x0024 /* FLTR Register (16-bit) */
#endif
/* Register Addresses ***************************************************************/
@ -64,6 +67,9 @@
# define STM32_I2C1_SR2 (STM32_I2C1_BASE+STM32_I2C_SR2_OFFSET)
# define STM32_I2C1_CCR (STM32_I2C1_BASE+STM32_I2C_CCR_OFFSET)
# define STM32_I2C1_TRISE (STM32_I2C1_BASE+STM32_I2C_TRISE_OFFSET)
# ifdef STM32_I2C_FLTR_OFFSET
# define STM32_I2C1_FLTR (STM32_I2C1_BASE+STM32_I2C_FLTR_OFFSET)
# endif
#endif
#if STM32_NI2C > 1
@ -76,6 +82,9 @@
# define STM32_I2C2_SR2 (STM32_I2C2_BASE+STM32_I2C_SR2_OFFSET)
# define STM32_I2C2_CCR (STM32_I2C2_BASE+STM32_I2C_CCR_OFFSET)
# define STM32_I2C2_TRISE (STM32_I2C2_BASE+STM32_I2C_TRISE_OFFSET)
# ifdef STM32_I2C_FLTR_OFFSET
# define STM32_I2C2_FLTR (STM32_I2C2_BASE+STM32_I2C_FLTR_OFFSET)
# endif
#endif
#if STM32_NI2C > 2
@ -88,6 +97,9 @@
# 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)
# ifdef STM32_I2C_FLTR_OFFSET
# define STM32_I2C3_FLTR (STM32_I2C3_BASE+STM32_I2C_FLTR_OFFSET)
# endif
#endif
/* Register Bitfield Definitions ****************************************************/
@ -188,5 +200,13 @@
#define I2C_TRISE_SHIFT (0) /* Bits 5-0: Maximum Rise Time in Fast/Standard mode (Master mode) */
#define I2C_TRISE_MASK (0x3f << I2C_TRISE_SHIFT)
/* FLTR Register */
#ifdef STM32_I2C_FLTR_OFFSET
# define I2C_FLTR_ANOFF (1 << 4) /* Bit 4: Analog noise filter disable */
# define I2C_FLTR_DNF_SHIFT 0 /* Bits 0-3: Digital noise filter */
# define I2C_FLTR_DNF_MASK (0xf << I2C_FLTR_DNF_SHIFT)
#endif
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_I2C_H */

View File

@ -80,7 +80,16 @@
#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define PWR_CR_FPDS (1 << 9) /* Bit 9: Flash power down in Stop mode */
# if defined(CONFIG_STM32_STM32F427)
# define PWR_CR_ADCDC1 (1 << 13) /* Bit 13: see AN4073 for details */
# define PWR_CR_VOS_SCALE_1 (3 << 14) /* Fmax = 168MHz */
# define PWR_CR_VOS_SCALE_2 (2 << 14) /* Fmax = 144MHz */
# define PWR_CR_VOS_SCALE_3 (1 << 14) /* Fmax = 120MHz */
# define PWR_CR_VOS_MASK (3 << 14) /* Bits 14-15: Regulator voltage scaling output selection */
# else
# define PWR_CR_VOS (1 << 14) /* Bit 14: Regulator voltage scaling output selection */
/* 0: Fmax = 144MHz 1: Fmax = 168MHz */
# endif
#endif
/* Power control/status register */

View File

@ -89,6 +89,11 @@
/* SYSCFG peripheral mode configuration register */
#define SYSCFG_PMC_MII_RMII_SEL (1 << 23) /* Bit 23: Ethernet PHY interface selection */
+#ifdef CONFIG_STM32_STM32F427
+# define SYSCFG_PMC_ADC3DC2 (1 << 18) /* Bit 18: See AN4073 */
+# define SYSCFG_PMC_ADC2DC2 (1 << 17) /* Bit 17: See AN4073 */
+# define SYSCFG_PMC_ADC1DC2 (1 << 16) /* Bit 16: See AN4073 */
+#endif
/* SYSCFG external interrupt configuration register 1-4 */

View File

@ -118,6 +118,24 @@
# define STM32_USART6_GTPR (STM32_USART6_BASE+STM32_USART_GTPR_OFFSET)
#endif
#if STM32_NUSART > 6
# define STM32_UART7_SR (STM32_UART7_BASE+STM32_USART_SR_OFFSET)
# define STM32_UART7_DR (STM32_UART7_BASE+STM32_USART_DR_OFFSET)
# define STM32_UART7_BRR (STM32_UART7_BASE+STM32_USART_BRR_OFFSET)
# define STM32_UART7_CR1 (STM32_UART7_BASE+STM32_USART_CR1_OFFSET)
# define STM32_UART7_CR2 (STM32_UART7_BASE+STM32_USART_CR2_OFFSET)
# define STM32_UART7_CR3 (STM32_UART7_BASE+STM32_USART_CR3_OFFSET)
#endif
#if STM32_NUSART > 7
# define STM32_UART8_SR (STM32_UART8_BASE+STM32_USART_SR_OFFSET)
# define STM32_UART8_DR (STM32_UART8_BASE+STM32_USART_DR_OFFSET)
# define STM32_UART8_BRR (STM32_UART8_BASE+STM32_USART_BRR_OFFSET)
# define STM32_UART8_CR1 (STM32_UART8_BASE+STM32_USART_CR1_OFFSET)
# define STM32_UART8_CR2 (STM32_UART8_BASE+STM32_USART_CR2_OFFSET)
# define STM32_UART8_CR3 (STM32_UART8_BASE+STM32_USART_CR3_OFFSET)
#endif
/* Register Bitfield Definitions ****************************************************/
/* Status register */

View File

@ -438,11 +438,21 @@
#define DMAMAP_USART2_TX STM32_DMA_MAP(DMA1,DMA_STREAM6,DMA_CHAN4)
#define DMAMAP_UART5_TX STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN4)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_UART8_TX STM32_DMA_MAP(CMA1,DMA_STREAM0,DMA_CHAN5)
# define DMAMAP_UART7_TX STM32_DMA_MAP(CMA1,DMA_STREAM1,DMA_CHAN5)
#endif
#define DMAMAP_TIM3_CH4 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN5)
#define DMAMAP_TIM3_UP STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN5)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_UART7_RX STM32_DMA_MAP(CMA1,DMA_STREAM3,DMA_CHAN5)
#endif
#define DMAMAP_TIM3_CH1 STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN5)
#define DMAMAP_TIM3_TRIG STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN5)
#define DMAMAP_TIM3_CH2 STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN5)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_UART8_RX STM32_DMA_MAP(CMA1,DMA_STREAM6,DMA_CHAN5)
#endif
#define DMAMAP_TIM3_CH3 STM32_DMA_MAP(DMA1,DMA_STREAM7,DMA_CHAN5)
#define DMAMAP_TIM5_CH3 STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN6)
@ -475,10 +485,18 @@
#define DMAMAP_DCMI_1 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN1)
#define DMAMAP_ADC2_1 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN1)
#define DMAMAP_ADC2_2 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN1)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_SPI6_TX STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN1)
# define DMAMAP_SPI6_RX STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN1)
#endif
#define DMAMAP_DCMI_2 STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN1)
#define DMAMAP_ADC3_1 STM32_DMA_MAP(DMA2,DMA_STREAM0,DMA_CHAN2)
#define DMAMAP_ADC3_2 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN2)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_SPI5_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN2)
# define DMAMAP_SPI5_TX_1 STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN2)
#endif
#define DMAMAP_CRYP_OUT STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN2)
#define DMAMAP_CRYP_IN STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN2)
#define DMAMAP_HASH_IN STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN2)
@ -488,6 +506,11 @@
#define DMAMAP_SPI1_TX_1 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN3)
#define DMAMAP_SPI1_TX_2 STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN3)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_SPI4_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM0,DMA_CHAN4)
# define DMAMAP_SPI4_TX_1 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN4)
#endif
#define DMAMAP_SPI4_TX_1 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN4)
#define DMAMAP_USART1_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN4)
#define DMAMAP_SDIO_1 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN4)
#define DMAMAP_USART1_RX_2 STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN4)
@ -496,6 +519,10 @@
#define DMAMAP_USART6_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN5)
#define DMAMAP_USART6_RX_2 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN5)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_SPI4_RX_2 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN5)
# define DMAMAP_SPI4_TX_2 STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN5)
#endif
#define DMAMAP_USART6_TX_1 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN5)
#define DMAMAP_USART6_TX_2 STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN5)
@ -512,7 +539,11 @@
#define DMAMAP_TIM8_UP STM32_DMA_MAP(DMA2,DMA_STREAM1,DMA_CHAN7)
#define DMAMAP_TIM8_CH1_2 STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN7)
#define DMAMAP_TIM8_CH2_2 STM32_DMA_MAP(DMA2,DMA_STREAM3,DMA_CHAN7)
#define DMAMAP_TIM8_CH3_2 STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN7)
#define DMAMAP_TIM8_CH3_2 STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN7)
#ifdef CONFIG_STM32_STM32F427
# define DMAMAP_SPI5_RX_2 STM32_DMA_MAP(DMA2,DMA_STREAM5,DMA_CHAN7)
# define DMAMAP_SPI5_TX_2 STM32_DMA_MAP(DMA2,DMA_STREAM6,DMA_CHAN7)
#endif
#define DMAMAP_TIM8_CH4 STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN7)
#define DMAMAP_TIM8_TRIG STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN7)
#define DMAMAP_TIM8_COM STM32_DMA_MAP(DMA2,DMA_STREAM7,DMA_CHAN7)

View File

@ -140,6 +140,8 @@
#define STM32_CAN2_BASE 0x40006800 /* 0x40006800-0x40006bff: bxCAN2 */
#define STM32_PWR_BASE 0x40007000 /* 0x40007000-0x400073ff: Power control PWR */
#define STM32_DAC_BASE 0x40007400 /* 0x40007400-0x400077ff: DAC */
#define STM32_UART7_BASE 0x40007800 /* 0x40007800-0x40007bff: UART7 */
#define STM32_UART8_BASE 0x40007c00 /* 0x40007c00-0x40007fff: UART8 */
/* APB2 Base Addresses **************************************************************/
@ -154,11 +156,14 @@
# define STM32_ADCCMN_BASE 0x40012300 /* Common */
#define STM32_SDIO_BASE 0x40012c00 /* 0x40012c00-0x40012fff: SDIO */
#define STM32_SPI1_BASE 0x40013000 /* 0x40013000-0x400133ff: SPI1 */
#define STM32_SPI4_BASE 0x40013400 /* 0x40013000-0x400137ff: SPI4 */
#define STM32_SYSCFG_BASE 0x40013800 /* 0x40013800-0x40013bff: SYSCFG */
#define STM32_EXTI_BASE 0x40013c00 /* 0x40013c00-0x40013fff: EXTI */
#define STM32_TIM9_BASE 0x40014000 /* 0x40014000-0x400143ff: TIM9 timer */
#define STM32_TIM10_BASE 0x40014400 /* 0x40014400-0x400147ff: TIM10 timer */
#define STM32_TIM11_BASE 0x40014800 /* 0x40014800-0x40014bff: TIM11 timer */
#define STM32_SPI5_BASE 0x40015000 /* 0x40015000-0x400153ff: SPI5 */
#define STM32_SPI6_BASE 0x40015400 /* 0x40015400-0x400157ff: SPI6 */
/* AHB1 Base Addresses **************************************************************/

View File

@ -331,6 +331,9 @@
#define GPIO_I2S2_CK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2S2_CK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN13)
#define GPIO_I2S2_CK_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN1)
#ifdef CONFIG_STM32_STM32F427
# define GPIO_I2S2_CK_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTD|GPIO_PIN3)
#endif
#define GPIO_I2S2_MCK (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN6)
#define GPIO_I2S2_SD_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN15)
#define GPIO_I2S2_SD_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN3)
@ -339,6 +342,9 @@
#define GPIO_I2S2_WS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN6)
#define GPIO_I2S2_WS_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN9)
#define GPIO_I2S2_WS_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN0)
#ifdef CONFIG_STM32_STM32F427
# define GPIO_I2S2_WS_6 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN6)
#endif
#define GPIO_I2S2EXT_SD_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN14)
#define GPIO_I2S2EXT_SD_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN2)
@ -349,6 +355,9 @@
#define GPIO_I2S3_MCK (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN7)
#define GPIO_I2S3_SD_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN5)
#define GPIO_I2S3_SD_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN12)
#ifdef CONFIG_STM32_STM32F427
# define GPIO_I2S3_SD_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTD|GPIO_PIN6)
#endif
#define GPIO_I2S3_WS_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN4)
#define GPIO_I2S3_WS_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN15)
@ -428,7 +437,7 @@
#define GPIO_SPI2_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN14)
#define GPIO_SPI2_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN2)
#define GPIO_SPI2_MISO_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN2)
#define GPIO_SPI2_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI2_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN15)
#define GPIO_SPI2_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN3)
#define GPIO_SPI2_MOSI_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN3)
#define GPIO_SPI2_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN12)
@ -437,16 +446,45 @@
#define GPIO_SPI2_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN10)
#define GPIO_SPI2_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN13)
#define GPIO_SPI2_SCK_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN1)
#ifdef CONFIG_STM32_STM32F427
# define GPIO_SPI2_SCK_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTD|GPIO_PIN3)
#endif
#define GPIO_SPI3_MISO_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN4)
#define GPIO_SPI3_MISO_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN11)
#define GPIO_SPI3_MOSI_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN5)
#define GPIO_SPI3_MOSI_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN12)
#ifdef CONFIG_STM32_STM32F427
# define GPIO_SPI3_MOSI_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTD|GPIO_PIN6)
#endif
#define GPIO_SPI3_NSS_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN15)
#define GPIO_SPI3_NSS_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN4)
#define GPIO_SPI3_SCK_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN3)
#define GPIO_SPI3_SCK_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN10)
#define GPIO_SPI4_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN5)
#define GPIO_SPI4_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN13)
#define GPIO_SPI4_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN6)
#define GPIO_SPI4_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN14)
#define GPIO_SPI4_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN4)
#define GPIO_SPI4_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN11)
#define GPIO_SPI4_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN2)
#define GPIO_SPI4_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTE|GPIO_PIN12)
#define GPIO_SPI5_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTF|GPIO_PIN8)
#define GPIO_SPI5_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTH|GPIO_PIN7)
#define GPIO_SPI5_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTF|GPIO_PIN9)
#define GPIO_SPI5_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTF|GPIO_PIN11)
#define GPIO_SPI5_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTF|GPIO_PIN6)
#define GPIO_SPI5_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTH|GPIO_PIN5)
#define GPIO_SPI5_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTF|GPIO_PIN7)
#define GPIO_SPI5_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTH|GPIO_PIN6)
#define GPIO_SPI6_MISO (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN12)
#define GPIO_SPI6_MOSI (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN14)
#define GPIO_SPI6_NSS (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN8)
#define GPIO_SPI6_SCK (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN13)
/* Timers */
#define GPIO_TIM1_BKIN_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN6)
@ -691,5 +729,15 @@
#define GPIO_USART6_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6)
#define GPIO_USART6_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14)
#ifdef CONFIG_STM32_STM32F427
# define GPIO_UART7_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN7)
# define GPIO_UART7_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN6)
# define GPIO_UART7_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN8)
# define GPIO_UART7_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN7)
# define GPIO_UART8_RX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN0)
# define GPIO_UART8_TX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN1)
#endif
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F40XXX_PINMAP_H */

View File

@ -65,6 +65,9 @@
#define STM32_RCC_CSR_OFFSET 0x0074 /* Control/status register */
#define STM32_RCC_SSCGR_OFFSET 0x0080 /* Spread spectrum clock generation register */
#define STM32_RCC_PLLI2SCFGR_OFFSET 0x0084 /* PLLI2S configuration register */
#ifdef CONFIG_STM32_STM32F427
# define STM32_RCC_DCKCFGR_OFFSET 0x008c /* Dedicated clocks configuration register */
#endif
/* Register Addresses *******************************************************************************/
@ -91,6 +94,9 @@
#define STM32_RCC_CSR (STM32_RCC_BASE+STM32_RCC_CSR_OFFSET)
#define STM32_RCC_SSCGR (STM32_RCC_BASE+STM32_RCC_SSCGR_OFFSET)
#define STM32_RCC_PLLI2SCFGR (STM32_RCC_BASE+STM32_RCC_PLLI2SCFGR_OFFSET)
#ifdef CONFIG_STM32_STM32F427
# define STM32_RCC_DCKCFGR (STM32_RCC_BASE+STM32_RCC_DCKCFGR_OFFSET)
#endif
/* Register Bitfield Definitions ********************************************************************/
@ -282,6 +288,10 @@
#define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */
#define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */
#define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC reset */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB1RSTR_UART7RST (1 << 30) /* Bit 30: USART 7 reset */
# define RCC_APB1RSTR_UART8RST (1 << 31) /* Bit 31: USART 8 reset */
#endif
/* APB2 Peripheral reset register */
@ -292,10 +302,17 @@
#define RCC_APB2RSTR_ADCRST (1 << 8) /* Bit 8: ADC interface reset (common to all ADCs) */
#define RCC_APB2RSTR_SDIORST (1 << 11) /* Bit 11: SDIO reset */
#define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI1 reset */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB2RSTR_SPI4RST (1 << 13) /* Bit 13: SPI4 reset */
#endif
#define RCC_APB2RSTR_SYSCFGRST (1 << 14) /* Bit 14: System configuration controller reset */
#define RCC_APB2RSTR_TIM9RST (1 << 16) /* Bit 16: TIM9 reset */
#define RCC_APB2RSTR_TIM10RST (1 << 17) /* Bit 17: TIM10 reset */
#define RCC_APB2RSTR_TIM11RST (1 << 18) /* Bit 18: TIM11 reset */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB2RSTR_SPI5RST (1 << 20) /* Bit 20: SPI 5 reset */
# define RCC_APB2RSTR_SPI6RST (1 << 21) /* Bit 21: SPI 6 reset */
#endif
/* AHB1 Peripheral Clock enable register */
@ -358,6 +375,10 @@
#define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 26: CAN 2 clock enable */
#define RCC_APB1ENR_PWREN (1 << 28) /* Bit 28: Power interface clock enable */
#define RCC_APB1ENR_DACEN (1 << 29) /* Bit 29: DAC interface clock enable */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB1ENR_UART7EN (1 << 30) /* Bit 30: UART7 clock enable */
# define RCC_APB1ENR_UART8EN (1 << 31) /* Bit 31: UART8 clock enable */
#endif
/* APB2 Peripheral Clock enable register */
@ -370,10 +391,17 @@
#define RCC_APB2ENR_ADC3EN (1 << 10) /* Bit 10: ADC3 clock enable */
#define RCC_APB2ENR_SDIOEN (1 << 11) /* Bit 11: SDIO clock enable */
#define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI1 clock enable */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB2ENR_SPI4EN (1 << 13) /* Bit 13: SPI4 clock enable */
#endif
#define RCC_APB2ENR_SYSCFGEN (1 << 14) /* Bit 14: System configuration controller clock enable */
#define RCC_APB2ENR_TIM9EN (1 << 16) /* Bit 16: TIM9 clock enable */
#define RCC_APB2ENR_TIM10EN (1 << 17) /* Bit 17: TIM10 clock enable */
#define RCC_APB2ENR_TIM11EN (1 << 18) /* Bit 18: TIM11 clock enable */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB2ENR_SPI5EN (1 << 20) /* Bit 20: SPI5 clock enable */
# define RCC_APB2ENR_SPI6EN (1 << 21) /* Bit 21: SPI6 clock enable */
#endif
/* RCC AHB1 low power modeperipheral clock enable register */
@ -392,6 +420,9 @@
#define RCC_AHB1LPENR_SRAM1LPEN (1 << 16) /* Bit 16: SRAM 1 interface clock enable during Sleep mode */
#define RCC_AHB1LPENR_SRAM2LPEN (1 << 17) /* Bit 17: SRAM 2 interface clock enable during Sleep mode */
#define RCC_AHB1LPENR_BKPSRAMLPEN (1 << 18) /* Bit 18: Backup SRAM interface clock enable during Sleep mode */
#ifdef CONFIG_STM32_STM32F427
# define RCC_AHB1LPENR_SRAM3LPEN (1 << 19) /* Bit 19: SRAM 3 interface clock enable during Sleep mode */
#endif
#define RCC_AHB1LPENR_CCMDATARAMLPEN (1 << 20) /* Bit 20: CCM data RAM clock enable during Sleep mode */
#define RCC_AHB1LPENR_DMA1LPEN (1 << 21) /* Bit 21: DMA1 clock enable during Sleep mode */
#define RCC_AHB1LPENR_DMA2LPEN (1 << 22) /* Bit 22: DMA2 clock enable during Sleep mode */
@ -440,6 +471,10 @@
#define RCC_APB1LPENR_CAN2LPEN (1 << 26) /* Bit 26: CAN 2 clock enable during Sleep mode */
#define RCC_APB1LPENR_PWRLPEN (1 << 28) /* Bit 28: Power interface clock enable during Sleep mode */
#define RCC_APB1LPENR_DACLPEN (1 << 29) /* Bit 29: DAC interface clock enable during Sleep mode */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB1LPENR_UART7LPEN (1 << 30) /* Bit 30: UART7 clock enable during Sleep mode */
# define RCC_APB1LPENR_UART8LPEN (1 << 31) /* Bit 31: UART8 clock enable during Sleep mode */
#endif
/* RCC APB2 low power modeperipheral clock enable register */
@ -452,10 +487,17 @@
#define RCC_APB2LPENR_ADC3LPEN (1 << 10) /* Bit 10: ADC3 clock enable during Sleep mode */
#define RCC_APB2LPENR_SDIOLPEN (1 << 11) /* Bit 11: SDIO clock enable during Sleep mode */
#define RCC_APB2LPENR_SPI1LPEN (1 << 12) /* Bit 12: SPI1 clock enable during Sleep mode */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB2LPENR_SPI4LPEN (1 << 13) /* Bit 13: SPI4 clock enable during Sleep mode */
#endif
#define RCC_APB2LPENR_SYSCFGLPEN (1 << 14) /* Bit 14: System configuration controller clock enable during Sleep mode */
#define RCC_APB2LPENR_TIM9LPEN (1 << 16) /* Bit 16: TIM9 clock enable during Sleep mode */
#define RCC_APB2LPENR_TIM10LPEN (1 << 17) /* Bit 17: TIM10 clock enable during Sleep mode */
#define RCC_APB2LPENR_TIM11LPEN (1 << 18) /* Bit 18: TIM11 clock enable during Sleep mode */
#ifdef CONFIG_STM32_STM32F427
# define RCC_APB2LPENR_SPI5LPEN (1 << 20) /* Bit 20: SPI5 clock enable during Sleep mode */
# define RCC_APB2LPENR_SPI6LPEN (1 << 21) /* Bit 21: SPI6 clock enable during Sleep mode */
#endif
/* Backup domain control register */
@ -502,5 +544,11 @@
#define RCC_PLLI2SCFGR_PLLI2SR_SHIFT (28) /* Bits 28-30: PLLI2S division factor for I2S clocks */
#define RCC_PLLI2SCFGR_PLLI2SR_MASK (7 << RCC_PLLI2SCFGR_PLLI2SR_SHIFT)
/* Dedicated clocks configuration register */
#ifdef CONFIG_STM32_STM32F427
# define RCC_DCKCFGR_TIMPRE (1 << 24) /* Bit 24: Timer clock prescaler selection */
#endif
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F40XXX_RCC_H */

View File

@ -40,7 +40,7 @@
/* This file is included by stm32_vectors.S. It provides the macro VECTOR that
* supplies ach STM32F40xxx vector in terms of a (lower-case) ISR label and an
* (upper-case) IRQ number as defined in arch/arm/include/stm32/stm32f40xxx_irq.h.
* stm32_vectors.S will defined the VECTOR in different ways in order to generate
* stm32_vectors.S will define the VECTOR macro in different ways in order to generate
* the interrupt vectors and handlers in their final form.
*/
@ -50,9 +50,13 @@
#ifdef CONFIG_ARMV7M_CMNVECTOR
/* Reserve 82 interrupt table entries for I/O interrupts. */
/* Reserve interrupt table entries for I/O interrupts. */
# ifdef CONFIG_STM32_STM32F427
# define ARMV7M_PERIPHERAL_INTERRUPTS 87
# else
# define ARMV7M_PERIPHERAL_INTERRUPTS 82
# endif
#else
@ -139,4 +143,12 @@ VECTOR(stm32_cryp, STM32_IRQ_CRYP) /* Vector 16+79: CRYP crypto gl
VECTOR(stm32_hash, STM32_IRQ_HASH) /* Vector 16+80: Hash and Rng global interrupt */
VECTOR(stm32_fpu, STM32_IRQ_FPU) /* Vector 16+81: FPU global interrupt */
#ifdef CONFIG_STM32_STM32F427
VECTOR(stm32_uart7, STM32_IRQ_UART7) /* Vector 16+82: UART7 interrupt */
VECTOR(stm32_uart8, STM32_IRQ_UART8) /* Vector 16+83: UART8 interrupt */
VECTOR(stm32_spi4, STM32_IRQ_SPI4) /* Vector 16+84: SPI4 interrupt */
VECTOR(stm32_spi5, STM32_IRQ_SPI5) /* Vector 16+85: SPI5 interrupt */
VECTOR(stm32_spi6, STM32_IRQ_SPI6) /* Vector 16+86: SPI6 interrupt */
#endif
#endif /* CONFIG_ARMV7M_CMNVECTOR */

View File

@ -160,6 +160,40 @@
# define STM32_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
#elif defined(CONFIG_UART7_SERIAL_CONSOLE)
# define STM32_CONSOLE_BASE STM32_UART7_BASE
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
# define STM32_CONSOLE_BAUD CONFIG_UART7_BAUD
# define STM32_CONSOLE_BITS CONFIG_UART7_BITS
# define STM32_CONSOLE_PARITY CONFIG_UART7_PARITY
# define STM32_CONSOLE_2STOP CONFIG_UART7_2STOP
# define STM32_CONSOLE_TX GPIO_UART7_TX
# define STM32_CONSOLE_RX GPIO_UART7_RX
# ifdef CONFIG_UART7_RS485
# define STM32_CONSOLE_RS485_DIR GPIO_UART7_RS485_DIR
# if (CONFIG_UART7_RS485_DIR_POLARITY == 0)
# define STM32_CONSOLE_RS485_DIR_POLARITY false
# else
# define STM32_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
#elif defined(CONFIG_UART8_SERIAL_CONSOLE)
# define STM32_CONSOLE_BASE STM32_UART8_BASE
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
# define STM32_CONSOLE_BAUD CONFIG_UART8_BAUD
# define STM32_CONSOLE_BITS CONFIG_UART8_BITS
# define STM32_CONSOLE_PARITY CONFIG_UART8_PARITY
# define STM32_CONSOLE_2STOP CONFIG_UART8_2STOP
# define STM32_CONSOLE_TX GPIO_UART8_TX
# define STM32_CONSOLE_RX GPIO_UART8_RX
# ifdef CONFIG_UART8_RS485
# define STM32_CONSOLE_RS485_DIR GPIO_UART8_RS485_DIR
# if (CONFIG_UART8_RS485_DIR_POLARITY == 0)
# define STM32_CONSOLE_RS485_DIR_POLARITY false
# else
# define STM32_CONSOLE_RS485_DIR_POLARITY true
# endif
# endif
#endif
/* CR1 settings */

View File

@ -90,9 +90,10 @@
# endif
# if defined(CONFIG_USART2_RXDMA) || defined(CONFIG_USART3_RXDMA) || \
defined(CONFIG_UART4_RXDMA) || defined(CONFIG_UART5_RXDMA)
defined(CONFIG_UART4_RXDMA) || defined(CONFIG_UART5_RXDMA) || \
defined(CONFIG_UART7_RXDMA) || defined(CONFIG_UART8_RXDMA)
# ifndef CONFIG_STM32_DMA1
# error STM32 USART2/3/4/5 receive DMA requires CONFIG_STM32_DMA1
# error STM32 USART2/3/4/5/7/8 receive DMA requires CONFIG_STM32_DMA1
# endif
# endif
@ -105,7 +106,9 @@
(defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_RS485)) || \
(defined(CONFIG_UART4_RXDMA) && defined(CONFIG_UART4_RS485)) || \
(defined(CONFIG_UART5_RXDMA) && defined(CONFIG_UART5_RS485)) || \
(defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_RS485))
(defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_RS485)) || \
(defined(CONFIG_UART7_RXDMA) && defined(CONFIG_UART7_RS485)) || \
(defined(CONFIG_UART8_RXDMA) && defined(CONFIG_UART8_RS485))
# error "RXDMA and RS-485 cannot be enabled at the same time for the same U[S]ART"
# endif
@ -138,6 +141,14 @@
# error "USART6 DMA channel not defined (DMAMAP_USART6_RX)"
# endif
# if defined(CONFIG_UART7_RXDMA) && !defined(DMAMAP_UART7_RX)
# error "UART7 DMA channel not defined (DMAMAP_UART7_RX)"
# endif
# if defined(CONFIG_UART8_RXDMA) && !defined(DMAMAP_UART8_RX)
# error "UART8 DMA channel not defined (DMAMAP_UART8_RX)"
# endif
# elif defined(CONFIG_STM32_STM32F10XX)
# if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART2_RXDMA) || \
@ -337,6 +348,12 @@ static int up_interrupt_uart5(int irq, void *context);
#ifdef CONFIG_STM32_USART6
static int up_interrupt_usart6(int irq, void *context);
#endif
#ifdef CONFIG_STM32_UART7
static int up_interrupt_uart7(int irq, void *context);
#endif
#ifdef CONFIG_STM32_UART8
static int up_interrupt_uart8(int irq, void *context);
#endif
/****************************************************************************
* Private Variables
@ -428,6 +445,22 @@ static char g_usart6rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
#ifdef CONFIG_STM32_UART7
static char g_uart7rxbuffer[CONFIG_UART7_RXBUFSIZE];
static char g_uart7txbuffer[CONFIG_UART7_TXBUFSIZE];
# ifdef CONFIG_UART7_RXDMA
static char g_uart7rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
#ifdef CONFIG_STM32_UART8
static char g_uart8rxbuffer[CONFIG_UART8_RXBUFSIZE];
static char g_uart8txbuffer[CONFIG_UART8_TXBUFSIZE];
# ifdef CONFIG_UART8_RXDMA
static char g_uart8rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
/* This describes the state of the STM32 USART1 ports. */
#ifdef CONFIG_STM32_USART1
@ -792,6 +825,126 @@ static struct up_dev_s g_usart6priv =
};
#endif
/* This describes the state of the STM32 UART7 port. */
#ifdef CONFIG_STM32_UART7
static struct up_dev_s g_uart7priv =
{
.dev =
{
#if CONSOLE_UART == 7
.isconsole = true,
#endif
.recv =
{
.size = CONFIG_UART7_RXBUFSIZE,
.buffer = g_uart7rxbuffer,
},
.xmit =
{
.size = CONFIG_UART7_TXBUFSIZE,
.buffer = g_uart7txbuffer,
},
#ifdef CONFIG_UART7_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_uart7priv,
},
.irq = STM32_IRQ_UART7,
.parity = CONFIG_UART7_PARITY,
.bits = CONFIG_UART7_BITS,
.stopbits2 = CONFIG_UART7_2STOP,
.baud = CONFIG_UART7_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_UART7_BASE,
.tx_gpio = GPIO_UART7_TX,
.rx_gpio = GPIO_UART7_RX,
#ifdef GPIO_UART7_CTS
.cts_gpio = GPIO_UART7_CTS,
#endif
#ifdef GPIO_UART7_RTS
.rts_gpio = GPIO_UART7_RTS,
#endif
#ifdef CONFIG_UART7_RXDMA
.rxdma_channel = DMAMAP_UART7_RX,
.rxfifo = g_uart7rxfifo,
#endif
.vector = up_interrupt_uart7,
#ifdef CONFIG_UART7_RS485
.rs485_dir_gpio = GPIO_UART7_RS485_DIR,
# if (CONFIG_UART7_RS485_DIR_POLARITY == 0)
.rs485_dir_polarity = false,
# else
.rs485_dir_polarity = true,
# endif
#endif
};
#endif
/* This describes the state of the STM32 UART8 port. */
#ifdef CONFIG_STM32_UART8
static struct up_dev_s g_uart8priv =
{
.dev =
{
#if CONSOLE_UART == 8
.isconsole = true,
#endif
.recv =
{
.size = CONFIG_UART8_RXBUFSIZE,
.buffer = g_uart8rxbuffer,
},
.xmit =
{
.size = CONFIG_UART8_TXBUFSIZE,
.buffer = g_uart8txbuffer,
},
#ifdef CONFIG_UART8_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_uart8priv,
},
.irq = STM32_IRQ_UART8,
.parity = CONFIG_UART8_PARITY,
.bits = CONFIG_UART8_BITS,
.stopbits2 = CONFIG_UART8_2STOP,
.baud = CONFIG_UART8_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_UART8_BASE,
.tx_gpio = GPIO_UART8_TX,
.rx_gpio = GPIO_UART8_RX,
#ifdef GPIO_UART8_CTS
.cts_gpio = GPIO_UART8_CTS,
#endif
#ifdef GPIO_UART8_RTS
.rts_gpio = GPIO_UART8_RTS,
#endif
#ifdef CONFIG_UART8_RXDMA
.rxdma_channel = DMAMAP_UART8_RX,
.rxfifo = g_uart8rxfifo,
#endif
.vector = up_interrupt_uart8,
#ifdef CONFIG_UART8_RS485
.rs485_dir_gpio = GPIO_UART8_RS485_DIR,
# if (CONFIG_UART8_RS485_DIR_POLARITY == 0)
.rs485_dir_polarity = false,
# else
.rs485_dir_polarity = true,
# endif
#endif
};
#endif
/* This table lets us iterate over the configured USARTs */
static struct up_dev_s *uart_devs[STM32_NUSART] =
@ -814,6 +967,12 @@ static struct up_dev_s *uart_devs[STM32_NUSART] =
#ifdef CONFIG_STM32_USART6
[5] = &g_usart6priv,
#endif
#ifdef CONFIG_STM32_UART7
[6] = &g_uart7priv,
#endif
#ifdef CONFIG_STM32_UART8
[7] = &g_uart8priv,
#endif
};
#ifdef CONFIG_PM
@ -1899,6 +2058,20 @@ static int up_interrupt_usart6(int irq, void *context)
}
#endif
#ifdef CONFIG_STM32_UART7
static int up_interrupt_uart7(int irq, void *context)
{
return up_interrupt_common(&g_uart7priv);
}
#endif
#ifdef CONFIG_STM32_UART8
static int up_interrupt_uart8(int irq, void *context)
{
return up_interrupt_common(&g_uart8priv);
}
#endif
/****************************************************************************
* Name: up_dma_rxcallback
*
@ -2187,6 +2360,20 @@ void stm32_serial_dma_poll(void)
}
#endif
#ifdef CONFIG_UART7_RXDMA
if (g_uart7priv.rxdma != NULL)
{
up_dma_rxcallback(g_uart7priv.rxdma, 0, &g_uart7priv);
}
#endif
#ifdef CONFIG_UART8_RXDMA
if (g_uart8priv.rxdma != NULL)
{
up_dma_rxcallback(g_uart8priv.rxdma, 0, &g_uart8priv);
}
#endif
irqrestore(flags);
}
#endif

View File

@ -82,7 +82,8 @@
#include "stm32_dma.h"
#include "stm32_spi.h"
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) || \
defined(CONFIG_STM32_SPI4) || defined(CONFIG_STM32_SPI5) || defined(CONFIG_STM32_SPI6)
/************************************************************************************
* Definitions
@ -377,6 +378,123 @@ static struct stm32_spidev_s g_spi3dev =
};
#endif
#ifdef CONFIG_STM32_SPI4
static const struct spi_ops_s g_sp4iops =
{
#ifndef CONFIG_SPI_OWNBUS
.lock = spi_lock,
#endif
.select = stm32_spi4select,
.setfrequency = spi_setfrequency,
.setmode = spi_setmode,
.setbits = spi_setbits,
.status = stm32_spi4status,
#ifdef CONFIG_SPI_CMDDATA
.cmddata = stm32_spi4cmddata,
#endif
.send = spi_send,
#ifdef CONFIG_SPI_EXCHANGE
.exchange = spi_exchange,
#else
.sndblock = spi_sndblock,
.recvblock = spi_recvblock,
#endif
.registercallback = 0,
};
static struct stm32_spidev_s g_spi4dev =
{
.spidev = { &g_sp4iops },
.spibase = STM32_SPI4_BASE,
.spiclock = STM32_PCLK1_FREQUENCY,
#ifdef CONFIG_STM32_SPI_INTERRUPTS
.spiirq = STM32_IRQ_SPI4,
#endif
#ifdef CONFIG_STM32_SPI_DMA
.rxch = DMACHAN_SPI4_RX,
.txch = DMACHAN_SPI4_TX,
#endif
};
#endif
#ifdef CONFIG_STM32_SPI5
static const struct spi_ops_s g_sp5iops =
{
#ifndef CONFIG_SPI_OWNBUS
.lock = spi_lock,
#endif
.select = stm32_spi5select,
.setfrequency = spi_setfrequency,
.setmode = spi_setmode,
.setbits = spi_setbits,
.status = stm32_spi5status,
#ifdef CONFIG_SPI_CMDDATA
.cmddata = stm32_spi5cmddata,
#endif
.send = spi_send,
#ifdef CONFIG_SPI_EXCHANGE
.exchange = spi_exchange,
#else
.sndblock = spi_sndblock,
.recvblock = spi_recvblock,
#endif
.registercallback = 0,
};
static struct stm32_spidev_s g_spi5dev =
{
.spidev = { &g_sp5iops },
.spibase = STM32_SPI5_BASE,
.spiclock = STM32_PCLK1_FREQUENCY,
#ifdef CONFIG_STM32_SPI_INTERRUPTS
.spiirq = STM32_IRQ_SPI5,
#endif
#ifdef CONFIG_STM32_SPI_DMA
.rxch = DMACHAN_SPI5_RX,
.txch = DMACHAN_SPI5_TX,
#endif
};
#endif
#ifdef CONFIG_STM32_SPI6
static const struct spi_ops_s g_sp6iops =
{
#ifndef CONFIG_SPI_OWNBUS
.lock = spi_lock,
#endif
.select = stm32_spi6select,
.setfrequency = spi_setfrequency,
.setmode = spi_setmode,
.setbits = spi_setbits,
.status = stm32_spi6status,
#ifdef CONFIG_SPI_CMDDATA
.cmddata = stm32_spi3cmddata,
#endif
.send = spi_send,
#ifdef CONFIG_SPI_EXCHANGE
.exchange = spi_exchange,
#else
.sndblock = spi_sndblock,
.recvblock = spi_recvblock,
#endif
.registercallback = 0,
};
static struct stm32_spidev_s g_spi6dev =
{
.spidev = { &g_sp6iops },
.spibase = STM32_SPI6_BASE,
.spiclock = STM32_PCLK1_FREQUENCY,
#ifdef CONFIG_STM32_SPI_INTERRUPTS
.spiirq = STM32_IRQ_SPI6,
#endif
#ifdef CONFIG_STM32_SPI_DMA
.rxch = DMACHAN_SPI6_RX,
.txch = DMACHAN_SPI6_TX,
#endif
};
#endif
/************************************************************************************
* Public Data
************************************************************************************/
@ -1464,6 +1582,78 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
}
else
#endif
#ifdef CONFIG_STM32_SPI4
if (port == 4)
{
/* Select SPI4 */
priv = &g_spi4dev;
/* Only configure if the port is not already configured */
if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
{
/* Configure SPI4 pins: SCK, MISO, and MOSI */
stm32_configgpio(GPIO_SPI4_SCK);
stm32_configgpio(GPIO_SPI4_MISO);
stm32_configgpio(GPIO_SPI4_MOSI);
/* Set up default configuration: Master, 8-bit, etc. */
spi_portinitialize(priv);
}
}
else
#endif
#ifdef CONFIG_STM32_SPI5
if (port == 5)
{
/* Select SPI5 */
priv = &g_spi5dev;
/* Only configure if the port is not already configured */
if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
{
/* Configure SPI5 pins: SCK, MISO, and MOSI */
stm32_configgpio(GPIO_SPI5_SCK);
stm32_configgpio(GPIO_SPI5_MISO);
stm32_configgpio(GPIO_SPI5_MOSI);
/* Set up default configuration: Master, 8-bit, etc. */
spi_portinitialize(priv);
}
}
else
#endif
#ifdef CONFIG_STM32_SPI6
if (port == 6)
{
/* Select SPI6 */
priv = &g_spi6dev;
/* Only configure if the port is not already configured */
if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
{
/* Configure SPI6 pins: SCK, MISO, and MOSI */
stm32_configgpio(GPIO_SPI6_SCK);
stm32_configgpio(GPIO_SPI6_MISO);
stm32_configgpio(GPIO_SPI6_MOSI);
/* Set up default configuration: Master, 8-bit, etc. */
spi_portinitialize(priv);
}
}
else
#endif
{
spidbg("ERROR: Unsupported SPI port: %d\n", port);
return NULL;
@ -1473,4 +1663,4 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
return (FAR struct spi_dev_s *)priv;
}
#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 || CONFIG_STM32_SPI3 */
#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 || CONFIG_STM32_SPI3 || CONFIG_STM32_SPI4 || CONFIG_STM32_SPI5 || CONFIG_STM32_SPI6 */

View File

@ -71,11 +71,11 @@ enum spi_dev_e;
************************************************************************************/
/************************************************************************************
* Name: stm32_spi1/2/3select and stm32_spi1/2/3status
* Name: stm32_spi1/2/...select and stm32_spi1/2/...status
*
* Description:
* The external functions, stm32_spi1/2/3select, stm32_spi1/2/3status, and
* stm32_spi1/2/3cmddata must be provided by board-specific logic. These are
* The external functions, stm32_spi1/2/...select, stm32_spi1/2/...status, and
* stm32_spi1/2/...cmddata must be provided by board-specific logic. These are
* implementations of the select, status, and cmddata methods of the SPI interface
* defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods
* (including up_spiinitialize()) are provided by common STM32 logic. To use this
@ -83,11 +83,11 @@ enum spi_dev_e;
*
* 1. Provide logic in stm32_boardinitialize() to configure SPI chip select
* pins.
* 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your
* 2. Provide stm32_spi1/2/...select() and stm32_spi1/2/...status() functions in your
* board-specific logic. These functions will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 3. If CONFIG_SPI_CMDDATA is defined in your NuttX configuration file, then
* provide stm32_spi1/2/3cmddata() functions in your board-specific logic.
* provide stm32_spi1/2/...cmddata() functions in your board-specific logic.
* These functions will perform cmd/data selection operations using GPIOs in the
* way your board is configured.
* 4. Add a calls to up_spiinitialize() in your low level application
@ -111,6 +111,18 @@ EXTERN void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, b
EXTERN uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
EXTERN int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
EXTERN void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
EXTERN uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
EXTERN int stm32_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
EXTERN void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
EXTERN uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
EXTERN int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
EXTERN void stm32_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
EXTERN uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
EXTERN int stm32_spi6cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#undef EXTERN
#if defined(__cplusplus)
}

View File

@ -52,6 +52,12 @@
* the device.
*/
#if STM32_NUSART < 8
# undef CONFIG_STM32_UART8
#endif
#if STM32_NUSART < 7
# undef CONFIG_STM32_UART7
#endif
#if STM32_NUSART < 6
# undef CONFIG_STM32_USART6
#endif
@ -75,7 +81,8 @@
#if defined(CONFIG_STM32_USART1) || defined(CONFIG_STM32_USART2) || \
defined(CONFIG_STM32_USART3) || defined(CONFIG_STM32_UART4) || \
defined(CONFIG_STM32_UART5) || defined(CONFIG_STM32_USART6)
defined(CONFIG_STM32_UART5) || defined(CONFIG_STM32_USART6) || \
defined(CONFIG_STM32_UART7) || defined(CONFIG_STM32_UART8)
# define HAVE_UART 1
#endif
@ -87,6 +94,8 @@
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 1
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART2)
@ -95,6 +104,8 @@
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 2
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART3)
@ -103,6 +114,8 @@
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 3
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART4)
@ -111,6 +124,8 @@
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 4
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART5)
@ -119,6 +134,8 @@
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 5
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART6)
@ -127,8 +144,31 @@
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 6
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART7_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART7)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 7
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART8_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART8)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART6_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# define CONSOLE_UART 8
# define HAVE_CONSOLE 1
#else
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
@ -136,6 +176,8 @@
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_UART7_SERIAL_CONSOLE
# undef CONFIG_UART8_SERIAL_CONSOLE
# define CONSOLE_UART 0
# undef HAVE_CONSOLE
#endif
@ -149,6 +191,8 @@
# undef CONFIG_UART4_RXDMA
# undef CONFIG_UART5_RXDMA
# undef CONFIG_USART6_RXDMA
# undef CONFIG_UART7_RXDMA
# undef CONFIG_UART8_RXDMA
#endif
/* Disable the DMA configuration on all unused USARTs */
@ -177,12 +221,21 @@
# undef CONFIG_USART6_RXDMA
#endif
#ifndef CONFIG_STM32_UART7
# undef CONFIG_UART7_RXDMA
#endif
#ifndef CONFIG_STM32_UART8
# undef CONFIG_UART8_RXDMA
#endif
/* Is DMA available on any (enabled) USART? */
#undef SERIAL_HAVE_DMA
#if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART2_RXDMA) || \
defined(CONFIG_USART3_RXDMA) || defined(CONFIG_UART4_RXDMA) || \
defined(CONFIG_UART5_RXDMA) || defined(CONFIG_USART6_RXDMA)
defined(CONFIG_UART5_RXDMA) || defined(CONFIG_USART6_RXDMA) || \
defined(CONFIG_UART7_RXDMA) || defined(CONFIG_UART8_RXDMA)
# define SERIAL_HAVE_DMA 1
#endif
@ -201,6 +254,10 @@
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_USART6_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_UART7_SERIAL_CONSOLE) && defined(CONFIG_UART7_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#elif defined(CONFIG_UART8_SERIAL_CONSOLE) && defined(CONFIG_UART8_RXDMA)
# define SERIAL_HAVE_CONSOLE_DMA 1
#endif
/* Is DMA used on all (enabled) USARTs */
@ -218,13 +275,18 @@
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_USART6) && !defined(CONFIG_USART6_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_UART7) && !defined(CONFIG_UART7_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_UART8) && !defined(CONFIG_UART8_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#endif
/* Is RS-485 used? */
#if defined(CONFIG_USART1_RS485) || defined(CONFIG_USART2_RS485) || \
defined(CONFIG_USART3_RS485) || defined(CONFIG_UART4_RS485) || \
defined(CONFIG_UART5_RS485) || defined(CONFIG_USART6_RS485)
defined(CONFIG_UART5_RS485) || defined(CONFIG_USART6_RS485) || \
defined(CONFIG_UART7_RS485) || defined(CONFIG_UART8_RS485)
# define HAVE_RS485 1
#endif

View File

@ -437,6 +437,19 @@ static inline void rcc_enableapb1(void)
regval |= RCC_APB1ENR_DACEN;
#endif
#ifdef CONFIG_STM32_UART7
/* UART7 clock enable */
regval |= RCC_APB1ENR_UART7EN;
#endif
#ifdef CONFIG_STM32_UART8
/* UART8 clock enable */
regval |= RCC_APB1ENR_UART8EN;
#endif
putreg32(regval, STM32_RCC_APB1ENR); /* Enable peripherals */
}
@ -512,6 +525,12 @@ static inline void rcc_enableapb2(void)
regval |= RCC_APB2ENR_SPI1EN;
#endif
#ifdef CONFIG_STM32_SPI4
/* SPI4 clock enable */
regval |= RCC_APB2ENR_SPI4EN;
#endif
#ifdef CONFIG_STM32_SYSCFG
/* System configuration controller clock enable */
@ -536,6 +555,18 @@ static inline void rcc_enableapb2(void)
regval |= RCC_APB2ENR_TIM11EN;
#endif
#ifdef CONFIG_STM32_SPI5
/* SPI5 clock enable */
regval |= RCC_APB2ENR_SPI5EN;
#endif
#ifdef CONFIG_STM32_SPI6
/* SPI6 clock enable */
regval |= RCC_APB2ENR_SPI6EN;
#endif
putreg32(regval, STM32_RCC_APB2ENR); /* Enable peripherals */
}
@ -591,7 +622,12 @@ static void stm32_stdclockconfig(void)
putreg32(regval, STM32_RCC_APB1ENR);
regval = getreg32(STM32_PWR_CR);
#if defined(CONFIG_STM32_STM32F427)
regval &= ~PWR_CR_VOS_MASK;
regval |= PWR_CR_VOS_SCALE_1;
#else
regval |= PWR_CR_VOS;
#endif
putreg32(regval, STM32_PWR_CR);
/* Set the HCLK source/divider */

View File

@ -292,6 +292,10 @@ config ARCH_HAVE_UART5
bool
config ARCH_HAVE_UART6
bool
config ARCH_HAVE_UART7
bool
config ARCH_HAVE_UART8
bool
config ARCH_HAVE_USART0
bool
@ -307,6 +311,10 @@ config ARCH_HAVE_USART5
bool
config ARCH_HAVE_USART6
bool
config ARCH_HAVE_USART7
bool
config ARCH_HAVE_USART8
bool
config MCU_SERIAL
bool
@ -403,6 +411,22 @@ config USART6_SERIAL_CONSOLE
bool "USART6"
depends on ARCH_HAVE_USART6
config UART7_SERIAL_CONSOLE
bool "UART7"
depends on ARCH_HAVE_UART7
config USART7_SERIAL_CONSOLE
bool "USART7"
depends on ARCH_HAVE_USART7
config UART8_SERIAL_CONSOLE
bool "UART8"
depends on ARCH_HAVE_UART8
config USART8_SERIAL_CONSOLE
bool "USART8"
depends on ARCH_HAVE_USART8
config NO_SERIAL_CONSOLE
bool "No serial console"
@ -1052,3 +1076,173 @@ config UART6_2STOP
1=Two stop bits
endmenu
menu "USART7 Configuration"
depends on ARCH_HAVE_USART7
config USART7_RXBUFSIZE
int "Receive buffer size"
default 256
help
Characters are buffered as they are received. This specifies
the size of the receive buffer.
config USART7_TXBUFSIZE
int "Transmit buffer size"
default 256
help
Characters are buffered before being sent. This specifies
the size of the transmit buffer.
config USART7_BAUD
int "BAUD rate"
default 115200
help
The configured BAUD of the USART.
config USART7_BITS
int "Character size"
default 8
help
The number of bits. Must be either 7 or 8.
config USART7_PARITY
int "Parity setting"
default 0
help
0=no parity, 1=odd parity, 2=even parity
config USART7_2STOP
int "Uses 2 stop bits"
default 0
help
1=Two stop bits
endmenu
menu "UART7 Configuration"
depends on ARCH_HAVE_UART7
config UART7_RXBUFSIZE
int "Receive buffer size"
default 256
help
Characters are buffered as they are received. This specifies
the size of the receive buffer.
config UART7_TXBUFSIZE
int "Transmit buffer size"
default 256
help
Characters are buffered before being sent. This specifies
the size of the transmit buffer.
config UART7_BAUD
int "BAUD rate"
default 115200
help
The configured BAUD of the UART.
config UART7_BITS
int "Character size"
default 8
help
The number of bits. Must be either 7 or 8.
config UART7_PARITY
int "Parity setting"
default 0
help
0=no parity, 1=odd parity, 2=even parity
config UART7_2STOP
int "Uses 2 stop bits"
default 0
help
1=Two stop bits
menu "USART8 Configuration"
depends on ARCH_HAVE_USART8
config USART8_RXBUFSIZE
int "Receive buffer size"
default 256
help
Characters are buffered as they are received. This specifies
the size of the receive buffer.
config USART8_TXBUFSIZE
int "Transmit buffer size"
default 256
help
Characters are buffered before being sent. This specifies
the size of the transmit buffer.
config USART8_BAUD
int "BAUD rate"
default 115200
help
The configured BAUD of the USART.
config USART8_BITS
int "Character size"
default 8
help
The number of bits. Must be either 7 or 8.
config USART8_PARITY
int "Parity setting"
default 0
help
0=no parity, 1=odd parity, 2=even parity
config USART8_2STOP
int "Uses 2 stop bits"
default 0
help
1=Two stop bits
endmenu
menu "UART8 Configuration"
depends on ARCH_HAVE_UART8
config UART8_RXBUFSIZE
int "Receive buffer size"
default 256
help
Characters are buffered as they are received. This specifies
the size of the receive buffer.
config UART8_TXBUFSIZE
int "Transmit buffer size"
default 256
help
Characters are buffered before being sent. This specifies
the size of the transmit buffer.
config UART8_BAUD
int "BAUD rate"
default 115200
help
The configured BAUD of the UART.
config UART8_BITS
int "Character size"
default 8
help
The number of bits. Must be either 7 or 8.
config UART8_PARITY
int "Parity setting"
default 0
help
0=no parity, 1=odd parity, 2=even parity
config UART8_2STOP
int "Uses 2 stop bits"
default 0
help
1=Two stop bits
endmenu