diff --git a/arch/arm/include/stm32/chip.h b/arch/arm/include/stm32/chip.h index f155df64d23..2405bd39b9f 100644 --- a/arch/arm/include/stm32/chip.h +++ b/arch/arm/include/stm32/chip.h @@ -2099,6 +2099,31 @@ # define STM32_NRNG 1 /* Random number generator (RNG) */ # define STM32_NDCMI 1 /* Digital camera interface (DCMI) */ +#elif defined(CONFIG_ARCH_CHIP_STM32F427A) /* UBGA169 1024/2048KiB flash 256KiB SRAM */ +# 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_NLCD 0 /* No LCD */ +# define STM32_NUSBOTG 1 /* USB OTG FS/HS */ +# define STM32_NGPIO 130 /* GPIOA-I */ +# define STM32_NADC 3 /* 12-bit ADC1-3, 24 channels */ +# define STM32_NDAC 2 /* 12-bit DAC1, 2 channels */ +# define STM32_NCAPSENSE 0 /* No capacitive sensing channels */ +# 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*/ + #elif defined(CONFIG_ARCH_CHIP_STM32F429I) /* BGA176; LQFP176 1024/2048KiB flash 256KiB SRAM */ # define STM32_NFSMC 1 /* FSMC */ # define STM32_NATIM 2 /* Two advanced timers TIM1 and 8 */ diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 7a3768dde79..44bd7f8bed6 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -1061,6 +1061,12 @@ config ARCH_CHIP_STM32F407IG select STM32_STM32F4XXX select STM32_STM32F407 +config ARCH_CHIP_STM32F427A + bool "STM32F427A" + select STM32_STM32F4XXX + select STM32_STM32F427A + select STM32_STM32F427 + config ARCH_CHIP_STM32F427V bool "STM32F427V" select STM32_STM32F4XXX @@ -1811,6 +1817,51 @@ config STM32_STM32F427 select STM32_HAVE_SPI6 select STM32_HAVE_I2SPLL + +config STM32_STM32F427A + bool + default n + select STM32_HAVE_OVERDRIVE + select STM32_HAVE_FMC + select STM32_HAVE_CCM + select STM32_HAVE_USART2 + select STM32_HAVE_USART3 + select STM32_HAVE_UART4 + select STM32_HAVE_UART5 + select STM32_HAVE_USART6 + select STM32_HAVE_UART7 + select STM32_HAVE_UART8 + select STM32_HAVE_TIM1 + select STM32_HAVE_TIM3 + select STM32_HAVE_TIM4 + select STM32_HAVE_TIM5 + select STM32_HAVE_TIM6 + select STM32_HAVE_TIM7 + select STM32_HAVE_TIM8 + select STM32_HAVE_TIM9 + select STM32_HAVE_TIM10 + select STM32_HAVE_TIM11 + select STM32_HAVE_TIM12 + select STM32_HAVE_TIM13 + select STM32_HAVE_TIM14 + select STM32_HAVE_ADC1 + select STM32_HAVE_ADC2 + select STM32_HAVE_ADC3 + select STM32_HAVE_CAN1 + select STM32_HAVE_CAN2 + select STM32_HAVE_DAC1 + select STM32_HAVE_RNG + select STM32_HAVE_ETHMAC + select STM32_HAVE_SPI2 + select STM32_HAVE_SPI3 + select STM32_HAVE_SPI4 + select STM32_HAVE_SPI5 + select STM32_HAVE_I2S3 + select STM32_HAVE_I2C3 + select STM32_HAVE_OTGFS + select STM32_HAVE_SPI6 + select STM32_HAVE_I2SPLL + # This is really 429/439, but we treat the two the same. config STM32_STM32F429 diff --git a/arch/arm/src/stm32/hardware/stm32_memorymap.h b/arch/arm/src/stm32/hardware/stm32_memorymap.h index ea79db26377..4f3f276e68b 100644 --- a/arch/arm/src/stm32/hardware/stm32_memorymap.h +++ b/arch/arm/src/stm32/hardware/stm32_memorymap.h @@ -41,7 +41,11 @@ #elif defined(CONFIG_STM32_STM32F37XX) # include "hardware/stm32f37xxx_memorymap.h" #elif defined(CONFIG_STM32_STM32F4XXX) -# include "hardware/stm32f40xxx_memorymap.h" +# if defined (CONFIG_STM32_STM32F427A) +# include "hardware/stm32f427ax_memorymap.h" +# else +# include "hardware/stm32f40xxx_memorymap.h" +# endif #elif defined(CONFIG_STM32_STM32G4XXX) # include "hardware/stm32g4xxxx_memorymap.h" #else diff --git a/arch/arm/src/stm32/hardware/stm32_pinmap.h b/arch/arm/src/stm32/hardware/stm32_pinmap.h index 348b301714b..cf1163dabcb 100644 --- a/arch/arm/src/stm32/hardware/stm32_pinmap.h +++ b/arch/arm/src/stm32/hardware/stm32_pinmap.h @@ -180,9 +180,17 @@ #elif defined(CONFIG_STM32_STM32F4XXX) # if defined(CONFIG_STM32_USE_LEGACY_PINMAP) -# include "hardware/stm32f40xxx_pinmap_legacy.h" +# if defined(CONFIG_STM32_STM32F427A) +# include "hardware/stm32f427ax_pinmap_legacy.h" +# else +# include "hardware/stm32f40xxx_pinmap_legacy.h" +# endif # else -# include "hardware/stm32f40xxx_pinmap.h" +# if defined(CONFIG_STM32_STM32F427A) +# include "hardware/stm32f427ax_pinmap.h" +# else +# include "hardware/stm32f40xxx_pinmap.h" +# endif # endif /* STM32 G4 Family **********************************************************/ diff --git a/arch/arm/src/stm32/hardware/stm32f427ax_gpio.h b/arch/arm/src/stm32/hardware/stm32f427ax_gpio.h new file mode 100644 index 00000000000..f883f18e33f --- /dev/null +++ b/arch/arm/src/stm32/hardware/stm32f427ax_gpio.h @@ -0,0 +1,380 @@ +/**************************************************************************** + * arch/arm/src/stm32/hardware/stm32f427xx_gpio.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_GPIO_H +#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_GPIO_H + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define STM32_NGPIO_PORTS ((STM32_NGPIO + 15) >> 4) + +/* Register Offsets *********************************************************/ + +#define STM32_GPIO_MODER_OFFSET 0x0000 /* GPIO port mode register */ +#define STM32_GPIO_OTYPER_OFFSET 0x0004 /* GPIO port output type register */ +#define STM32_GPIO_OSPEED_OFFSET 0x0008 /* GPIO port output speed register */ +#define STM32_GPIO_PUPDR_OFFSET 0x000c /* GPIO port pull-up/pull-down register */ +#define STM32_GPIO_IDR_OFFSET 0x0010 /* GPIO port input data register */ +#define STM32_GPIO_ODR_OFFSET 0x0014 /* GPIO port output data register */ +#define STM32_GPIO_BSRR_OFFSET 0x0018 /* GPIO port bit set/reset register */ +#define STM32_GPIO_LCKR_OFFSET 0x001c /* GPIO port configuration lock register */ +#define STM32_GPIO_AFRL_OFFSET 0x0020 /* GPIO alternate function low register */ +#define STM32_GPIO_AFRH_OFFSET 0x0024 /* GPIO alternate function high register */ + +/* Register Addresses *******************************************************/ + +#if STM32_NGPIO_PORTS > 0 +# define STM32_GPIOA_MODER (STM32_GPIOA_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOA_OTYPER (STM32_GPIOA_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOA_OSPEED (STM32_GPIOA_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOA_PUPDR (STM32_GPIOA_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOA_IDR (STM32_GPIOA_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOA_ODR (STM32_GPIOA_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOA_BSRR (STM32_GPIOA_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOA_LCKR (STM32_GPIOA_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOA_AFRL (STM32_GPIOA_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOA_AFRH (STM32_GPIOA_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 1 +# define STM32_GPIOB_MODER (STM32_GPIOB_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOB_OTYPER (STM32_GPIOB_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOB_OSPEED (STM32_GPIOB_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOB_PUPDR (STM32_GPIOB_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOB_IDR (STM32_GPIOB_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOB_ODR (STM32_GPIOB_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOB_BSRR (STM32_GPIOB_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOB_LCKR (STM32_GPIOB_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOB_AFRL (STM32_GPIOB_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOB_AFRH (STM32_GPIOB_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 2 +# define STM32_GPIOC_MODER (STM32_GPIOC_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOC_OTYPER (STM32_GPIOC_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOC_OSPEED (STM32_GPIOC_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOC_PUPDR (STM32_GPIOC_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOC_IDR (STM32_GPIOC_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOC_ODR (STM32_GPIOC_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOC_BSRR (STM32_GPIOC_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOC_LCKR (STM32_GPIOC_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOC_AFRL (STM32_GPIOC_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOC_AFRH (STM32_GPIOC_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 3 +# define STM32_GPIOD_MODER (STM32_GPIOD_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOD_OTYPER (STM32_GPIOD_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOD_OSPEED (STM32_GPIOD_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOD_PUPDR (STM32_GPIOD_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOD_IDR (STM32_GPIOD_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOD_ODR (STM32_GPIOD_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOD_BSRR (STM32_GPIOD_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOD_LCKR (STM32_GPIOD_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOD_AFRL (STM32_GPIOD_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOD_AFRH (STM32_GPIOD_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 4 +# define STM32_GPIOE_MODER (STM32_GPIOE_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOE_OTYPER (STM32_GPIOE_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOE_OSPEED (STM32_GPIOE_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOE_PUPDR (STM32_GPIOE_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOE_IDR (STM32_GPIOE_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOE_ODR (STM32_GPIOE_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOE_BSRR (STM32_GPIOE_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOE_LCKR (STM32_GPIOE_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOE_AFRL (STM32_GPIOE_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOE_AFRH (STM32_GPIOE_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 5 +# define STM32_GPIOF_MODER (STM32_GPIOF_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOF_OTYPER (STM32_GPIOF_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOF_OSPEED (STM32_GPIOF_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOF_PUPDR (STM32_GPIOF_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOF_IDR (STM32_GPIOF_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOF_ODR (STM32_GPIOF_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOF_BSRR (STM32_GPIOF_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOF_LCKR (STM32_GPIOF_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOF_AFRL (STM32_GPIOF_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOF_AFRH (STM32_GPIOF_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 6 +# define STM32_GPIOG_MODER (STM32_GPIOG_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOG_OTYPER (STM32_GPIOG_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOG_OSPEED (STM32_GPIOG_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOG_PUPDR (STM32_GPIOG_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOG_IDR (STM32_GPIOG_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOG_ODR (STM32_GPIOG_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOG_BSRR (STM32_GPIOG_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOG_LCKR (STM32_GPIOG_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOG_AFRL (STM32_GPIOG_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOG_AFRH (STM32_GPIOG_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 7 +# define STM32_GPIOH_MODER (STM32_GPIOH_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOH_OTYPER (STM32_GPIOH_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOH_OSPEED (STM32_GPIOH_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOH_PUPDR (STM32_GPIOH_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOH_IDR (STM32_GPIOH_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOH_ODR (STM32_GPIOH_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOH_BSRR (STM32_GPIOH_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOH_LCKR (STM32_GPIOH_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOH_AFRL (STM32_GPIOH_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOH_AFRH (STM32_GPIOH_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 8 +# define STM32_GPIOI_MODER (STM32_GPIOI_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOI_OTYPER (STM32_GPIOI_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOI_OSPEED (STM32_GPIOI_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOI_PUPDR (STM32_GPIOI_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOI_IDR (STM32_GPIOI_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOI_ODR (STM32_GPIOI_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOI_BSRR (STM32_GPIOI_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOI_LCKR (STM32_GPIOI_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOI_AFRL (STM32_GPIOI_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOI_AFRH (STM32_GPIOI_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 9 +# define STM32_GPIOJ_MODER (STM32_GPIOJ_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOJ_OTYPER (STM32_GPIOJ_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOJ_OSPEED (STM32_GPIOJ_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOJ_PUPDR (STM32_GPIOJ_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOJ_IDR (STM32_GPIOJ_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOJ_ODR (STM32_GPIOJ_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOJ_BSRR (STM32_GPIOJ_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOJ_LCKR (STM32_GPIOJ_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOJ_AFRL (STM32_GPIOJ_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOJ_AFRH (STM32_GPIOJ_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +#if STM32_NGPIO_PORTS > 10 +# define STM32_GPIOK_MODER (STM32_GPIOK_BASE+STM32_GPIO_MODER_OFFSET) +# define STM32_GPIOK_OTYPER (STM32_GPIOK_BASE+STM32_GPIO_OTYPER_OFFSET) +# define STM32_GPIOK_OSPEED (STM32_GPIOK_BASE+STM32_GPIO_OSPEED_OFFSET) +# define STM32_GPIOK_PUPDR (STM32_GPIOK_BASE+STM32_GPIO_PUPDR_OFFSET) +# define STM32_GPIOK_IDR (STM32_GPIOK_BASE+STM32_GPIO_IDR_OFFSET) +# define STM32_GPIOK_ODR (STM32_GPIOK_BASE+STM32_GPIO_ODR_OFFSET) +# define STM32_GPIOK_BSRR (STM32_GPIOK_BASE+STM32_GPIO_BSRR_OFFSET) +# define STM32_GPIOK_LCKR (STM32_GPIOK_BASE+STM32_GPIO_LCKR_OFFSET) +# define STM32_GPIOK_AFRL (STM32_GPIOK_BASE+STM32_GPIO_AFRL_OFFSET) +# define STM32_GPIOK_AFRH (STM32_GPIOK_BASE+STM32_GPIO_AFRH_OFFSET) +#endif + +/* Register Bitfield Definitions ********************************************/ + +/* GPIO port mode register */ + +#define GPIO_MODER_INPUT (0) /* Input */ +#define GPIO_MODER_OUTPUT (1) /* General purpose output mode */ +#define GPIO_MODER_ALT (2) /* Alternate mode */ +#define GPIO_MODER_ANALOG (3) /* Analog mode */ + +#define GPIO_MODER_SHIFT(n) ((n) << 1) +#define GPIO_MODER_MASK(n) (3 << GPIO_MODER_SHIFT(n)) + +#define GPIO_MODER0_SHIFT (0) +#define GPIO_MODER0_MASK (3 << GPIO_MODER0_SHIFT) +#define GPIO_MODER1_SHIFT (2) +#define GPIO_MODER1_MASK (3 << GPIO_MODER1_SHIFT) +#define GPIO_MODER2_SHIFT (4) +#define GPIO_MODER2_MASK (3 << GPIO_MODER2_SHIFT) +#define GPIO_MODER3_SHIFT (6) +#define GPIO_MODER3_MASK (3 << GPIO_MODER3_SHIFT) +#define GPIO_MODER4_SHIFT (8) +#define GPIO_MODER4_MASK (3 << GPIO_MODER4_SHIFT) +#define GPIO_MODER5_SHIFT (10) +#define GPIO_MODER5_MASK (3 << GPIO_MODER5_SHIFT) +#define GPIO_MODER6_SHIFT (12) +#define GPIO_MODER6_MASK (3 << GPIO_MODER6_SHIFT) +#define GPIO_MODER7_SHIFT (14) +#define GPIO_MODER7_MASK (3 << GPIO_MODER7_SHIFT) +#define GPIO_MODER8_SHIFT (16) +#define GPIO_MODER8_MASK (3 << GPIO_MODER8_SHIFT) +#define GPIO_MODER9_SHIFT (18) +#define GPIO_MODER9_MASK (3 << GPIO_MODER9_SHIFT) +#define GPIO_MODER10_SHIFT (20) +#define GPIO_MODER10_MASK (3 << GPIO_MODER10_SHIFT) +#define GPIO_MODER11_SHIFT (22) +#define GPIO_MODER11_MASK (3 << GPIO_MODER11_SHIFT) +#define GPIO_MODER12_SHIFT (24) +#define GPIO_MODER12_MASK (3 << GPIO_MODER12_SHIFT) +#define GPIO_MODER13_SHIFT (26) +#define GPIO_MODER13_MASK (3 << GPIO_MODER13_SHIFT) +#define GPIO_MODER14_SHIFT (28) +#define GPIO_MODER14_MASK (3 << GPIO_MODER14_SHIFT) +#define GPIO_MODER15_SHIFT (30) +#define GPIO_MODER15_MASK (3 << GPIO_MODER15_SHIFT) + +/* GPIO port output type register */ + +#define GPIO_OTYPER_OD(n) (1 << (n)) /* 1=Output open-drain */ +#define GPIO_OTYPER_PP(n) (0) /* 0=Output push-pull */ + +/* GPIO port output speed register */ + +#define GPIO_OSPEED_2MHz (0) /* 2 MHz Low speed */ +#define GPIO_OSPEED_25MHz (1) /* 25 MHz Medium speed */ +#define GPIO_OSPEED_50MHz (2) /* 50 MHz Fast speed */ +#define GPIO_OSPEED_100MHz (3) /* 100 MHz High speed on 30 pF (80 MHz Output max speed on 15 pF) */ + +#define GPIO_OSPEED_SHIFT(n) ((n) << 1) +#define GPIO_OSPEED_MASK(n) (3 << GPIO_OSPEED_SHIFT(n)) + +#define GPIO_OSPEED0_SHIFT (0) +#define GPIO_OSPEED0_MASK (3 << GPIO_OSPEED0_SHIFT) +#define GPIO_OSPEED1_SHIFT (2) +#define GPIO_OSPEED1_MASK (3 << GPIO_OSPEED1_SHIFT) +#define GPIO_OSPEED2_SHIFT (4) +#define GPIO_OSPEED2_MASK (3 << GPIO_OSPEED2_SHIFT) +#define GPIO_OSPEED3_SHIFT (6) +#define GPIO_OSPEED3_MASK (3 << GPIO_OSPEED3_SHIFT) +#define GPIO_OSPEED4_SHIFT (8) +#define GPIO_OSPEED4_MASK (3 << GPIO_OSPEED4_SHIFT) +#define GPIO_OSPEED5_SHIFT (10) +#define GPIO_OSPEED5_MASK (3 << GPIO_OSPEED5_SHIFT) +#define GPIO_OSPEED6_SHIFT (12) +#define GPIO_OSPEED6_MASK (3 << GPIO_OSPEED6_SHIFT) +#define GPIO_OSPEED7_SHIFT (14) +#define GPIO_OSPEED7_MASK (3 << GPIO_OSPEED7_SHIFT) +#define GPIO_OSPEED8_SHIFT (16) +#define GPIO_OSPEED8_MASK (3 << GPIO_OSPEED8_SHIFT) +#define GPIO_OSPEED9_SHIFT (18) +#define GPIO_OSPEED9_MASK (3 << GPIO_OSPEED9_SHIFT) +#define GPIO_OSPEED10_SHIFT (20) +#define GPIO_OSPEED10_MASK (3 << GPIO_OSPEED10_SHIFT) +#define GPIO_OSPEED11_SHIFT (22) +#define GPIO_OSPEED11_MASK (3 << GPIO_OSPEED11_SHIFT) +#define GPIO_OSPEED12_SHIFT (24) +#define GPIO_OSPEED12_MASK (3 << GPIO_OSPEED12_SHIFT) +#define GPIO_OSPEED13_SHIFT (26) +#define GPIO_OSPEED13_MASK (3 << GPIO_OSPEED13_SHIFT) +#define GPIO_OSPEED14_SHIFT (28) +#define GPIO_OSPEED14_MASK (3 << GPIO_OSPEED14_SHIFT) +#define GPIO_OSPEED15_SHIFT (30) +#define GPIO_OSPEED15_MASK (3 << GPIO_OSPEED15_SHIFT) + +/* GPIO port pull-up/pull-down register */ + +#define GPIO_PUPDR_NONE (0) /* No pull-up, pull-down */ +#define GPIO_PUPDR_PULLUP (1) /* Pull-up */ +#define GPIO_PUPDR_PULLDOWN (2) /* Pull-down */ + +#define GPIO_PUPDR_SHIFT(n) ((n) << 1) +#define GPIO_PUPDR_MASK(n) (3 << GPIO_PUPDR_SHIFT(n)) + +#define GPIO_PUPDR0_SHIFT (0) +#define GPIO_PUPDR0_MASK (3 << GPIO_PUPDR0_SHIFT) +#define GPIO_PUPDR1_SHIFT (2) +#define GPIO_PUPDR1_MASK (3 << GPIO_PUPDR1_SHIFT) +#define GPIO_PUPDR2_SHIFT (4) +#define GPIO_PUPDR2_MASK (3 << GPIO_PUPDR2_SHIFT) +#define GPIO_PUPDR3_SHIFT (6) +#define GPIO_PUPDR3_MASK (3 << GPIO_PUPDR3_SHIFT) +#define GPIO_PUPDR4_SHIFT (8) +#define GPIO_PUPDR4_MASK (3 << GPIO_PUPDR4_SHIFT) +#define GPIO_PUPDR5_SHIFT (10) +#define GPIO_PUPDR5_MASK (3 << GPIO_PUPDR5_SHIFT) +#define GPIO_PUPDR6_SHIFT (12) +#define GPIO_PUPDR6_MASK (3 << GPIO_PUPDR6_SHIFT) +#define GPIO_PUPDR7_SHIFT (14) +#define GPIO_PUPDR7_MASK (3 << GPIO_PUPDR7_SHIFT) +#define GPIO_PUPDR8_SHIFT (16) +#define GPIO_PUPDR8_MASK (3 << GPIO_PUPDR8_SHIFT) +#define GPIO_PUPDR9_SHIFT (18) +#define GPIO_PUPDR9_MASK (3 << GPIO_PUPDR9_SHIFT) +#define GPIO_PUPDR10_SHIFT (20) +#define GPIO_PUPDR10_MASK (3 << GPIO_PUPDR10_SHIFT) +#define GPIO_PUPDR11_SHIFT (22) +#define GPIO_PUPDR11_MASK (3 << GPIO_PUPDR11_SHIFT) +#define GPIO_PUPDR12_SHIFT (24) +#define GPIO_PUPDR12_MASK (3 << GPIO_PUPDR12_SHIFT) +#define GPIO_PUPDR13_SHIFT (26) +#define GPIO_PUPDR13_MASK (3 << GPIO_PUPDR13_SHIFT) +#define GPIO_PUPDR14_SHIFT (28) +#define GPIO_PUPDR14_MASK (3 << GPIO_PUPDR14_SHIFT) +#define GPIO_PUPDR15_SHIFT (30) +#define GPIO_PUPDR15_MASK (3 << GPIO_PUPDR15_SHIFT) + +/* GPIO port input data register */ + +#define GPIO_IDR(n) (1 << (n)) + +/* GPIO port output data register */ + +#define GPIO_ODR(n) (1 << (n)) + +/* GPIO port bit set/reset register */ + +#define GPIO_BSRR_SET(n) (1 << (n)) +#define GPIO_BSRR_RESET(n) (1 << ((n)+16)) + +/* GPIO port configuration lock register */ + +#define GPIO_LCKR(n) (1 << (n)) +#define GPIO_LCKK (1 << 16) /* Lock key */ + +/* GPIO alternate function low/high register */ + +#define GPIO_AFR_SHIFT(n) ((n) << 2) +#define GPIO_AFR_MASK(n) (15 << GPIO_AFR_SHIFT(n)) + +#define GPIO_AFRL0_SHIFT (0) +#define GPIO_AFRL0_MASK (15 << GPIO_AFRL0_SHIFT) +#define GPIO_AFRL1_SHIFT (4) +#define GPIO_AFRL1_MASK (15 << GPIO_AFRL1_SHIFT) +#define GPIO_AFRL2_SHIFT (8) +#define GPIO_AFRL2_MASK (15 << GPIO_AFRL2_SHIFT) +#define GPIO_AFRL3_SHIFT (12) +#define GPIO_AFRL3_MASK (15 << GPIO_AFRL3_SHIFT) +#define GPIO_AFRL4_SHIFT (16) +#define GPIO_AFRL4_MASK (15 << GPIO_AFRL4_SHIFT) +#define GPIO_AFRL5_SHIFT (20) +#define GPIO_AFRL5_MASK (15 << GPIO_AFRL5_SHIFT) +#define GPIO_AFRL6_SHIFT (24) +#define GPIO_AFRL6_MASK (15 << GPIO_AFRL6_SHIFT) +#define GPIO_AFRL7_SHIFT (28) +#define GPIO_AFRL7_MASK (15 << GPIO_AFRL7_SHIFT) + +#define GPIO_AFRH8_SHIFT (0) +#define GPIO_AFRH8_MASK (15 << GPIO_AFRH8_SHIFT) +#define GPIO_AFRH9_SHIFT (4) +#define GPIO_AFRH9_MASK (15 << GPIO_AFRH9_SHIFT) +#define GPIO_AFRH10_SHIFT (8) +#define GPIO_AFRH10_MASK (15 << GPIO_AFRH10_SHIFT) +#define GPIO_AFRH11_SHIFT (12) +#define GPIO_AFRH11_MASK (15 << GPIO_AFRH11_SHIFT) +#define GPIO_AFRH12_SHIFT (16) +#define GPIO_AFRH12_MASK (15 << GPIO_AFRH12_SHIFT) +#define GPIO_AFRH13_SHIFT (20) +#define GPIO_AFRH13_MASK (15 << GPIO_AFRH13_SHIFT) +#define GPIO_AFRH14_SHIFT (24) +#define GPIO_AFRH14_MASK (15 << GPIO_AFRH14_SHIFT) +#define GPIO_AFRH15_SHIFT (28) +#define GPIO_AFRH15_MASK (15 << GPIO_AFRH15_SHIFT) + +#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_GPIO_H */ diff --git a/arch/arm/src/stm32/hardware/stm32f427ax_memorymap.h b/arch/arm/src/stm32/hardware/stm32f427ax_memorymap.h new file mode 100644 index 00000000000..431243fbe8a --- /dev/null +++ b/arch/arm/src/stm32/hardware/stm32f427ax_memorymap.h @@ -0,0 +1,222 @@ +/**************************************************************************** + * arch/arm/src/stm32/hardware/stm32f427xx_memorymap.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_MEMORYMAP_H +#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_MEMORYMAP_H + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* STM32F40XXX Address Blocks ***********************************************/ + +#define STM32_CODE_BASE 0x00000000 /* 0x00000000-0x1fffffff: 512Mb code block */ +#define STM32_SRAM_BASE 0x20000000 /* 0x20000000-0x3fffffff: 512Mb sram block */ +#define STM32_PERIPH_BASE 0x40000000 /* 0x40000000-0x5fffffff: 512Mb peripheral block */ + +#define STM32_FSMC_BASE12 0x60000000 /* 0x60000000-0x7fffffff: 512Mb FSMC bank1&2 block */ +# define STM32_FSMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */ +# define STM32_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */ +#define STM32_FSMC_BASE34 0x80000000 /* 0x80000000-0x8fffffff: 512Mb FSMC bank3&4 block */ +# define STM32_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */ +# define STM32_FSMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/ +#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */ + +#define STM32_FMC_BASE12 0x60000000 /* 0x60000000-0x7fffffff: 512Mb FMC bank1&2 block */ +# define STM32_FMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */ +# define STM32_FMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */ +#define STM32_FMC_BASE34 0x80000000 /* 0x80000000-0x8fffffff: 512Mb FMC bank3&4 block */ +# define STM32_FMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */ +# define STM32_FMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/ +#define STM32_FMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FMC register block */ +#define STM32_FMC_BASE56 0x80000000 /* 0x80000000-0x8fffffff: 512Mb FMC bank5&6 block */ +# define STM32_FMC_BANK5 0xc0000000 /* 0xc0000000-0xcfffffff: 256Mb SDRAM */ +# define STM32_FMC_BANK6 0xd0000000 /* 0xd0000000-0xdfffffff: 256Mb SDRAM */ + +#define STM32_CORTEX_BASE 0xe0000000 /* 0xe0000000-0xffffffff: 512Mb Cortex-M4 block */ + +#define STM32_REGION_MASK 0xf0000000 +#define STM32_IS_SRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_SRAM_BASE) +#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FSMC_BANK1) + +/* Code Base Addresses ******************************************************/ + +#define STM32_BOOT_BASE 0x00000000 /* 0x00000000-0x000fffff: Aliased boot memory */ + /* 0x00100000-0x07ffffff: Reserved */ +#define STM32_FLASH_BASE 0x08000000 /* 0x08000000-0x080fffff: FLASH memory */ + /* 0x08100000-0x0fffffff: Reserved */ +#define STM32_CCMRAM_BASE 0x10000000 /* 0x10000000-0x1000ffff: 64Kb CCM data RAM */ + /* 0x10010000-0x1ffeffff: Reserved */ +#define STM32_SYSMEM_BASE 0x1fff0000 /* 0x1fff0000-0x1fff7a0f: System memory */ + /* 0x1fff7a10-0x1fff7fff: Reserved */ +#define STM32_OPTION_BASE 0x1fffc000 /* 0x1fffc000-0x1fffc007: Option bytes */ + /* 0x1fffc008-0x1fffffff: Reserved */ + +/* System Memory Addresses **************************************************/ + +#define STM32_SYSMEM_UID 0x1fff7a10 /* The 96-bit unique device identifier */ +#define STM32_SYSMEM_FSIZE 0x1fff7a22 /* This bitfield indicates the size of + * the device Flash memory expressed in + * Kbytes. Example: 0x0400 corresponds + * to 1024 Kbytes. + */ + +/* SRAM Base Addresses ******************************************************/ + +/* 0x20000000-0x2001bfff: + * 112Kb aliased by bit-banding + */ + +/* 0x2001c000-0x2001ffff: + * 16Kb aliased by bit-banding + */ + +#define STM32_SRAMBB_BASE 0x22000000 /* 0x22000000- : SRAM bit-band region */ + +/* Peripheral Base Addresses ************************************************/ + +#define STM32_APB1_BASE 0x40000000 /* 0x40000000-0x400023ff: APB1 */ + /* 0x40002400-0x400027ff: Reserved */ + /* 0x40002800-0x400077ff: APB1 */ + /* 0x40007800-0x4000ffff: Reserved */ +#define STM32_APB2_BASE 0x40010000 /* 0x40010000-0x400023ff: APB2 */ + /* 0x40013400-0x400137ff: Reserved */ + /* 0x40013800-0x40013bff: SYSCFG */ +#define STM32_EXTI_BASE 0x40013c00 /* 0x40013c00-0x40013fff: EXTI */ + /* 0x40014000-0x40014bff: APB2 */ + /* 0x40014c00-0x4001ffff: Reserved */ +#define STM32_AHB1_BASE 0x40020000 /* 0x40020000-0x400223ff: APB1 */ + /* 0x40022400-0x40022fff: Reserved */ + /* 0x40023000-0x400233ff: CRC */ + /* 0x40023400-0x400237ff: Reserved */ + /* 0x40023800-0x40023bff: Reset and Clock control RCC */ + /* 0x40023c00-0x400293ff: AHB1 (?) */ + /* 0x40029400-0x4fffffff: Reserved (?) */ +#define STM32_AHB2_BASE 0x50000000 /* 0x50000000-0x5003ffff: AHB2 */ + /* 0x50040000-0x5004ffff: Reserved */ + /* 0x50050000-0x500503ff: AHB2 */ + /* 0x50050400-0x500607ff: Reserved */ + /* 0x50060800-0x50060bff: AHB2 */ + /* 0x50060c00-0x5fffffff: Reserved */ + +/* FSMC Base Addresses ******************************************************/ + +#define STM32_AHB3_BASE 0x60000000 /* 0x60000000-0xa0000fff: AHB3 */ + +/* APB1 Base Addresses ******************************************************/ + +#define STM32_TIM2_BASE 0x40000000 /* 0x40000000-0x400003ff: TIM2 timer */ +#define STM32_TIM3_BASE 0x40000400 /* 0x40000400-0x400007ff: TIM3 timer */ +#define STM32_TIM4_BASE 0x40000800 /* 0x40000800-0x40000bff: TIM4 timer */ +#define STM32_TIM5_BASE 0x40000c00 /* 0x40000c00-0x40000fff: TIM5 timer */ +#define STM32_TIM6_BASE 0x40001000 /* 0x40001000-0x400013ff: TIM6 timer */ +#define STM32_TIM7_BASE 0x40001400 /* 0x40001400-0x400017ff: TIM7 timer */ +#define STM32_TIM12_BASE 0x40001800 /* 0x40001800-0x40001bff: TIM12 timer */ +#define STM32_TIM13_BASE 0x40001c00 /* 0x40001c00-0x40001fff: TIM13 timer */ +#define STM32_TIM14_BASE 0x40002000 /* 0x40002000-0x400023ff: TIM14 timer */ +#define STM32_RTC_BASE 0x40002800 /* 0x40002800-0x40002bff: RTC & BKP registers */ +#define STM32_WWDG_BASE 0x40002c00 /* 0x40002c00-0x40002fff: Window watchdog (WWDG) */ +#define STM32_IWDG_BASE 0x40003000 /* 0x40003000-0x400033ff: Independent watchdog (IWDG) */ +#define STM32_I2S2EXT_BASE 0x40003400 /* 0x40003400-0x400037ff: I2S2ext */ +#define STM32_SPI2_BASE 0x40003800 /* 0x40003800-0x40003bff: SPI2/I2S2 */ +#define STM32_I2S2_BASE 0x40003800 +#define STM32_SPI3_BASE 0x40003c00 /* 0x40003c00-0x40003fff: SPI3/I2S3 */ +#define STM32_I2S3_BASE 0x40003c00 +#define STM32_I2S3EXT_BASE 0x40004000 /* 0x40003400-0x400043ff: I2S3ext */ +#define STM32_USART2_BASE 0x40004400 /* 0x40004400-0x400047ff: USART2 */ +#define STM32_USART3_BASE 0x40004800 /* 0x40004800-0x40004bff: USART3 */ +#define STM32_UART4_BASE 0x40004c00 /* 0x40004c00-0x40004fff: UART4 */ +#define STM32_UART5_BASE 0x40005000 /* 0x40005000-0x400053ff: UART5 */ +#define STM32_I2C1_BASE 0x40005400 /* 0x40005400-0x400057ff: I2C1 */ +#define STM32_I2C2_BASE 0x40005800 /* 0x40005800-0x40005Bff: I2C2 */ +#define STM32_I2C3_BASE 0x40005c00 /* 0x40005c00-0x40005fff: I2C3 */ +#define STM32_CAN1_BASE 0x40006400 /* 0x40006400-0x400067ff: bxCAN1 */ +#define STM32_CAN2_BASE 0x40006800 /* 0x40006800-0x40006bff: bxCAN2 */ +#define STM32_PWR_BASE 0x40007000 /* 0x40007000-0x400073ff: Power control PWR */ +#define STM32_DAC1_BASE 0x40007400 /* 0x40007400-0x400077ff: DAC1 */ +#define STM32_UART7_BASE 0x40007800 /* 0x40007800-0x40007bff: UART7 */ +#define STM32_UART8_BASE 0x40007c00 /* 0x40007c00-0x40007fff: UART8 */ + +/* APB2 Base Addresses ******************************************************/ + +#define STM32_TIM1_BASE 0x40010000 /* 0x40010000-0x400103ff: TIM1 timer */ +#define STM32_TIM8_BASE 0x40010400 /* 0x40010400-0x400107ff: TIM8 timer */ +#define STM32_USART1_BASE 0x40011000 /* 0x40011000-0x400113ff: USART1 */ +#define STM32_USART6_BASE 0x40011400 /* 0x40011400-0x400117ff: USART6 */ +#define STM32_ADC_BASE 0x40012000 /* 0x40012000-0x400123ff: ADC1-3 */ +#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 */ +#define STM32_SAI1_BASE 0x40015800 /* 0x40015800-0x40015Bff: SAI1 */ +#define STM32_LTDC_BASE 0x40016800 /* 0x40016800-0x40016Bff: LTDC (LCD-TFT) */ + +/* AHB1 Base Addresses ******************************************************/ + +#define STM32_GPIOA_BASE 0x40020000 /* 0x40020000-0x400203ff: GPIO Port A */ +#define STM32_GPIOB_BASE 0x40020400 /* 0x40020400-0x400207ff: GPIO Port B */ +#define STM32_GPIOC_BASE 0x40020800 /* 0x40020800-0x40020bff: GPIO Port C */ +#define STM32_GPIOD_BASE 0X40020C00 /* 0x40020c00-0x40020fff: GPIO Port D */ +#define STM32_GPIOE_BASE 0x40021000 /* 0x40021000-0x400213ff: GPIO Port E */ +#define STM32_GPIOF_BASE 0x40021400 /* 0x40021400-0x400217ff: GPIO Port F */ +#define STM32_GPIOG_BASE 0x40021800 /* 0x40021800-0x40021bff: GPIO Port G */ +#define STM32_GPIOH_BASE 0x40021C00 /* 0x40021C00-0x40021fff: GPIO Port H */ +#define STM32_GPIOI_BASE 0x40022000 /* 0x40022000-0x400223ff: GPIO Port I */ +#define STM32_GPIOJ_BASE 0x40022400 /* 0x40022400-0x400227ff: GPIO Port J */ +#define STM32_GPIOK_BASE 0x40022800 /* 0x40022800-0x40022Bff: GPIO Port K */ +#define STM32_CRC_BASE 0x40023000 /* 0x40023000-0x400233ff: CRC */ +#define STM32_RCC_BASE 0x40023800 /* 0x40023800-0x40023bff: Reset and Clock control RCC */ +#define STM32_FLASHIF_BASE 0x40023c00 /* 0x40023c00-0x40023fff: Flash memory interface */ +#define STM32_BKPSRAM_BASE 0x40024000 /* 0x40024000-0x40024fff: Backup SRAM (BKPSRAM) */ +#define STM32_DMA1_BASE 0x40026000 /* 0x40026000-0x400263ff: DMA1 */ +#define STM32_DMA2_BASE 0x40026400 /* 0x40026400-0x400267ff: DMA2 */ +#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000-0x400283ff: Ethernet MAC */ + /* 0x40028400-0x400287ff: Ethernet MAC */ + /* 0x40028800-0x40028bff: Ethernet MAC */ + /* 0x40028c00-0x40028fff: Ethernet MAC */ + /* 0x40029000-0x400293ff: Ethernet MAC */ +#define STM32_DMA2D_BASE 0x4002B000 /* 0x4002B000-0x4002BBFF: DMA2D */ +#define STM32_OTGHS_BASE 0x40040000 /* 0x40040000-0x4007ffff: USB OTG HS */ +#define STM32_PERIPHBB_BASE 0x42000000 /* Peripheral bit-band region */ + +/* AHB2 Base Addresses ******************************************************/ + +#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000-0x5003ffff: USB OTG FS */ +#define STM32_DCMI_BASE 0x50050000 /* 0x50050000-0x500503ff: DCMI */ +#define STM32_CRYP_BASE 0x50060000 /* 0x50060000-0x500603ff: CRYP */ +#define STM32_HASH_BASE 0x50060400 /* 0x50060400-0x500607ff: HASH */ +#define STM32_RNG_BASE 0x50060800 /* 0x50060800-0x50060bff: RNG */ + +/* Cortex-M4 Base Addresses *************************************************/ + +/* Other registers -- see armv7-m/nvic.h for standard Cortex-M3 registers in + * this address range + */ + +#define STM32_SCS_BASE 0xe000e000 +#define STM32_DEBUGMCU_BASE 0xe0042000 + +#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32F40XXX_MEMORYMAP_H */ diff --git a/arch/arm/src/stm32/hardware/stm32f427ax_pinmap.h b/arch/arm/src/stm32/hardware/stm32f427ax_pinmap.h new file mode 100644 index 00000000000..fe333b017e8 --- /dev/null +++ b/arch/arm/src/stm32/hardware/stm32f427ax_pinmap.h @@ -0,0 +1,947 @@ +/**************************************************************************** + * arch/arm/src/stm32/hardware/stm32f427xx_pinmap.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_PINMAP_H +#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_PINMAP_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "stm32_gpio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Alternate Pin Functions. + * All members of the STM32F427Ax family share the same pin multiplexing + * (although they may differ in the pins physically available). + * + * Alternative pin selections are provided with a numeric suffix like _1, _2, + * etc. Drivers, however, will use the pin selection without the numeric + * suffix. Additional definitions are required in the board.h file. For + * example, if CAN1_RX connects via PA11 on some board, then the following + * definitions should appear in the board.h header file for that board: + * + * #define GPIO_CAN1_RX GPIO_CAN1_RX_1 + * + * The driver will then automatically configure PA11 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as + * frequency, open-drain/push-pull, and pull-up/down! + * Just the basics are defined for most pins in this file. + */ + +/* ADC */ + +#define GPIO_ADC1_IN0_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC1_IN1_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC1_IN2_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC1_IN3_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC1_IN4_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC1_IN5_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC1_IN6_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC1_IN7_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC1_IN8_0 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC1_IN9_0 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC1_IN10_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC1_IN11_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC1_IN12_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC1_IN13_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC1_IN14_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC1_IN15_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) + +#define GPIO_ADC2_IN0_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC2_IN1_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC2_IN2_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC2_IN3_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC2_IN4_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC2_IN5_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC2_IN6_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC2_IN7_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC2_IN8_0 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC2_IN9_0 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC2_IN10_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC2_IN11_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC2_IN12_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC2_IN13_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC2_IN14_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC2_IN15_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) + +#define GPIO_ADC3_IN0_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC3_IN1_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC3_IN2_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC3_IN3_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC3_IN4_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN6) +#define GPIO_ADC3_IN5_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN7) +#define GPIO_ADC3_IN6_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN8) +#define GPIO_ADC3_IN7_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN9) +#define GPIO_ADC3_IN8_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN10) +#define GPIO_ADC3_IN9_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN3) +#define GPIO_ADC3_IN10_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC3_IN11_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC3_IN12_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC3_IN13_0 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC3_IN14_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN4) +#define GPIO_ADC3_IN15_0 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN5) + +/* CAN */ + +#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_CAN1_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_CAN1_RX_3 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN0) +#define GPIO_CAN1_RX_4 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN9) +#define GPIO_CAN1_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12) +#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN1) +#define GPIO_CAN1_TX_4 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN13) +#define GPIO_CAN1_TX_5 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN1) + +#define GPIO_CAN2_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +#define GPIO_CAN2_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +#define GPIO_CAN2_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +#define GPIO_CAN2_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) + +/* DAC - "Once the DAC channelx is enabled, the corresponding GPIO pin + * (PA4 or PA5) is automatically connected to the analog converter output + * (DAC_OUTx). In order to avoid parasitic consumption, the PA4 or PA5 pin + * should first be configured to analog (AIN)". + */ + +#define GPIO_DAC1_OUT1_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC1_OUT2_0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) + +/* Digital Camera Interface (DCMI) */ + +#define GPIO_DCMI_D0_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN9) +#define GPIO_DCMI_D0_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN6) +#define GPIO_DCMI_D0_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN9) +#define GPIO_DCMI_D1_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN10) +#define GPIO_DCMI_D1_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN7) +#define GPIO_DCMI_D1_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN10) +#define GPIO_DCMI_D2_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN8) +#define GPIO_DCMI_D2_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN0) +#define GPIO_DCMI_D2_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN11) +#define GPIO_DCMI_D3_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN9) +#define GPIO_DCMI_D3_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN1) +#define GPIO_DCMI_D3_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN12) +#define GPIO_DCMI_D4_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN11) +#define GPIO_DCMI_D4_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN4) +#define GPIO_DCMI_D4_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN14) +#define GPIO_DCMI_D5_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN6) +#define GPIO_DCMI_D5_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN4) +#define GPIO_DCMI_D6_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN8) +#define GPIO_DCMI_D6_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN5) +#define GPIO_DCMI_D6_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN6) +#define GPIO_DCMI_D7_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN9) +#define GPIO_DCMI_D7_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN6) +#define GPIO_DCMI_D7_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN7) +#define GPIO_DCMI_D8_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN10) +#define GPIO_DCMI_D8_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN1) +#define GPIO_DCMI_D9_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN12) +#define GPIO_DCMI_D9_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN2) +#define GPIO_DCMI_D10_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN5) +#define GPIO_DCMI_D10_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN3) +#define GPIO_DCMI_D11_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN2) +#define GPIO_DCMI_D11_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN15) +#define GPIO_DCMI_D13_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN15) +#define GPIO_DCMI_D13_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN0) +#define GPIO_DCMI_HSYNC_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DCMI_HSYNC_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN8) +#define GPIO_DCMI_PIXCLK_0 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN6) +#define GPIO_DCMI_VSYNC_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN7) +#define GPIO_DCMI_VSYNC_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN5) + +# define GPIO_DCMI_D2_4 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN10) +# define GPIO_DCMI_D3_4 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN11) +# define GPIO_DCMI_D5_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN3) +# define GPIO_DCMI_D8_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN6) +# define GPIO_DCMI_D9_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN7) +# define GPIO_DCMI_D10_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN6) +# define GPIO_DCMI_D11_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN10) +# define GPIO_DCMI_D12_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN11) +# define GPIO_DCMI_D12_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN6) +# define GPIO_DCMI_D13_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN7) +# define GPIO_DCMI_VSYNC_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN9) + + +/* Clocks outputs */ + +#define GPIO_MCO1_0 (GPIO_ALT|GPIO_AF0|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +#define GPIO_MCO2_0 (GPIO_ALT|GPIO_AF0|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) + +/* Ethernet MAC */ + +# define GPIO_ETH_MDC_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN1) +# define GPIO_ETH_MDIO_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +# define GPIO_ETH_MII_COL_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +# define GPIO_ETH_MII_COL_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN3) +# define GPIO_ETH_MII_CRS_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +# define GPIO_ETH_MII_CRS_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN2) +# define GPIO_ETH_MII_RXD0_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) +# define GPIO_ETH_MII_RXD1_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) +# define GPIO_ETH_MII_RXD2_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +# define GPIO_ETH_MII_RXD2_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6) +# define GPIO_ETH_MII_RXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +# define GPIO_ETH_MII_RXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN7) +# define GPIO_ETH_MII_RX_CLK_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +# define GPIO_ETH_MII_RX_DV_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +# define GPIO_ETH_MII_RX_ER_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +# define GPIO_ETH_MII_RX_ER_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN10) +# define GPIO_ETH_MII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +# define GPIO_ETH_MII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13) +# define GPIO_ETH_MII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +# define GPIO_ETH_MII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14) +# define GPIO_ETH_MII_TXD2_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN2) +# define GPIO_ETH_MII_TXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +# define GPIO_ETH_MII_TXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN2) +# define GPIO_ETH_MII_TX_CLK_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN3) +# define GPIO_ETH_MII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +# define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) +# define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +# define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8) +# define GPIO_ETH_RMII_CRS_DV_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +# define GPIO_ETH_RMII_REF_CLK_0 (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN1) +# define GPIO_ETH_RMII_RXD0_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) +# define GPIO_ETH_RMII_RXD1_0 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) +# define GPIO_ETH_RMII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +# define GPIO_ETH_RMII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13) +# define GPIO_ETH_RMII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +# define GPIO_ETH_RMII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14) +# define GPIO_ETH_RMII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +# define GPIO_ETH_RMII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) + +/* Flexible Memory Controller (FMC) */ + +#define GPIO_FMC_A0_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN0) +#define GPIO_FMC_A1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN1) +#define GPIO_FMC_A2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN2) +#define GPIO_FMC_A3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN3) +#define GPIO_FMC_A4_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN4) +#define GPIO_FMC_A5_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN5) +#define GPIO_FMC_A6_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN12) +#define GPIO_FMC_A7_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN13) +#define GPIO_FMC_A8_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN14) +#define GPIO_FMC_A9_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN15) +#define GPIO_FMC_A10_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN0) +#define GPIO_FMC_A11_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN1) +#define GPIO_FMC_A12_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN2) +#define GPIO_FMC_A13_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN3) +#define GPIO_FMC_A14_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN4) +#define GPIO_FMC_A15_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN5) +#define GPIO_FMC_A16_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN11) +#define GPIO_FMC_A17_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN12) +#define GPIO_FMC_A18_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN13) +#define GPIO_FMC_A19_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN3) +#define GPIO_FMC_A20_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN4) +#define GPIO_FMC_A21_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN5) +#define GPIO_FMC_A22_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN6) +#define GPIO_FMC_A23_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN2) +#define GPIO_FMC_A24_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN13) +#define GPIO_FMC_A25_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN14) +#define GPIO_FMC_NBL1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN1) +#define GPIO_FMC_CLK_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN3) +#define GPIO_FMC_D0_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN14) +#define GPIO_FMC_D1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN15) +#define GPIO_FMC_D2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN0) +#define GPIO_FMC_D3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN1) +#define GPIO_FMC_D4_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN7) +#define GPIO_FMC_D5_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN8) +#define GPIO_FMC_D6_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN9) +#define GPIO_FMC_D7_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN10) +#define GPIO_FMC_D8_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN11) +#define GPIO_FMC_D9_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN12) +#define GPIO_FMC_D10_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN13) +#define GPIO_FMC_D11_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN14) +#define GPIO_FMC_D12_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN15) +#define GPIO_FMC_D13_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN8) +#define GPIO_FMC_D14_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN9) +#define GPIO_FMC_D15_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN10) +#define GPIO_FMC_NBL0_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN0) +#define GPIO_FMC_NE1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN7) +#define GPIO_FMC_NE2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9) +#define GPIO_FMC_NE3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN10) +#define GPIO_FMC_NE4_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN12) +#define GPIO_FMC_NL_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN7) +#define GPIO_FMC_NOE_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN4) +#define GPIO_FMC_NWAIT_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN6) +#define GPIO_FMC_NWE_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN5) + +#define GPIO_FMC_INT3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN7) +#define GPIO_FMC_NCE3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9) + +# define GPIO_FMC_CD_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN9) +# define GPIO_FMC_INT2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN6) +# define GPIO_FMC_INTR_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN10) +# define GPIO_FMC_NCE2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN7) +# define GPIO_FMC_NCE4_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN10) +# define GPIO_FMC_NCE4_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN11) +# define GPIO_FMC_NIORD_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN6) +# define GPIO_FMC_NIOWR_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN8) +# define GPIO_FMC_SDCKE0_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN2) +# define GPIO_FMC_SDCKE0_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN3) +# define GPIO_FMC_SDNE0_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN3) +# define GPIO_FMC_SDNE0_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN2) +# define GPIO_FMC_SDNWE_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN0) +# define GPIO_FMC_SDNWE_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN5) +# define GPIO_FMC_SDNRAS_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN11) +# define GPIO_FMC_SDCLK_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN8) +# define GPIO_FMC_SDNCAS_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN15) +# define GPIO_FMC_BA0_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN4) +# define GPIO_FMC_BA1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN5) +# define GPIO_FMC_NREG_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN7) + +# define GPIO_FMC_D16_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN8) +# define GPIO_FMC_D17_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN9) +# define GPIO_FMC_D18_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN10) +# define GPIO_FMC_D19_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN11) +# define GPIO_FMC_D20_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN12) +# define GPIO_FMC_D21_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN13) +# define GPIO_FMC_D22_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN14) +# define GPIO_FMC_D23_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN15) +# define GPIO_FMC_D24_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN0) +# define GPIO_FMC_D25_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN1) +# define GPIO_FMC_D26_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN2) +# define GPIO_FMC_D27_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN3) +# define GPIO_FMC_D28_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN6) +# define GPIO_FMC_D29_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN7) +# define GPIO_FMC_D30_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN9) +# define GPIO_FMC_D31_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN10) +# define GPIO_FMC_NBL2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN4) +# define GPIO_FMC_NBL3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTI|GPIO_PIN5) +# define GPIO_FMC_SDCKE0_3 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN2) +# define GPIO_FMC_SDCKE1_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN5) +# define GPIO_FMC_SDCKE1_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN7) +# define GPIO_FMC_SDNE0_3 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN3) +# define GPIO_FMC_SDNE1_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN6) +# define GPIO_FMC_SDNE1_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN6) +# define GPIO_FMC_SDNWE_3 (GPIO_ALT|GPIO_AF12|GPIO_PORTH|GPIO_PIN5) + +/* Flexible Static Memory Controller (FSMC) */ + +#define GPIO_FSMC_A0_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN0) +#define GPIO_FSMC_A1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN1) +#define GPIO_FSMC_A2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN2) +#define GPIO_FSMC_A3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN3) +#define GPIO_FSMC_A4_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN4) +#define GPIO_FSMC_A5_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN5) +#define GPIO_FSMC_A6_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN12) +#define GPIO_FSMC_A7_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN13) +#define GPIO_FSMC_A8_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN14) +#define GPIO_FSMC_A9_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN15) +#define GPIO_FSMC_A10_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN0) +#define GPIO_FSMC_A11_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN1) +#define GPIO_FSMC_A12_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN2) +#define GPIO_FSMC_A13_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN3) +#define GPIO_FSMC_A14_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN4) +#define GPIO_FSMC_A15_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN5) +#define GPIO_FSMC_A16_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN11) +#define GPIO_FSMC_A17_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN12) +#define GPIO_FSMC_A18_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN13) +#define GPIO_FSMC_A19_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN3) +#define GPIO_FSMC_A20_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN4) +#define GPIO_FSMC_A21_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN5) +#define GPIO_FSMC_A22_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN6) +#define GPIO_FSMC_A23_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN2) +#define GPIO_FSMC_A24_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN13) +#define GPIO_FSMC_A25_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN14) +#define GPIO_FSMC_NBL1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN1) +#define GPIO_FSMC_CLK_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN3) +#define GPIO_FSMC_D0_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN14) +#define GPIO_FSMC_D1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN15) +#define GPIO_FSMC_D2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN0) +#define GPIO_FSMC_D3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN1) +#define GPIO_FSMC_D4_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN7) +#define GPIO_FSMC_D5_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN8) +#define GPIO_FSMC_D6_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN9) +#define GPIO_FSMC_D7_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN10) +#define GPIO_FSMC_D8_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN11) +#define GPIO_FSMC_D9_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN12) +#define GPIO_FSMC_D10_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN13) +#define GPIO_FSMC_D11_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN14) +#define GPIO_FSMC_D12_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN15) +#define GPIO_FSMC_D13_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN8) +#define GPIO_FSMC_D14_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN9) +#define GPIO_FSMC_D15_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN10) +#define GPIO_FSMC_NBL0_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN0) +#define GPIO_FSMC_NE1_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN7) +#define GPIO_FSMC_NE2_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9) +#define GPIO_FSMC_NE3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN10) +#define GPIO_FSMC_NE4_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN12) +#define GPIO_FSMC_NL_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN7) +#define GPIO_FSMC_NOE_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN4) +#define GPIO_FSMC_NWAIT_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN6) +#define GPIO_FSMC_NWE_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN5) + +#define GPIO_FSMC_INT3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN7) +#define GPIO_FSMC_NCE3_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9) + + +/* I2C */ + +#define GPIO_I2C1_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN9) +#define GPIO_I2C1_SMBA_0 (GPIO_ALT|GPIO_AF4|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) + +#define GPIO_I2C2_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTF|GPIO_PIN1) +#define GPIO_I2C2_SCL_3 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN4) +#define GPIO_I2C2_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTF|GPIO_PIN0) +#define GPIO_I2C2_SDA_3 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN5) +#define GPIO_I2C2_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +#define GPIO_I2C2_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN2) +#define GPIO_I2C2_SMBA_3 (GPIO_ALT|GPIO_AF4|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6) + +#define GPIO_I2C3_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN8) +#define GPIO_I2C3_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN7) +#define GPIO_I2C3_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTC|GPIO_PIN9) +#define GPIO_I2C3_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN8) + +#define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) + + +/* I2S */ + +#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) +#define GPIO_I2S2_SD_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN15) +#define GPIO_I2S2_SD_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN3) +#define GPIO_I2S2_SD_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN3) +#define GPIO_I2S2_WS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN12) +#define GPIO_I2S2_WS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN9) +#define GPIO_I2S2_WS_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN0) + +# define GPIO_I2S2_CK_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTD|GPIO_PIN3) +# define GPIO_I2S2_SD_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN1) + + +# define GPIO_I2S2_MCK_0 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN6) + + +#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) +#define GPIO_I2S2EXT_SD_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTI|GPIO_PIN2) + +#define GPIO_I2S3_CK_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN3) +#define GPIO_I2S3_CK_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN10) +#define GPIO_I2S3_MCK_0 (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) +#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) + +# define GPIO_I2S3_SD_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTD|GPIO_PIN6) + + +# define GPIO_I2S3EXT_SD_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN4) + +#define GPIO_I2S3EXT_SD_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN11) + +#define GPIO_I2S_CKIN_0 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN9) + +/* JTAG */ + +#define GPIO_JTCK_SWCLK_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN14) +#define GPIO_JTDI_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) +#define GPIO_JTDO_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) +#define GPIO_JTMS_SWDIO_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13) +#define GPIO_JTRST_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) + +/* OTG FS/HS (VBUS PA9 is not an alternate configuration) */ + +#define GPIO_OTGFS_DM_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_OTGFS_DP_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12) +#define GPIO_OTGFS_ID_0 (GPIO_ALT|GPIO_PULLUP|GPIO_AF10|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN10) +#define GPIO_OTGFS_SOF_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) + +#define GPIO_OTGHSFS_DM_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_OTGHSFS_DP_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_OTGHSFS_ID_0 (GPIO_ALT|GPIO_PULLUP|GPIO_AF12|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN12) + +#define GPIO_OTGHS_DM_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_OTGHS_DP_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_OTGHS_ID_0 (GPIO_ALT|GPIO_PULLUP|GPIO_AF12|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN12) +#define GPIO_OTGHS_SOF_0 (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN4) + +#define GPIO_OTGHS_ULPI_CK_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN5) +#define GPIO_OTGHS_ULPI_D0_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN3) +#define GPIO_OTGHS_ULPI_D1_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN0) +#define GPIO_OTGHS_ULPI_D2_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN1) +#define GPIO_OTGHS_ULPI_D3_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN10) +#define GPIO_OTGHS_ULPI_D5_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN12) +#define GPIO_OTGHS_ULPI_D6_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN13) +#define GPIO_OTGHS_ULPI_D7_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN5) +#define GPIO_OTGHS_ULPI_DIR_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN2) +#define GPIO_OTGHS_ULPI_DIR_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTI|GPIO_PIN11) +#define GPIO_OTGHS_ULPI_NXT_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN3) +#define GPIO_OTGHS_ULPI_NXT_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTH|GPIO_PIN4) +#define GPIO_OTGHS_ULPI_STP_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN0) + +# define GPIO_OTGHS_ULPI_D4_0 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN11) + +/* RTC */ + +#define GPIO_RTC_50HZ_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTC|GPIO_PIN15) + +/* SDIO + * + * Note if the board uses GPIO_SPEED_50MHz I/O, for using the SDIO that you + * must enable I/O Compensation via the configuration + * option CONFIG_STM32_SYSCFG_IOCOMPENSATION=y. + */ + +#define GPIO_SDIO_CMD_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN2) +#define GPIO_SDIO_D0_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_SDIO_D3_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11) +#define GPIO_SDIO_D4_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_SDIO_D5_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SDIO_D6_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_SDIO_D7_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) + + +# define GPIO_SDIO_CK_0 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN12) +# define GPIO_SDIO_D1_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +# define GPIO_SDIO_D2_0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) + +/* SPI */ + +#define GPIO_SPI1_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN6) +#define GPIO_SPI1_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI1_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN7) +#define GPIO_SPI1_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN5) +#define GPIO_SPI1_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI1_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI1_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN5) +#define GPIO_SPI1_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN3) + +#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_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) +#define GPIO_SPI2_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SPI2_NSS_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN0) +#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) + +# define GPIO_SPI2_SCK_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTD|GPIO_PIN3) + + +#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) +#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_SPI3_MOSI_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTD|GPIO_PIN6) + + +# 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_0 (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN12) +# define GPIO_SPI6_MOSI_0 (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN14) +# define GPIO_SPI6_NSS_0 (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN8) +# define GPIO_SPI6_SCK_0 (GPIO_ALT|GPIO_AF5|GPIO_PORTG|GPIO_PIN13) + +/* Timers */ + +#define GPIO_TIM1_BKIN_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM1_BKIN_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN12) +#define GPIO_TIM1_BKIN_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN15) +#define GPIO_TIM1_CH1N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM1_CH1N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN13) +#define GPIO_TIM1_CH1N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN8) +#define GPIO_TIM1_CH1IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH1OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH2N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM1_CH2N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM1_CH2N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN10) +#define GPIO_TIM1_CH2IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH2OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH3N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM1_CH3N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM1_CH3N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN12) +#define GPIO_TIM1_CH3IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH3OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH4IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_CH4OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_ETR_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN12) +#define GPIO_TIM1_ETR_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN7) + +#define GPIO_TIM2_CH1IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH1IN_3 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH1OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH1OUT_3 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH2IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH2OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH3IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH3OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH4IN_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4IN_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_CH4OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_ETR_1 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_ETR_2 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_ETR_3 (GPIO_ALT|GPIO_AF1|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN5) + +#define GPIO_TIM3_CH1IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1IN_3 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH2IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2IN_3 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH3IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH4IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_ETR_0 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN2) + +#define GPIO_TIM4_CH1IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM4_CH1IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN12) +#define GPIO_TIM4_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM4_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN12) +#define GPIO_TIM4_CH2IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM4_CH2IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN13) +#define GPIO_TIM4_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM4_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13) +#define GPIO_TIM4_CH3IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM4_CH3IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN14) +#define GPIO_TIM4_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM4_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN14) +#define GPIO_TIM4_CH4IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM4_CH4IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) +#define GPIO_TIM4_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM4_CH4OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN15) +#define GPIO_TIM4_ETR_0 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN0) + +#define GPIO_TIM5_CH1IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH1IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN10) +#define GPIO_TIM5_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN10) +#define GPIO_TIM5_CH2IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH2IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN11) +#define GPIO_TIM5_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN11) +#define GPIO_TIM5_CH3IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH3IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN12) +#define GPIO_TIM5_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN12) +#define GPIO_TIM5_CH4IN_1 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM5_CH4IN_2 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN0) +#define GPIO_TIM5_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM5_CH4OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN0) +#define GPIO_TIM5_ETR_0 (GPIO_ALT|GPIO_AF2|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN10) + +#define GPIO_TIM8_BKIN_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM8_BKIN_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN4) +#define GPIO_TIM8_CH1N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM8_CH1N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM8_CH1N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN13) +#define GPIO_TIM8_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM8_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN5) +#define GPIO_TIM8_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM8_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN5) +#define GPIO_TIM8_CH2N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM8_CH2N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM8_CH2N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN14) +#define GPIO_TIM8_CH2IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM8_CH2IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN6) +#define GPIO_TIM8_CH2OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM8_CH2OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN6) +#define GPIO_TIM8_CH3N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM8_CH3N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM8_CH3N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN15) +#define GPIO_TIM8_CH3IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM8_CH3IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN7) +#define GPIO_TIM8_CH3OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM8_CH3OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN7) +#define GPIO_TIM8_CH4IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_CH4IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN2) +#define GPIO_TIM8_CH4OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_CH4OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN2) +#define GPIO_TIM8_ETR_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM8_ETR_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN3) + +#define GPIO_TIM9_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM9_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM9_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM9_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM9_CH2IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM9_CH2IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN6) +#define GPIO_TIM9_CH2OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM9_CH2OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN6) + +#define GPIO_TIM10_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM10_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN6) +#define GPIO_TIM10_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM10_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN6) + +#define GPIO_TIM11_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM11_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN7) +#define GPIO_TIM11_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM11_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN7) + +#define GPIO_TIM12_CH1IN_1 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN6) +#define GPIO_TIM12_CH1IN_2 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM12_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6) +#define GPIO_TIM12_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM12_CH2IN_1 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM12_CH2IN_2 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN9) +#define GPIO_TIM12_CH2OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM12_CH2OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) + +#define GPIO_TIM13_CH1IN_1 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM13_CH1IN_2 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN8) +#define GPIO_TIM13_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM13_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN8) + +#define GPIO_TIM14_CH1IN_1 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM14_CH1IN_2 (GPIO_ALT|GPIO_AF9|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN9) +#define GPIO_TIM14_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM14_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN9) + + +/* Trace */ + +#define GPIO_TRACECLK_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +#define GPIO_TRACESWO_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + + +# define GPIO_TRACED0_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) + + + + +# define GPIO_TRACED2_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3_0 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) + + +/* UARTs/USARTs */ + +#define GPIO_USART1_CK_0 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN8) +#define GPIO_USART1_CTS_0 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN11) +#define GPIO_USART1_RTS_0 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN12) +#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10) +#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7) + +#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) + +#define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN4) +#define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN7) +#define GPIO_USART2_CTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN0) +#define GPIO_USART2_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN3) +#define GPIO_USART2_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN1) +#define GPIO_USART2_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN4) +#define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN6) +#define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5) + +#define GPIO_USART3_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN12) +#define GPIO_USART3_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTC|GPIO_PIN12) +#define GPIO_USART3_CK_3 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN10) +#define GPIO_USART3_CTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN13) +#define GPIO_USART3_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN11) +#define GPIO_USART3_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN14) +#define GPIO_USART3_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN12) +#define GPIO_USART3_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +#define GPIO_USART3_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11) +#define GPIO_USART3_RX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN9) + + +#define GPIO_USART3_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +#define GPIO_USART3_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) +#define GPIO_USART3_TX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN8) + +#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11) +#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) + +#define GPIO_UART5_RX_0 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN2) +#define GPIO_UART5_TX_0 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN12) + +#define GPIO_USART6_CK_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN8) +#define GPIO_USART6_CK_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN7) +#define GPIO_USART6_CTS_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN13) +#define GPIO_USART6_CTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN15) +#define GPIO_USART6_RTS_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN12) +#define GPIO_USART6_RTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN8) +#define GPIO_USART6_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_USART6_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN9) +#define GPIO_USART6_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_USART6_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14) + +# define GPIO_UART7_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN7) +# define GPIO_UART7_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN6) +# define GPIO_UART7_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN8) +# define GPIO_UART7_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN7) + +# define GPIO_UART8_RX_0 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN0) +# define GPIO_UART8_TX_0 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN1) + +/* LCD-TFT Display Controller (LTDC) */ + +# define GPIO_LTDC_R0_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN2) +# define GPIO_LTDC_R0_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN15) +# define GPIO_LTDC_R1_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN3) +# define GPIO_LTDC_R1_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN0) +# define GPIO_LTDC_R2_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) +# define GPIO_LTDC_R2_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN8) +# define GPIO_LTDC_R2_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN1) +# define GPIO_LTDC_R3_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +# define GPIO_LTDC_R3_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) +# define GPIO_LTDC_R3_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN2) +# define GPIO_LTDC_R4_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +# define GPIO_LTDC_R4_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN10) +# define GPIO_LTDC_R4_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN3) +# define GPIO_LTDC_R5_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12) +# define GPIO_LTDC_R5_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN11) +# define GPIO_LTDC_R5_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN4) +# define GPIO_LTDC_R6_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +# define GPIO_LTDC_R6_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN12) +# define GPIO_LTDC_R6_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN5) +# define GPIO_LTDC_R6_4 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +# define GPIO_LTDC_R7_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN6) +# define GPIO_LTDC_R7_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN15) +# define GPIO_LTDC_R7_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN6) + +# define GPIO_LTDC_G0_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN5) +# define GPIO_LTDC_G0_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN7) +# define GPIO_LTDC_G1_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN6) +# define GPIO_LTDC_G1_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN8) +# define GPIO_LTDC_G2_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +# define GPIO_LTDC_G2_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN13) +# define GPIO_LTDC_G2_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN9) +# define GPIO_LTDC_G3_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN10) +# define GPIO_LTDC_G3_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN14) +# define GPIO_LTDC_G3_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN10) +# define GPIO_LTDC_G3_4 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) +# define GPIO_LTDC_G4_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +# define GPIO_LTDC_G4_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN15) +# define GPIO_LTDC_G4_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN11) +# define GPIO_LTDC_G5_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +# define GPIO_LTDC_G5_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN0) +# define GPIO_LTDC_G5_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN0) +# define GPIO_LTDC_G6_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +# define GPIO_LTDC_G6_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN1) +# define GPIO_LTDC_G6_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN1) +# define GPIO_LTDC_G7_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN3) +# define GPIO_LTDC_G7_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN2) +# define GPIO_LTDC_G7_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN2) + +# define GPIO_LTDC_B0_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN4) +# define GPIO_LTDC_B0_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN12) +# define GPIO_LTDC_B1_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN12) +# define GPIO_LTDC_B1_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN13) +# define GPIO_LTDC_B2_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN6) +# define GPIO_LTDC_B2_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN10) +# define GPIO_LTDC_B2_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN14) +# define GPIO_LTDC_B3_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) +# define GPIO_LTDC_B3_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN10) +# define GPIO_LTDC_B3_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN15) +# define GPIO_LTDC_B4_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN12) +# define GPIO_LTDC_B4_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN12) +# define GPIO_LTDC_B4_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN4) +# define GPIO_LTDC_B4_4 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN3) +# define GPIO_LTDC_B5_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +# define GPIO_LTDC_B5_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN5) +# define GPIO_LTDC_B5_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN4) +# define GPIO_LTDC_B6_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +# define GPIO_LTDC_B6_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN6) +# define GPIO_LTDC_B6_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN5) +# define GPIO_LTDC_B7_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +# define GPIO_LTDC_B7_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN7) +# define GPIO_LTDC_B7_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN6) + +# define GPIO_LTDC_VSYNC_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN4) +# define GPIO_LTDC_VSYNC_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN9) +# define GPIO_LTDC_VSYNC_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN13) +# define GPIO_LTDC_HSYNC_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +# define GPIO_LTDC_HSYNC_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN10) +# define GPIO_LTDC_HSYNC_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN12) +# define GPIO_LTDC_DE_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN10) +# define GPIO_LTDC_DE_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) +# define GPIO_LTDC_DE_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN7) +# define GPIO_LTDC_CLK_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN7) +# define GPIO_LTDC_CLK_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) +# define GPIO_LTDC_CLK_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN14) + +#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_PINMAP_H */ diff --git a/arch/arm/src/stm32/hardware/stm32f427ax_pinmap_legacy.h b/arch/arm/src/stm32/hardware/stm32f427ax_pinmap_legacy.h new file mode 100644 index 00000000000..edde1cc38f9 --- /dev/null +++ b/arch/arm/src/stm32/hardware/stm32f427ax_pinmap_legacy.h @@ -0,0 +1,949 @@ +/**************************************************************************** + * arch/arm/src/stm32/hardware/stm32f427xx_pinmap_legacy.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_PINMAP_LEGACY_H +#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_PINMAP_LEGACY_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "stm32_gpio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Alternate Pin Functions. + * All members of the STM32F427xx family share the same pin multiplexing + * (although they may differ in the pins physically available). + * + * Alternative pin selections are provided with a numeric suffix like _1, _2, + * etc. Drivers, however, will use the pin selection without the numeric + * suffix. Additional definitions are required in the board.h file. For + * example, if CAN1_RX connects via PA11 on some board, then the following + * definitions should appear in the board.h header file for that board: + * + * #define GPIO_CAN1_RX GPIO_CAN1_RX_1 + * + * The driver will then automatically configure PA11 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as + * frequency, open-drain/push-pull, and pull-up/down! + * Just the basics are defined for most pins in this file. + */ + +/* ADC */ + +#define GPIO_ADC1_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC1_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC1_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC1_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC1_IN4 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC1_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC1_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC1_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC1_IN8 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC1_IN9 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC1_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC1_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC1_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC1_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC1_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC1_IN15 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) + +#define GPIO_ADC2_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC2_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC2_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC2_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC2_IN4 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC2_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC2_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC2_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC2_IN8 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC2_IN9 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC2_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC2_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC2_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC2_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC2_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC2_IN15 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) + +#define GPIO_ADC3_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC3_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC3_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC3_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC3_IN4 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN6) +#define GPIO_ADC3_IN5 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN7) +#define GPIO_ADC3_IN6 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN8) +#define GPIO_ADC3_IN7 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN9) +#define GPIO_ADC3_IN8 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN10) +#define GPIO_ADC3_IN9 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN3) +#define GPIO_ADC3_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC3_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC3_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC3_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC3_IN14 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN4) +#define GPIO_ADC3_IN15 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN5) + +/* CAN */ + +#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_CAN1_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_CAN1_RX_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN0) +#define GPIO_CAN1_RX_4 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN9) +#define GPIO_CAN1_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12) +#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN1) +#define GPIO_CAN1_TX_4 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN13) +#define GPIO_CAN1_TX_5 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN1) + +#define GPIO_CAN2_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +#define GPIO_CAN2_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +#define GPIO_CAN2_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +#define GPIO_CAN2_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) + +/* DAC - "Once the DAC channelx is enabled, the corresponding GPIO pin + * (PA4 or PA5) is automatically connected to the analog converter output + * (DAC_OUTx). In order to avoid parasitic consumption, the PA4 or PA5 pin + * should first be configured to analog (AIN)". + */ + +#define GPIO_DAC1_OUT1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC1_OUT2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) + +/* Digital Camera Interface (DCMI) */ + +#define GPIO_DCMI_D0_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN9) +#define GPIO_DCMI_D0_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN6) +#define GPIO_DCMI_D0_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN9) +#define GPIO_DCMI_D1_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN10) +#define GPIO_DCMI_D1_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN7) +#define GPIO_DCMI_D1_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN10) +#define GPIO_DCMI_D2_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN8) +#define GPIO_DCMI_D2_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN0) +#define GPIO_DCMI_D2_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN11) +#define GPIO_DCMI_D3_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN9) +#define GPIO_DCMI_D3_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN1) +#define GPIO_DCMI_D3_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN12) +#define GPIO_DCMI_D4_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN11) +#define GPIO_DCMI_D4_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN4) +#define GPIO_DCMI_D4_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN14) +#define GPIO_DCMI_D5_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN6) +#define GPIO_DCMI_D5_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN4) +#define GPIO_DCMI_D6_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN8) +#define GPIO_DCMI_D6_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN5) +#define GPIO_DCMI_D6_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN6) +#define GPIO_DCMI_D7_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN9) +#define GPIO_DCMI_D7_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN6) +#define GPIO_DCMI_D7_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN7) +#define GPIO_DCMI_D8_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN10) +#define GPIO_DCMI_D8_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN1) +#define GPIO_DCMI_D9_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN12) +#define GPIO_DCMI_D9_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN2) +#define GPIO_DCMI_D10_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN5) +#define GPIO_DCMI_D10_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN3) +#define GPIO_DCMI_D11_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN2) +#define GPIO_DCMI_D11_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN15) +#define GPIO_DCMI_D13_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN15) +#define GPIO_DCMI_D13_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN0) +#define GPIO_DCMI_HSYNC_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DCMI_HSYNC_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN8) +#define GPIO_DCMI_PIXCLK (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN6) +#define GPIO_DCMI_VSYNC_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN7) +#define GPIO_DCMI_VSYNC_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN5) + +# define GPIO_DCMI_D2_4 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN10) +# define GPIO_DCMI_D3_4 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN11) +# define GPIO_DCMI_D5_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN3) +# define GPIO_DCMI_D8_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN6) +# define GPIO_DCMI_D9_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTH|GPIO_PIN7) +# define GPIO_DCMI_D10_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN6) +# define GPIO_DCMI_D11_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN10) +# define GPIO_DCMI_D12_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN11) +# define GPIO_DCMI_D12_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN6) +# define GPIO_DCMI_D13_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN7) +# define GPIO_DCMI_VSYNC_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN9) + + +/* Clocks outputs */ + +#define GPIO_MCO1 (GPIO_ALT|GPIO_AF0|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +#define GPIO_MCO2 (GPIO_ALT|GPIO_AF0|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) + +/* Ethernet MAC */ + +# define GPIO_ETH_MDC (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN1) +# define GPIO_ETH_MDIO (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +# define GPIO_ETH_MII_COL_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +# define GPIO_ETH_MII_COL_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN3) +# define GPIO_ETH_MII_CRS_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +# define GPIO_ETH_MII_CRS_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN2) +# define GPIO_ETH_MII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) +# define GPIO_ETH_MII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) +# define GPIO_ETH_MII_RXD2_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +# define GPIO_ETH_MII_RXD2_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6) +# define GPIO_ETH_MII_RXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +# define GPIO_ETH_MII_RXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN7) +# define GPIO_ETH_MII_RX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +# define GPIO_ETH_MII_RX_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +# define GPIO_ETH_MII_RX_ER_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +# define GPIO_ETH_MII_RX_ER_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN10) +# define GPIO_ETH_MII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +# define GPIO_ETH_MII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13) +# define GPIO_ETH_MII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +# define GPIO_ETH_MII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14) +# define GPIO_ETH_MII_TXD2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN2) +# define GPIO_ETH_MII_TXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +# define GPIO_ETH_MII_TXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN2) +# define GPIO_ETH_MII_TX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN3) +# define GPIO_ETH_MII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +# define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) +# define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +# define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8) +# define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +# define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN1) +# define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4) +# define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5) +# define GPIO_ETH_RMII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +# define GPIO_ETH_RMII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13) +# define GPIO_ETH_RMII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +# define GPIO_ETH_RMII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14) +# define GPIO_ETH_RMII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +# define GPIO_ETH_RMII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) + +/* Flexible Memory Controller (FMC) */ + +#define GPIO_FMC_A0 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN0) +#define GPIO_FMC_A1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN1) +#define GPIO_FMC_A2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN2) +#define GPIO_FMC_A3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN3) +#define GPIO_FMC_A4 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN4) +#define GPIO_FMC_A5 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN5) +#define GPIO_FMC_A6 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN12) +#define GPIO_FMC_A7 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN13) +#define GPIO_FMC_A8 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN14) +#define GPIO_FMC_A9 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN15) +#define GPIO_FMC_A10 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN0) +#define GPIO_FMC_A11 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN1) +#define GPIO_FMC_A12 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN2) +#define GPIO_FMC_A13 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN3) +#define GPIO_FMC_A14 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN4) +#define GPIO_FMC_A15 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN5) +#define GPIO_FMC_A16 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN11) +#define GPIO_FMC_A17 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN12) +#define GPIO_FMC_A18 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN13) +#define GPIO_FMC_A19 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN3) +#define GPIO_FMC_A20 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN4) +#define GPIO_FMC_A21 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN5) +#define GPIO_FMC_A22 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN6) +#define GPIO_FMC_A23 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN2) +#define GPIO_FMC_A24 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN13) +#define GPIO_FMC_A25 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN14) +#define GPIO_FMC_NBL1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN1) +#define GPIO_FMC_CLK (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN3) +#define GPIO_FMC_D0 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN14) +#define GPIO_FMC_D1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN15) +#define GPIO_FMC_D2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN0) +#define GPIO_FMC_D3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN1) +#define GPIO_FMC_D4 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN7) +#define GPIO_FMC_D5 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN8) +#define GPIO_FMC_D6 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN9) +#define GPIO_FMC_D7 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN10) +#define GPIO_FMC_D8 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN11) +#define GPIO_FMC_D9 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN12) +#define GPIO_FMC_D10 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN13) +#define GPIO_FMC_D11 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN14) +#define GPIO_FMC_D12 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN15) +#define GPIO_FMC_D13 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN8) +#define GPIO_FMC_D14 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN9) +#define GPIO_FMC_D15 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN10) +#define GPIO_FMC_NBL0 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN0) +#define GPIO_FMC_NE1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN7) +#define GPIO_FMC_NE2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN9) +#define GPIO_FMC_NE3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN10) +#define GPIO_FMC_NE4 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN12) +#define GPIO_FMC_NL (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTB|GPIO_PIN7) +#define GPIO_FMC_NOE (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN4) +#define GPIO_FMC_NWAIT (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN6) +#define GPIO_FMC_NWE (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN5) + +#define GPIO_FMC_INT3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN7) +#define GPIO_FMC_NCE3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN9) + + +# define GPIO_FMC_CD (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN9) +# define GPIO_FMC_INT2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN6) +# define GPIO_FMC_INTR (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN10) +# define GPIO_FMC_NCE2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN7) +# define GPIO_FMC_NCE4_1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN10) +# define GPIO_FMC_NCE4_2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN11) +# define GPIO_FMC_NIORD (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN6) +# define GPIO_FMC_NIOWR (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN8) +# define GPIO_FMC_SDCKE0_1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN2) +# define GPIO_FMC_SDCKE0_2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTC|GPIO_PIN3) +# define GPIO_FMC_SDNE0_1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN3) +# define GPIO_FMC_SDNE0_2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTC|GPIO_PIN2) +# define GPIO_FMC_SDNWE_1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTC|GPIO_PIN0) +# define GPIO_FMC_SDNWE_2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN5) +# define GPIO_FMC_SDNRAS (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN11) +# define GPIO_FMC_SDCLK (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN8) +# define GPIO_FMC_SDNCAS (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN15) +# define GPIO_FMC_BA0 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN4) +# define GPIO_FMC_BA1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN5) +# define GPIO_FMC_NREG (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN7) + + + +# define GPIO_FMC_D16 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN8) +# define GPIO_FMC_D17 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN9) +# define GPIO_FMC_D18 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN10) +# define GPIO_FMC_D19 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN11) +# define GPIO_FMC_D20 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN12) +# define GPIO_FMC_D21 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN13) +# define GPIO_FMC_D22 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN14) +# define GPIO_FMC_D23 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN15) +# define GPIO_FMC_D24 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN0) +# define GPIO_FMC_D25 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN1) +# define GPIO_FMC_D26 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN2) +# define GPIO_FMC_D27 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN3) +# define GPIO_FMC_D28 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN6) +# define GPIO_FMC_D29 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN7) +# define GPIO_FMC_D30 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN9) +# define GPIO_FMC_D31 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN10) +# define GPIO_FMC_NBL2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN4) +# define GPIO_FMC_NBL3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTI|GPIO_PIN5) +# define GPIO_FMC_SDCKE0_3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN2) +# define GPIO_FMC_SDCKE1_1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTB|GPIO_PIN5) +# define GPIO_FMC_SDCKE1_2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN7) +# define GPIO_FMC_SDNE0_3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN3) +# define GPIO_FMC_SDNE1_1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTB|GPIO_PIN6) +# define GPIO_FMC_SDNE1_2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN6) +# define GPIO_FMC_SDNWE_3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTH|GPIO_PIN5) + +/* Flexible Static Memory Controller (FSMC) */ + +#define GPIO_FSMC_A0 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN0) +#define GPIO_FSMC_A1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN1) +#define GPIO_FSMC_A2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN2) +#define GPIO_FSMC_A3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN3) +#define GPIO_FSMC_A4 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN4) +#define GPIO_FSMC_A5 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN5) +#define GPIO_FSMC_A6 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN12) +#define GPIO_FSMC_A7 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN13) +#define GPIO_FSMC_A8 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN14) +#define GPIO_FSMC_A9 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTF|GPIO_PIN15) +#define GPIO_FSMC_A10 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN0) +#define GPIO_FSMC_A11 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN1) +#define GPIO_FSMC_A12 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN2) +#define GPIO_FSMC_A13 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN3) +#define GPIO_FSMC_A14 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN4) +#define GPIO_FSMC_A15 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN5) +#define GPIO_FSMC_A16 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN11) +#define GPIO_FSMC_A17 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN12) +#define GPIO_FSMC_A18 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN13) +#define GPIO_FSMC_A19 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN3) +#define GPIO_FSMC_A20 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN4) +#define GPIO_FSMC_A21 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN5) +#define GPIO_FSMC_A22 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN6) +#define GPIO_FSMC_A23 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN2) +#define GPIO_FSMC_A24 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN13) +#define GPIO_FSMC_A25 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN14) +#define GPIO_FSMC_NBL1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN1) +#define GPIO_FSMC_CLK (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN3) +#define GPIO_FSMC_D0 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN14) +#define GPIO_FSMC_D1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN15) +#define GPIO_FSMC_D2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN0) +#define GPIO_FSMC_D3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN1) +#define GPIO_FSMC_D4 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN7) +#define GPIO_FSMC_D5 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN8) +#define GPIO_FSMC_D6 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN9) +#define GPIO_FSMC_D7 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN10) +#define GPIO_FSMC_D8 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN11) +#define GPIO_FSMC_D9 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN12) +#define GPIO_FSMC_D10 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN13) +#define GPIO_FSMC_D11 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN14) +#define GPIO_FSMC_D12 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN15) +#define GPIO_FSMC_D13 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN8) +#define GPIO_FSMC_D14 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN9) +#define GPIO_FSMC_D15 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN10) +#define GPIO_FSMC_NBL0 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN0) +#define GPIO_FSMC_NE1 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN7) +#define GPIO_FSMC_NE2 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN9) +#define GPIO_FSMC_NE3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN10) +#define GPIO_FSMC_NE4 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN12) +#define GPIO_FSMC_NL (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTB|GPIO_PIN7) +#define GPIO_FSMC_NOE (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN4) +#define GPIO_FSMC_NWAIT (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN6) +#define GPIO_FSMC_NWE (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN5) + +#define GPIO_FSMC_INT3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN7) +#define GPIO_FSMC_NCE3 (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PORTG|GPIO_PIN9) + +/* I2C */ + +#define GPIO_I2C1_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN9) +#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) + +#define GPIO_I2C2_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTF|GPIO_PIN1) +#define GPIO_I2C2_SCL_3 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN4) +#define GPIO_I2C2_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTF|GPIO_PIN0) +#define GPIO_I2C2_SDA_3 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN5) +#define GPIO_I2C2_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +#define GPIO_I2C2_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN2) +#define GPIO_I2C2_SMBA_3 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6) + + +#define GPIO_I2C3_SCL_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN8) +#define GPIO_I2C3_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN7) +#define GPIO_I2C3_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTC|GPIO_PIN9) +#define GPIO_I2C3_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN8) + +#define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) + + +/* I2S */ + +#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) +#define GPIO_I2S2_SD_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN15) +#define GPIO_I2S2_SD_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN3) +#define GPIO_I2S2_SD_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN3) +#define GPIO_I2S2_WS_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN12) +#define GPIO_I2S2_WS_2 (GPIO_ALT|GPIO_AF5|GPIO_PORTB|GPIO_PIN9) +#define GPIO_I2S2_WS_3 (GPIO_ALT|GPIO_AF5|GPIO_PORTI|GPIO_PIN0) + +# define GPIO_I2S2_CK_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTD|GPIO_PIN3) +# define GPIO_I2S2_SD_4 (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN1) + + +# define GPIO_I2S2_MCK (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN6) + +#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) +#define GPIO_I2S2EXT_SD_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTI|GPIO_PIN2) + +#define GPIO_I2S3_CK_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTB|GPIO_PIN3) +#define GPIO_I2S3_CK_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN10) +#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) +#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) + +# define GPIO_I2S3_SD_3 (GPIO_ALT|GPIO_AF6|GPIO_PORTD|GPIO_PIN6) + + +# define GPIO_I2S3EXT_SD_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN4) + +#define GPIO_I2S3EXT_SD_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTC|GPIO_PIN11) + +#define GPIO_I2S_CKIN (GPIO_ALT|GPIO_AF5|GPIO_PORTC|GPIO_PIN9) + +/* JTAG */ + +#define GPIO_JTCK_SWCLK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN14) +#define GPIO_JTDI (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) +#define GPIO_JTDO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) +#define GPIO_JTMS_SWDIO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13) +#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) + +/* OTG FS/HS (VBUS PA9 is not an alternate configuration) */ + +#define GPIO_OTGFS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_OTGFS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12) +#define GPIO_OTGFS_ID (GPIO_ALT|GPIO_PULLUP|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN10) +#define GPIO_OTGFS_SOF (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) + +#define GPIO_OTGHSFS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_OTGHSFS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_OTGHSFS_ID (GPIO_ALT|GPIO_PULLUP|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN12) + +#define GPIO_OTGHS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_OTGHS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_OTGHS_ID (GPIO_ALT|GPIO_PULLUP|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN12) +#define GPIO_OTGHS_SOF (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN4) + +#define GPIO_OTGHS_ULPI_CK (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN5) +#define GPIO_OTGHS_ULPI_D0 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN3) +#define GPIO_OTGHS_ULPI_D1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN0) +#define GPIO_OTGHS_ULPI_D2 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN1) +#define GPIO_OTGHS_ULPI_D3 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN10) +#define GPIO_OTGHS_ULPI_D5 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN12) +#define GPIO_OTGHS_ULPI_D6 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN13) +#define GPIO_OTGHS_ULPI_D7 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN5) +#define GPIO_OTGHS_ULPI_DIR_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN2) +#define GPIO_OTGHS_ULPI_DIR_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTI|GPIO_PIN11) +#define GPIO_OTGHS_ULPI_NXT_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN3) +#define GPIO_OTGHS_ULPI_NXT_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTH|GPIO_PIN4) +#define GPIO_OTGHS_ULPI_STP (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN0) + + +# define GPIO_OTGHS_ULPI_D4 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN11) + +/* RTC */ + +#define GPIO_RTC_50HZ (GPIO_ALT|GPIO_AF0|GPIO_PORTC|GPIO_PIN15) + +/* SDIO + * + * Note that the below configures GPIO_SPEED_50MHz I/O, that means for using + * the SDIO that you must enable I/O Compensation via the configuration + * option CONFIG_STM32_SYSCFG_IOCOMPENSATION=y. + */ + +#define GPIO_SDIO_CMD (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN2) +#define GPIO_SDIO_D0 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_SDIO_D3 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11) +#define GPIO_SDIO_D4 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_SDIO_D5 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SDIO_D6 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_SDIO_D7 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) + +# define GPIO_SDIO_CK (GPIO_ALT|GPIO_AF12|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN12) +# define GPIO_SDIO_D1 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +# define GPIO_SDIO_D2 (GPIO_ALT|GPIO_AF12|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) + +/* SPI */ + +#define GPIO_SPI1_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN6) +#define GPIO_SPI1_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI1_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN7) +#define GPIO_SPI1_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN5) +#define GPIO_SPI1_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI1_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI1_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN5) +#define GPIO_SPI1_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3) + +#define GPIO_SPI2_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SPI2_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN2) +#define GPIO_SPI2_MISO_3 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTI|GPIO_PIN2) +#define GPIO_SPI2_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN15) +#define GPIO_SPI2_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN3) +#define GPIO_SPI2_MOSI_3 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTI|GPIO_PIN3) +#define GPIO_SPI2_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN12) +#define GPIO_SPI2_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SPI2_NSS_3 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTI|GPIO_PIN0) +#define GPIO_SPI2_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN10) +#define GPIO_SPI2_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN13) +#define GPIO_SPI2_SCK_3 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTI|GPIO_PIN1) + +# define GPIO_SPI2_SCK_4 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN3) + +#define GPIO_SPI3_MISO_1 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI3_MISO_2 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN11) +#define GPIO_SPI3_MOSI_1 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN5) +#define GPIO_SPI3_MOSI_2 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN12) +#define GPIO_SPI3_NSS_1 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI3_NSS_2 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI3_SCK_1 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI3_SCK_2 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN10) + +# define GPIO_SPI3_MOSI_3 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN6) + +# define GPIO_SPI4_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN5) +# define GPIO_SPI4_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN13) +# define GPIO_SPI4_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN6) +# define GPIO_SPI4_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN14) +# define GPIO_SPI4_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN4) +# define GPIO_SPI4_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN11) +# define GPIO_SPI4_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN2) +# define GPIO_SPI4_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTE|GPIO_PIN12) + + +# define GPIO_SPI5_MISO_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTF|GPIO_PIN8) +# define GPIO_SPI5_MISO_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTH|GPIO_PIN7) +# define GPIO_SPI5_MOSI_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTF|GPIO_PIN9) +# define GPIO_SPI5_MOSI_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTF|GPIO_PIN11) +# define GPIO_SPI5_NSS_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTF|GPIO_PIN6) +# define GPIO_SPI5_NSS_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTH|GPIO_PIN5) +# define GPIO_SPI5_SCK_1 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTF|GPIO_PIN7) +# define GPIO_SPI5_SCK_2 (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTH|GPIO_PIN6) + + +# define GPIO_SPI6_MISO (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTG|GPIO_PIN12) +# define GPIO_SPI6_MOSI (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTG|GPIO_PIN14) +# define GPIO_SPI6_NSS (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTG|GPIO_PIN8) +# define GPIO_SPI6_SCK (GPIO_ALT|GPIO_AF5|GPIO_SPEED_50MHz|GPIO_PORTG|GPIO_PIN13) + + +/* Timers */ + +#define GPIO_TIM1_BKIN_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM1_BKIN_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN12) +#define GPIO_TIM1_BKIN_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN15) +#define GPIO_TIM1_CH1N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM1_CH1N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN13) +#define GPIO_TIM1_CH1N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN8) +#define GPIO_TIM1_CH1IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH1OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH2N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM1_CH2N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM1_CH2N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN10) +#define GPIO_TIM1_CH2IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH2OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH3N_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM1_CH3N_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM1_CH3N_3 (GPIO_ALT|GPIO_AF1|GPIO_PORTE|GPIO_PIN12) +#define GPIO_TIM1_CH3IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH3OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH4IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_CH4OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_ETR_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN12) +#define GPIO_TIM1_ETR_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN7) + +#define GPIO_TIM2_CH1IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH1IN_3 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH1OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH1OUT_3 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH2IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH2OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH3IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH3OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH4IN_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4IN_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_CH4OUT_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4OUT_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_ETR_1 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_ETR_2 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_ETR_3 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN5) + +#define GPIO_TIM3_CH1IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1IN_3 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH2IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2IN_3 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2OUT_3 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH3IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH4IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_ETR (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN2) + +#define GPIO_TIM4_CH1IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM4_CH1IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN12) +#define GPIO_TIM4_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM4_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN12) +#define GPIO_TIM4_CH2IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM4_CH2IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN13) +#define GPIO_TIM4_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM4_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13) +#define GPIO_TIM4_CH3IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM4_CH3IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN14) +#define GPIO_TIM4_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM4_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN14) +#define GPIO_TIM4_CH4IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM4_CH4IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) +#define GPIO_TIM4_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM4_CH4OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN15) +#define GPIO_TIM4_ETR (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN0) + +#define GPIO_TIM5_CH1IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH1IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN10) +#define GPIO_TIM5_CH1OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH1OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN10) +#define GPIO_TIM5_CH2IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH2IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN11) +#define GPIO_TIM5_CH2OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH2OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN11) +#define GPIO_TIM5_CH3IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH3IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN12) +#define GPIO_TIM5_CH3OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH3OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN12) +#define GPIO_TIM5_CH4IN_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM5_CH4IN_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN0) +#define GPIO_TIM5_CH4OUT_1 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM5_CH4OUT_2 (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN0) +#define GPIO_TIM5_ETR (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN10) + +#define GPIO_TIM8_BKIN_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM8_BKIN_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTI|GPIO_PIN4) +#define GPIO_TIM8_CH1N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM8_CH1N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM8_CH1N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN13) +#define GPIO_TIM8_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM8_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN5) +#define GPIO_TIM8_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM8_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN5) +#define GPIO_TIM8_CH2N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM8_CH2N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM8_CH2N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN14) +#define GPIO_TIM8_CH2IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM8_CH2IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN6) +#define GPIO_TIM8_CH2OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM8_CH2OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN6) +#define GPIO_TIM8_CH3N_1 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM8_CH3N_2 (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM8_CH3N_3 (GPIO_ALT|GPIO_AF3|GPIO_PORTH|GPIO_PIN15) +#define GPIO_TIM8_CH3IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM8_CH3IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN7) +#define GPIO_TIM8_CH3OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM8_CH3OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN7) +#define GPIO_TIM8_CH4IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_CH4IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN2) +#define GPIO_TIM8_CH4OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_CH4OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN2) +#define GPIO_TIM8_ETR_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM8_ETR_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN3) + +#define GPIO_TIM9_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM9_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM9_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM9_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM9_CH2IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM9_CH2IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN6) +#define GPIO_TIM9_CH2OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM9_CH2OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN6) + +#define GPIO_TIM10_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM10_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN6) +#define GPIO_TIM10_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM10_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN6) + +#define GPIO_TIM11_CH1IN_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM11_CH1IN_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN7) +#define GPIO_TIM11_CH1OUT_1 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM11_CH1OUT_2 (GPIO_ALT|GPIO_AF3|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN7) + +#define GPIO_TIM12_CH1IN_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN6) +#define GPIO_TIM12_CH1IN_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM12_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6) +#define GPIO_TIM12_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM12_CH2IN_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM12_CH2IN_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN9) +#define GPIO_TIM12_CH2OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM12_CH2OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) + +#define GPIO_TIM13_CH1IN_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM13_CH1IN_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN8) +#define GPIO_TIM13_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM13_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN8) + +#define GPIO_TIM14_CH1IN_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM14_CH1IN_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN9) +#define GPIO_TIM14_CH1OUT_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM14_CH1OUT_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN9) + + +/* Trace */ + +#define GPIO_TRACECLK (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +#define GPIO_TRACESWO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + + +# define GPIO_TRACED0 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) + + +# define GPIO_TRACED2 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) + +/* UARTs/USARTs */ + +#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN8) +#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN11) +#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN12) +#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10) +#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7) + +#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) + +#define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN4) +#define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN7) +#define GPIO_USART2_CTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN0) +#define GPIO_USART2_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN3) +#define GPIO_USART2_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN1) +#define GPIO_USART2_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN4) +#define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN6) +#define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5) + +#define GPIO_USART3_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN12) +#define GPIO_USART3_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTC|GPIO_PIN12) +#define GPIO_USART3_CK_3 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN10) +#define GPIO_USART3_CTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN13) +#define GPIO_USART3_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN11) +#define GPIO_USART3_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN14) +#define GPIO_USART3_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN12) +#define GPIO_USART3_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +#define GPIO_USART3_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11) +#define GPIO_USART3_RX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN9) + +#define GPIO_USART3_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +#define GPIO_USART3_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) +#define GPIO_USART3_TX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN8) + + + +#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11) +#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) + + +#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN2) +#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN12) + +#define GPIO_USART6_CK_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN8) +#define GPIO_USART6_CK_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN7) +#define GPIO_USART6_CTS_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN13) +#define GPIO_USART6_CTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN15) +#define GPIO_USART6_RTS_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN12) +#define GPIO_USART6_RTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN8) +#define GPIO_USART6_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_USART6_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN9) +#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) + + +# 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) + + +/* LCD-TFT Display Controller (LTDC) */ + +# define GPIO_LTDC_R0_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN2) +# define GPIO_LTDC_R0_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN15) +# define GPIO_LTDC_R1_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN3) +# define GPIO_LTDC_R1_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN0) +# define GPIO_LTDC_R2_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10) +# define GPIO_LTDC_R2_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN8) +# define GPIO_LTDC_R2_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN1) +# define GPIO_LTDC_R3_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +# define GPIO_LTDC_R3_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) +# define GPIO_LTDC_R3_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN2) +# define GPIO_LTDC_R4_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +# define GPIO_LTDC_R4_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN10) +# define GPIO_LTDC_R4_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN3) +# define GPIO_LTDC_R5_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12) +# define GPIO_LTDC_R5_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN11) +# define GPIO_LTDC_R5_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN4) +# define GPIO_LTDC_R6_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +# define GPIO_LTDC_R6_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN12) +# define GPIO_LTDC_R6_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN5) +# define GPIO_LTDC_R6_4 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +# define GPIO_LTDC_R7_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN6) +# define GPIO_LTDC_R7_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN15) +# define GPIO_LTDC_R7_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN6) + +# define GPIO_LTDC_G0_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN5) +# define GPIO_LTDC_G0_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN7) +# define GPIO_LTDC_G1_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN6) +# define GPIO_LTDC_G1_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN8) +# define GPIO_LTDC_G2_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +# define GPIO_LTDC_G2_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN13) +# define GPIO_LTDC_G2_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN9) +# define GPIO_LTDC_G3_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN10) +# define GPIO_LTDC_G3_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN14) +# define GPIO_LTDC_G3_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN10) +# define GPIO_LTDC_G3_4 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) +# define GPIO_LTDC_G4_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +# define GPIO_LTDC_G4_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN15) +# define GPIO_LTDC_G4_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN11) +# define GPIO_LTDC_G5_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +# define GPIO_LTDC_G5_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN0) +# define GPIO_LTDC_G5_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN0) +# define GPIO_LTDC_G6_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +# define GPIO_LTDC_G6_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN1) +# define GPIO_LTDC_G6_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN1) +# define GPIO_LTDC_G7_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN3) +# define GPIO_LTDC_G7_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN2) +# define GPIO_LTDC_G7_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN2) + +# define GPIO_LTDC_B0_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN4) +# define GPIO_LTDC_B0_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN12) +# define GPIO_LTDC_B1_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN12) +# define GPIO_LTDC_B1_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN13) +# define GPIO_LTDC_B2_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN6) +# define GPIO_LTDC_B2_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN10) +# define GPIO_LTDC_B2_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN14) +# define GPIO_LTDC_B3_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) +# define GPIO_LTDC_B3_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN10) +# define GPIO_LTDC_B3_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTJ|GPIO_PIN15) +# define GPIO_LTDC_B4_1 (GPIO_ALT|GPIO_AF9 |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN12) +# define GPIO_LTDC_B4_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN12) +# define GPIO_LTDC_B4_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN4) +# define GPIO_LTDC_B4_4 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN3) +# define GPIO_LTDC_B5_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +# define GPIO_LTDC_B5_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN5) +# define GPIO_LTDC_B5_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN4) +# define GPIO_LTDC_B6_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +# define GPIO_LTDC_B6_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN6) +# define GPIO_LTDC_B6_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN5) +# define GPIO_LTDC_B7_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +# define GPIO_LTDC_B7_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN7) +# define GPIO_LTDC_B7_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN6) + +# define GPIO_LTDC_VSYNC_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN4) +# define GPIO_LTDC_VSYNC_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN9) +# define GPIO_LTDC_VSYNC_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN13) +# define GPIO_LTDC_HSYNC_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +# define GPIO_LTDC_HSYNC_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN10) +# define GPIO_LTDC_HSYNC_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN12) +# define GPIO_LTDC_DE_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN10) +# define GPIO_LTDC_DE_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) +# define GPIO_LTDC_DE_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTK|GPIO_PIN7) +# define GPIO_LTDC_CLK_1 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN7) +# define GPIO_LTDC_CLK_2 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) +# define GPIO_LTDC_CLK_3 (GPIO_ALT|GPIO_AF14|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN14) + +#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_PINMAP_LEGACY_H */ diff --git a/arch/arm/src/stm32/hardware/stm32f427ax_rcc.h b/arch/arm/src/stm32/hardware/stm32f427ax_rcc.h new file mode 100644 index 00000000000..6931b135108 --- /dev/null +++ b/arch/arm/src/stm32/hardware/stm32f427ax_rcc.h @@ -0,0 +1,682 @@ +/**************************************************************************** + * arch/arm/src/stm32/hardware/stm32f427xx_rcc.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_RCC_H +#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_RCC_H + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Offsets *********************************************************/ + +#define STM32_RCC_CR_OFFSET 0x0000 /* Clock control register */ +#define STM32_RCC_PLLCFG_OFFSET 0x0004 /* PLL configuration register */ +#define STM32_RCC_CFGR_OFFSET 0x0008 /* Clock configuration register */ +#define STM32_RCC_CIR_OFFSET 0x000c /* Clock interrupt register */ +#define STM32_RCC_AHB1RSTR_OFFSET 0x0010 /* AHB1 peripheral reset register */ +#define STM32_RCC_AHB2RSTR_OFFSET 0x0014 /* AHB2 peripheral reset register */ +#define STM32_RCC_AHB3RSTR_OFFSET 0x0018 /* AHB3 peripheral reset register */ +#define STM32_RCC_APB1RSTR_OFFSET 0x0020 /* APB1 Peripheral reset register */ +#define STM32_RCC_APB2RSTR_OFFSET 0x0024 /* APB2 Peripheral reset register */ +#define STM32_RCC_AHB1ENR_OFFSET 0x0030 /* AHB1 Peripheral Clock enable register */ +#define STM32_RCC_AHB2ENR_OFFSET 0x0034 /* AHB2 Peripheral Clock enable register */ +#define STM32_RCC_AHB3ENR_OFFSET 0x0038 /* AHB3 Peripheral Clock enable register */ +#define STM32_RCC_APB1ENR_OFFSET 0x0040 /* APB1 Peripheral Clock enable register */ +#define STM32_RCC_APB2ENR_OFFSET 0x0044 /* APB2 Peripheral Clock enable register */ +#define STM32_RCC_AHB1LPENR_OFFSET 0x0050 /* RCC AHB1 low power mode peripheral clock enable register */ +#define STM32_RCC_AHB2LPENR_OFFSET 0x0054 /* RCC AHB2 low power mode peripheral clock enable register */ +#define STM32_RCC_AHB3LPENR_OFFSET 0x0058 /* RCC AHB3 low power mode peripheral clock enable register */ +#define STM32_RCC_APB1LPENR_OFFSET 0x0060 /* RCC APB1 low power mode peripheral clock enable register */ +#define STM32_RCC_APB2LPENR_OFFSET 0x0064 /* RCC APB2 low power mode peripheral clock enable register */ +#define STM32_RCC_BDCR_OFFSET 0x0070 /* Backup domain control register */ +#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 */ + + +# define STM32_RCC_PLLSAICFGR_OFFSET 0x0088 /* PLLSAI configuration register */ +# define STM32_RCC_DCKCFGR_OFFSET 0x008c /* Dedicated clocks configuration register */ + + +/* Register Addresses *******************************************************/ + +#define STM32_RCC_CR (STM32_RCC_BASE+STM32_RCC_CR_OFFSET) +#define STM32_RCC_PLLCFG (STM32_RCC_BASE+STM32_RCC_PLLCFG_OFFSET) +#define STM32_RCC_CFGR (STM32_RCC_BASE+STM32_RCC_CFGR_OFFSET) +#define STM32_RCC_CIR (STM32_RCC_BASE+STM32_RCC_CIR_OFFSET) +#define STM32_RCC_AHB1RSTR (STM32_RCC_BASE+STM32_RCC_AHB1RSTR_OFFSET) +#define STM32_RCC_AHB2RSTR (STM32_RCC_BASE+STM32_RCC_AHB2RSTR_OFFSET) +#define STM32_RCC_AHB3RSTR (STM32_RCC_BASE+STM32_RCC_AHB3RSTR_OFFSET) +#define STM32_RCC_APB1RSTR (STM32_RCC_BASE+STM32_RCC_APB1RSTR_OFFSET) +#define STM32_RCC_APB2RSTR (STM32_RCC_BASE+STM32_RCC_APB2RSTR_OFFSET) +#define STM32_RCC_AHB1ENR (STM32_RCC_BASE+STM32_RCC_AHB1ENR_OFFSET) +#define STM32_RCC_AHB2ENR (STM32_RCC_BASE+STM32_RCC_AHB2ENR_OFFSET) +#define STM32_RCC_AHB3ENR (STM32_RCC_BASE+STM32_RCC_AHB3ENR_OFFSET) +#define STM32_RCC_APB1ENR (STM32_RCC_BASE+STM32_RCC_APB1ENR_OFFSET) +#define STM32_RCC_APB2ENR (STM32_RCC_BASE+STM32_RCC_APB2ENR_OFFSET) +#define STM32_RCC_AHB1LPENR (STM32_RCC_BASE+STM32_RCC_AHB1LPENR_OFFSET) +#define STM32_RCC_AHB2LPENR (STM32_RCC_BASE+STM32_RCC_AHB2LPENR) +#define STM32_RCC_AHB3LPENR (STM32_RCC_BASE+STM32_RCC_AHB3LPENR_OFFSET) +#define STM32_RCC_APB1LPENR (STM32_RCC_BASE+STM32_RCC_APB1LPENR_OFFSET) +#define STM32_RCC_APB2LPENR (STM32_RCC_BASE+STM32_RCC_APB2LPENR_OFFSET) +#define STM32_RCC_BDCR (STM32_RCC_BASE+STM32_RCC_BDCR_OFFSET) +#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) + + +#define STM32_RCC_PLLSAICFGR (STM32_RCC_BASE+STM32_RCC_PLLSAICFGR_OFFSET) +#define STM32_RCC_DCKCFGR (STM32_RCC_BASE+STM32_RCC_DCKCFGR_OFFSET) + + + +/* Register Bitfield Definitions ********************************************/ + +/* Clock control register */ + +#define RCC_CR_HSION (1 << 0) /* Bit 0: Internal High Speed clock enable */ +#define RCC_CR_HSIRDY (1 << 1) /* Bit 1: Internal High Speed clock ready flag */ +#define RCC_CR_HSITRIM_SHIFT (3) /* Bits 7-3: Internal High Speed clock trimming */ +#define RCC_CR_HSITRIM_MASK (0x1f << RCC_CR_HSITRIM_SHIFT) +#define RCC_CR_HSICAL_SHIFT (8) /* Bits 15-8: Internal High Speed clock Calibration */ +#define RCC_CR_HSICAL_MASK (0xff << RCC_CR_HSICAL_SHIFT) +#define RCC_CR_HSEON (1 << 16) /* Bit 16: External High Speed clock enable */ +#define RCC_CR_HSERDY (1 << 17) /* Bit 17: External High Speed clock ready flag */ +#define RCC_CR_HSEBYP (1 << 18) /* Bit 18: External High Speed clock Bypass */ +#define RCC_CR_CSSON (1 << 19) /* Bit 19: Clock Security System enable */ +#define RCC_CR_PLLON (1 << 24) /* Bit 24: PLL enable */ +#define RCC_CR_PLLRDY (1 << 25) /* Bit 25: PLL clock ready flag */ +#define RCC_CR_PLLI2SON (1 << 26) /* Bit 26: PLLI2S enable */ +#define RCC_CR_PLLI2SRDY (1 << 27) /* Bit 27: PLLI2S clock ready flag */ +#define RCC_CR_PLLSAION (1 << 28) /* Bit 28: PLLSAI enable */ +#define RCC_CR_PLLSAIRDY (1 << 29) /* Bit 29: PLLSAI clock ready flag */ + +/* PLL configuration register */ + +#define RCC_PLLCFG_PLLM_SHIFT (0) /* Bits 0-5: Main PLL (PLL) and audio PLL (PLLI2S) + * input clock divider */ +#define RCC_PLLCFG_PLLM_MASK (0x3f << RCC_PLLCFG_PLLM_SHIFT) +# define RCC_PLLCFG_PLLM(n) ((n) << RCC_PLLCFG_PLLM_SHIFT) /* n = 2..63 */ + +#define RCC_PLLCFG_PLLN_SHIFT (6) /* Bits 6-14: Main PLL (PLL) VCO multiplier */ +#define RCC_PLLCFG_PLLN_MASK (0x1ff << RCC_PLLCFG_PLLN_SHIFT) +# define RCC_PLLCFG_PLLN(n) ((n) << RCC_PLLCFG_PLLN_SHIFT) /* n = 2..432 */ + +#define RCC_PLLCFG_PLLP_SHIFT (16) /* Bits 16-17: Main PLL (PLL) main system clock divider */ +#define RCC_PLLCFG_PLLP_MASK (3 << RCC_PLLCFG_PLLP_SHIFT) +# define RCC_PLLCFG_PLLP(n) ((((n)>>1)-1)<< RCC_PLLCFG_PLLP_SHIFT) /* n=2,4,6,8 */ + +# define RCC_PLLCFG_PLLP_2 (0 << RCC_PLLCFG_PLLP_SHIFT) /* 00: PLLP = 2 */ +# define RCC_PLLCFG_PLLP_4 (1 << RCC_PLLCFG_PLLP_SHIFT) /* 01: PLLP = 4 */ +# define RCC_PLLCFG_PLLP_6 (2 << RCC_PLLCFG_PLLP_SHIFT) /* 10: PLLP = 6 */ +# define RCC_PLLCFG_PLLP_8 (3 << RCC_PLLCFG_PLLP_SHIFT) /* 11: PLLP = 8 */ + +#define RCC_PLLCFG_PLLSRC (1 << 22) /* Bit 22: Main PLL(PLL) and audio PLL (PLLI2S) + * entry clock source */ +# define RCC_PLLCFG_PLLSRC_HSI (0) +# define RCC_PLLCFG_PLLSRC_HSE RCC_PLLCFG_PLLSRC +#define RCC_PLLCFG_PLLQ_SHIFT (24) /* Bits 24-27: Main PLL (PLL) divider + * (USB OTG FS, SDIO and RNG clocks) */ +#define RCC_PLLCFG_PLLQ_MASK (15 << RCC_PLLCFG_PLLQ_SHIFT) +# define RCC_PLLCFG_PLLQ(n) ((n) << RCC_PLLCFG_PLLQ_SHIFT) /* n=2..15 */ + + +# define RCC_PLLCFG_PLLR_SHIFT (28) /* Bits 28-30: Main PLLR (PLLR) divider + * (I2Ss, SAIs, SYSTEM and SPDIF-Rx clocks) */ +# define RCC_PLLCFG_PLLR_MASK (7 << RCC_PLLCFG_PLLR_SHIFT) +# define RCC_PLLCFG_PLLR(n) ((n) << RCC_PLLCFG_PLLR_SHIFT) /* n=1..7 */ + + +#define RCC_PLLCFG_RESET (0x24003010) /* PLLCFG reset value */ + +/* Clock configuration register */ + +#define RCC_CFGR_SW_SHIFT (0) /* Bits 0-1: System clock Switch */ +#define RCC_CFGR_SW_MASK (3 << RCC_CFGR_SW_SHIFT) +# define RCC_CFGR_SW_HSI (0 << RCC_CFGR_SW_SHIFT) /* 00: HSI selected as system clock */ +# define RCC_CFGR_SW_HSE (1 << RCC_CFGR_SW_SHIFT) /* 01: HSE selected as system clock */ +# define RCC_CFGR_SW_PLL (2 << RCC_CFGR_SW_SHIFT) /* 10: PLL selected as system clock */ + +#define RCC_CFGR_SWS_SHIFT (2) /* Bits 2-3: System Clock Switch Status */ +#define RCC_CFGR_SWS_MASK (3 << RCC_CFGR_SWS_SHIFT) +# define RCC_CFGR_SWS_HSI (0 << RCC_CFGR_SWS_SHIFT) /* 00: HSI oscillator used as system clock */ +# define RCC_CFGR_SWS_HSE (1 << RCC_CFGR_SWS_SHIFT) /* 01: HSE oscillator used as system clock */ +# define RCC_CFGR_SWS_PLL (2 << RCC_CFGR_SWS_SHIFT) /* 10: PLL used as system clock */ + +#define RCC_CFGR_HPRE_SHIFT (4) /* Bits 4-7: AHB prescaler */ +#define RCC_CFGR_HPRE_MASK (0x0f << RCC_CFGR_HPRE_SHIFT) +# define RCC_CFGR_HPRE_SYSCLK (0 << RCC_CFGR_HPRE_SHIFT) /* 0xxx: SYSCLK not divided */ +# define RCC_CFGR_HPRE_SYSCLKd2 (8 << RCC_CFGR_HPRE_SHIFT) /* 1000: SYSCLK divided by 2 */ +# define RCC_CFGR_HPRE_SYSCLKd4 (9 << RCC_CFGR_HPRE_SHIFT) /* 1001: SYSCLK divided by 4 */ +# define RCC_CFGR_HPRE_SYSCLKd8 (10 << RCC_CFGR_HPRE_SHIFT) /* 1010: SYSCLK divided by 8 */ +# define RCC_CFGR_HPRE_SYSCLKd16 (11 << RCC_CFGR_HPRE_SHIFT) /* 1011: SYSCLK divided by 16 */ +# define RCC_CFGR_HPRE_SYSCLKd64 (12 << RCC_CFGR_HPRE_SHIFT) /* 1100: SYSCLK divided by 64 */ +# define RCC_CFGR_HPRE_SYSCLKd128 (13 << RCC_CFGR_HPRE_SHIFT) /* 1101: SYSCLK divided by 128 */ +# define RCC_CFGR_HPRE_SYSCLKd256 (14 << RCC_CFGR_HPRE_SHIFT) /* 1110: SYSCLK divided by 256 */ +# define RCC_CFGR_HPRE_SYSCLKd512 (15 << RCC_CFGR_HPRE_SHIFT) /* 1111: SYSCLK divided by 512 */ + +#define RCC_CFGR_PPRE1_SHIFT (10) /* Bits 10-12: APB Low speed prescaler (APB1) */ +#define RCC_CFGR_PPRE1_MASK (7 << RCC_CFGR_PPRE1_SHIFT) +# define RCC_CFGR_PPRE1_HCLK (0 << RCC_CFGR_PPRE1_SHIFT) /* 0xx: HCLK not divided */ +# define RCC_CFGR_PPRE1_HCLKd2 (4 << RCC_CFGR_PPRE1_SHIFT) /* 100: HCLK divided by 2 */ +# define RCC_CFGR_PPRE1_HCLKd4 (5 << RCC_CFGR_PPRE1_SHIFT) /* 101: HCLK divided by 4 */ +# define RCC_CFGR_PPRE1_HCLKd8 (6 << RCC_CFGR_PPRE1_SHIFT) /* 110: HCLK divided by 8 */ +# define RCC_CFGR_PPRE1_HCLKd16 (7 << RCC_CFGR_PPRE1_SHIFT) /* 111: HCLK divided by 16 */ + +#define RCC_CFGR_PPRE2_SHIFT (13) /* Bits 13-15: APB High speed prescaler (APB2) */ +#define RCC_CFGR_PPRE2_MASK (7 << RCC_CFGR_PPRE2_SHIFT) +# define RCC_CFGR_PPRE2_HCLK (0 << RCC_CFGR_PPRE2_SHIFT) /* 0xx: HCLK not divided */ +# define RCC_CFGR_PPRE2_HCLKd2 (4 << RCC_CFGR_PPRE2_SHIFT) /* 100: HCLK divided by 2 */ +# define RCC_CFGR_PPRE2_HCLKd4 (5 << RCC_CFGR_PPRE2_SHIFT) /* 101: HCLK divided by 4 */ +# define RCC_CFGR_PPRE2_HCLKd8 (6 << RCC_CFGR_PPRE2_SHIFT) /* 110: HCLK divided by 8 */ +# define RCC_CFGR_PPRE2_HCLKd16 (7 << RCC_CFGR_PPRE2_SHIFT) /* 111: HCLK divided by 16 */ + +#define RCC_CFGR_RTCPRE_SHIFT (16) /* Bits 16-20: APB High speed prescaler (APB2) */ +#define RCC_CFGR_RTCPRE_MASK (31 << RCC_CFGR_RTCPRE_SHIFT) +# define RCC_CFGR_RTCPRE(n) ((n) << RCC_CFGR_RTCPRE_SHIFT) /* HSE/n, n=1..31 */ + +#define RCC_CFGR_MCO1_SHIFT (21) /* Bits 21-22: Microcontroller Clock Output */ +#define RCC_CFGR_MCO1_MASK (3 << RCC_CFGR_MCO1_SHIFT) +# define RCC_CFGR_MCO1_HSI (0 << RCC_CFGR_MCO1_SHIFT) /* 00: HSI clock selected */ +# define RCC_CFGR_MCO1_LSE (1 << RCC_CFGR_MCO1_SHIFT) /* 01: LSE oscillator selected */ +# define RCC_CFGR_MCO1_HSE (2 << RCC_CFGR_MCO1_SHIFT) /* 10: HSE oscillator clock selected */ +# define RCC_CFGR_MCO1_PLL (3 << RCC_CFGR_MCO1_SHIFT) /* 11: PLL clock selected */ + +#define RCC_CFGR_I2SSRC (1 << 23) /* Bit 23: I2S clock selection */ +#define RCC_CFGR_MCO1PRE_SHIFT (24) /* Bits 24-26: MCO1 prescaler */ +#define RCC_CFGR_MCO1PRE_MASK (7 << RCC_CFGR_MCO1PRE_SHIFT) +# define RCC_CFGR_MCO1PRE_NONE (0 << RCC_CFGR_MCO1PRE_SHIFT) /* 0xx: no division */ +# define RCC_CFGR_MCO1PRE_DIV2 (4 << RCC_CFGR_MCO1PRE_SHIFT) /* 100: division by 2 */ +# define RCC_CFGR_MCO1PRE_DIV3 (5 << RCC_CFGR_MCO1PRE_SHIFT) /* 101: division by 3 */ +# define RCC_CFGR_MCO1PRE_DIV4 (6 << RCC_CFGR_MCO1PRE_SHIFT) /* 110: division by 4 */ +# define RCC_CFGR_MCO1PRE_DIV5 (7 << RCC_CFGR_MCO1PRE_SHIFT) /* 111: division by 5 */ + +#define RCC_CFGR_MCO2PRE_SHIFT (27) /* Bits 27-29: MCO2 prescaler */ +#define RCC_CFGR_MCO2PRE_MASK (7 << RCC_CFGR_MCO2PRE_SHIFT) +# define RCC_CFGR_MCO2PRE_NONE (0 << RCC_CFGR_MCO2PRE_SHIFT) /* 0xx: no division */ +# define RCC_CFGR_MCO2PRE_DIV2 (4 << RCC_CFGR_MCO2PRE_SHIFT) /* 100: division by 2 */ +# define RCC_CFGR_MCO2PRE_DIV3 (5 << RCC_CFGR_MCO2PRE_SHIFT) /* 101: division by 3 */ +# define RCC_CFGR_MCO2PRE_DIV4 (6 << RCC_CFGR_MCO2PRE_SHIFT) /* 110: division by 4 */ +# define RCC_CFGR_MCO2PRE_DIV5 (7 << RCC_CFGR_MCO2PRE_SHIFT) /* 111: division by 5 */ + +#define RCC_CFGR_MCO2_SHIFT (30) /* Bits 30-31: Microcontroller clock output 2 */ +#define RCC_CFGR_MCO2_MASK (3 << RCC_CFGR_MCO2_SHIFT) +# define RCC_CFGR_MCO2_SYSCLK (0 << RCC_CFGR_MCO2_SHIFT) /* 00: System clock (SYSCLK) selected */ +# define RCC_CFGR_MCO2_PLLI2S (1 << RCC_CFGR_MCO2_SHIFT) /* 01: PLLI2S clock selected */ +# define RCC_CFGR_MCO2_HSE (2 << RCC_CFGR_MCO2_SHIFT) /* 10: HSE oscillator clock selected */ +# define RCC_CFGR_MCO2_PLL (3 << RCC_CFGR_MCO2_SHIFT) /* 11: PLL clock selected */ + +/* Clock interrupt register */ + +#define RCC_CIR_LSIRDYF (1 << 0) /* Bit 0: LSI Ready Interrupt flag */ +#define RCC_CIR_LSERDYF (1 << 1) /* Bit 1: LSE Ready Interrupt flag */ +#define RCC_CIR_HSIRDYF (1 << 2) /* Bit 2: HSI Ready Interrupt flag */ +#define RCC_CIR_HSERDYF (1 << 3) /* Bit 3: HSE Ready Interrupt flag */ +#define RCC_CIR_PLLRDYF (1 << 4) /* Bit 4: PLL Ready Interrupt flag */ +#define RCC_CIR_PLLI2SRDYF (1 << 5) /* Bit 5: PLLI2S Ready Interrupt flag */ +#define RCC_CIR_CSSF (1 << 7) /* Bit 7: Clock Security System Interrupt flag */ +#define RCC_CIR_LSIRDYIE (1 << 8) /* Bit 8: LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE (1 << 9) /* Bit 9: LSE Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE (1 << 10) /* Bit 10: HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE (1 << 11) /* Bit 11: HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE (1 << 12) /* Bit 12: PLL Ready Interrupt Enable */ +#define RCC_CIR_PLLI2SRDYIE (1 << 13) /* Bit 13: PLLI2S Ready Interrupt enable */ +#define RCC_CIR_PLLSAIRDYIE (1 << 14) /* Bit 14: PLLSAI Ready Interrupt enable */ +#define RCC_CIR_LSIRDYC (1 << 16) /* Bit 16: LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYC (1 << 17) /* Bit 17: LSE Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYC (1 << 18) /* Bit 18: HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYC (1 << 19) /* Bit 19: HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYC (1 << 20) /* Bit 20: PLL Ready Interrupt Clear */ +#define RCC_CIR_PLLI2SRDYC (1 << 21) /* Bit 21: PLLI2S Ready Interrupt clear */ +#define RCC_CIR_PLLSAIRDYC (1 << 22) /* Bit 22: PLLSAI Ready Interrupt clear */ +#define RCC_CIR_CSSC (1 << 23) /* Bit 23: Clock Security System Interrupt Clear */ + +/* AHB1 peripheral reset register */ + +#define RCC_AHB1RSTR_GPIOARST (1 << 0) /* Bit 0: IO port A reset */ +#define RCC_AHB1RSTR_GPIOBRST (1 << 1) /* Bit 1: IO port B reset */ +#define RCC_AHB1RSTR_GPIOCRST (1 << 2) /* Bit 2: IO port C reset */ +#define RCC_AHB1RSTR_GPIODRST (1 << 3) /* Bit 3: IO port D reset */ +#define RCC_AHB1RSTR_GPIOERST (1 << 4) /* Bit 4: IO port E reset */ +#define RCC_AHB1RSTR_GPIOFRST (1 << 5) /* Bit 5: IO port F reset */ +#define RCC_AHB1RSTR_GPIOGRST (1 << 6) /* Bit 6: IO port G reset */ +#define RCC_AHB1RSTR_GPIOHRST (1 << 7) /* Bit 7: IO port H reset */ + + +# define RCC_AHB1RSTR_GPIOIRST (1 << 8) /* Bit 8: IO port I reset */ + + + +#define RCC_AHB1RSTR_CRCRST (1 << 12) /* Bit 12 CRC reset */ +#define RCC_AHB1RSTR_DMA1RST (1 << 21) /* Bit 21: DMA1 reset */ +#define RCC_AHB1RSTR_DMA2RST (1 << 22) /* Bit 22: DMA2 reset */ + + +# define RCC_AHB1RSTR_DMA2DRST (1 << 23) /* Bit 23: DMA2D reset */ +# define RCC_AHB1RSTR_ETHMACRST (1 << 25) /* Bit 25: Ethernet MAC reset */ + +#define RCC_AHB1RSTR_OTGHSRST (1 << 29) /* Bit 29: USB OTG HS module reset */ + +/* AHB2 peripheral reset register */ + +#define RCC_AHB2RSTR_DCMIRST (1 << 0) /* Bit 0: Camera interface reset */ + + +# define RCC_AHB2RSTR_CRYPRST (1 << 4) /* Bit 4: Cryptographic module reset */ +# define RCC_AHB2RSTR_HASHRST (1 << 5) /* Bit 5: Hash module reset */ +# define RCC_AHB2RSTR_RNGRST (1 << 6) /* Bit 6: Random number generator module reset */ + +#define RCC_AHB2RSTR_OTGFSRST (1 << 7) /* Bit 7: USB OTG FS module reset */ + +/* AHB3 peripheral reset register */ + +#define RCC_AHB3RSTR_FSMCRST (1 << 0) /* Bit 0: Flexible static memory controller module reset */ + + +/* APB1 Peripheral reset register */ + +#define RCC_APB1RSTR_TIM2RST (1 << 0) /* Bit 0: TIM2 reset */ +#define RCC_APB1RSTR_TIM3RST (1 << 1) /* Bit 1: TIM3 reset */ +#define RCC_APB1RSTR_TIM4RST (1 << 2) /* Bit 2: TIM4 reset */ +#define RCC_APB1RSTR_TIM5RST (1 << 3) /* Bit 3: TIM5 reset */ +#define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: TIM6 reset */ +#define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: TIM7 reset */ +#define RCC_APB1RSTR_TIM12RST (1 << 6) /* Bit 6: TIM12 reset */ +#define RCC_APB1RSTR_TIM13RST (1 << 7) /* Bit 7: TIM13 reset */ +#define RCC_APB1RSTR_TIM14RST (1 << 8) /* Bit 8: TIM14 reset */ +#define RCC_APB1RSTR_WWDGRST (1 << 11) /* Bit 11: Window watchdog reset */ +#define RCC_APB1RSTR_SPI2RST (1 << 14) /* Bit 14: SPI 2 reset */ +#define RCC_APB1RSTR_SPI3RST (1 << 15) /* Bit 15: SPI 3 reset */ +#define RCC_APB1RSTR_USART2RST (1 << 17) /* Bit 17: USART 2 reset */ +#define RCC_APB1RSTR_USART3RST (1 << 18) /* Bit 18: USART 3 reset */ +#define RCC_APB1RSTR_UART4RST (1 << 19) /* Bit 19: USART 4 reset */ +#define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 20: USART 5 reset */ +#define RCC_APB1RSTR_I2C1RST (1 << 21) /* Bit 21: I2C 1 reset */ +#define RCC_APB1RSTR_I2C2RST (1 << 22) /* Bit 22: I2C 2 reset */ +#define RCC_APB1RSTR_I2C3RST (1 << 23) /* Bit 23: I2C3 reset */ +#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +#define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ +#define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */ +#define RCC_APB1RSTR_DAC1RST (1 << 29) /* Bit 29: DAC1 reset */ + + +# define RCC_APB1RSTR_UART7RST (1 << 30) /* Bit 30: USART 7 reset */ +# define RCC_APB1RSTR_UART8RST (1 << 31) /* Bit 31: USART 8 reset */ + + +/* APB2 Peripheral reset register */ + +#define RCC_APB2RSTR_TIM1RST (1 << 0) /* Bit 0: TIM1 reset */ +#define RCC_APB2RSTR_TIM8RST (1 << 1) /* Bit 1: TIM8 reset */ +#define RCC_APB2RSTR_USART1RST (1 << 4) /* Bit 4: USART1 reset */ +#define RCC_APB2RSTR_USART6RST (1 << 5) /* Bit 5: USART6 reset */ +#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 */ + + +# define RCC_APB2RSTR_SPI4RST (1 << 13) /* Bit 13: SPI4 reset */ + + +#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 */ + +# define RCC_APB2RSTR_SPI5RST (1 << 20) /* Bit 20: SPI 5 reset */ + + +# define RCC_APB2RSTR_SPI6RST (1 << 21) /* Bit 21: SPI 6 reset */ + + +# define RCC_APB2RSTR_SAI1RST (1 << 22) /* Bit 22: SAI 1 reset */ + +/* AHB1 Peripheral Clock enable register */ + +#define RCC_AHB1ENR_GPIOEN(n) (1 << (n)) +#define RCC_AHB1ENR_GPIOAEN (1 << 0) /* Bit 0: IO port A clock enable */ +#define RCC_AHB1ENR_GPIOBEN (1 << 1) /* Bit 1: IO port B clock enable */ +#define RCC_AHB1ENR_GPIOCEN (1 << 2) /* Bit 2: IO port C clock enable */ +#define RCC_AHB1ENR_GPIODEN (1 << 3) /* Bit 3: IO port D clock enable */ +#define RCC_AHB1ENR_GPIOEEN (1 << 4) /* Bit 4: IO port E clock enable */ +#define RCC_AHB1ENR_GPIOFEN (1 << 5) /* Bit 5: IO port F clock enable */ +#define RCC_AHB1ENR_GPIOGEN (1 << 6) /* Bit 6: IO port G clock enable */ +#define RCC_AHB1ENR_GPIOHEN (1 << 7) /* Bit 7: IO port H clock enable */ + +# define RCC_AHB1ENR_GPIOIEN (1 << 8) /* Bit 8: IO port I clock enable */ + +#define RCC_AHB1ENR_CRCEN (1 << 12) /* Bit 12: CRC clock enable */ +#define RCC_AHB1ENR_BKPSRAMEN (1 << 18) /* Bit 18: Backup SRAM interface clock enable */ + +# define RCC_AHB1ENR_CCMDATARAMEN (1 << 20) /* Bit 20: CCM data RAM clock enable */ + +#define RCC_AHB1ENR_DMA1EN (1 << 21) /* Bit 21: DMA1 clock enable */ +#define RCC_AHB1ENR_DMA2EN (1 << 22) /* Bit 22: DMA2 clock enable */ + +# define RCC_AHB1ENR_DMA2DEN (1 << 23) /* Bit 23: DMA2D clock enable */ +# define RCC_AHB1ENR_ETHMACEN (1 << 25) /* Bit 25: Ethernet MAC clock enable */ +# define RCC_AHB1ENR_ETHMACTXEN (1 << 26) /* Bit 26: Ethernet Transmission clock enable */ +# define RCC_AHB1ENR_ETHMACRXEN (1 << 27) /* Bit 27: Ethernet Reception clock enable */ +# define RCC_AHB1ENR_ETHMACPTPEN (1 << 28) /* Bit 28: Ethernet PTP clock enable */ + +#define RCC_AHB1ENR_OTGHSEN (1 << 29) /* Bit 29: USB OTG HS clock enable */ +#define RCC_AHB1ENR_OTGHSULPIEN (1 << 30) /* Bit 30: USB OTG HSULPI clock enable */ + +/* AHB2 Peripheral Clock enable register */ + +#define RCC_AHB2ENR_DCMIEN (1 << 0) /* Bit 0: Camera interface enable */ + +# define RCC_AHB2ENR_CRYPEN (1 << 4) /* Bit 4: Cryptographic modules clock enable */ +# define RCC_AHB2ENR_HASHEN (1 << 5) /* Bit 5: Hash modules clock enable */ +# define RCC_AHB2ENR_RNGEN (1 << 6) /* Bit 6: Random number generator clock enable */ + +#define RCC_AHB2ENR_OTGFSEN (1 << 7) /* Bit 7: USB OTG FS clock enable */ + +/* AHB3 Peripheral Clock enable register */ + +#define RCC_AHB3ENR_FSMCEN (1 << 0) /* Bit 0: Flexible static memory controller module clock enable */ +#define RCC_AHB3ENR_FMCEN (1 << 0) /* Bit 0: Flexible memory controller module clock enable */ + + +/* APB1 Peripheral Clock enable register */ + +#define RCC_APB1ENR_TIM2EN (1 << 0) /* Bit 0: TIM2 clock enable */ +#define RCC_APB1ENR_TIM3EN (1 << 1) /* Bit 1: TIM3 clock enable */ +#define RCC_APB1ENR_TIM4EN (1 << 2) /* Bit 2: TIM4 clock enable */ +#define RCC_APB1ENR_TIM5EN (1 << 3) /* Bit 3: TIM5 clock enable */ +#define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: TIM6 clock enable */ +#define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: TIM7 clock enable */ +#define RCC_APB1ENR_TIM12EN (1 << 6) /* Bit 6: TIM12 clock enable */ +#define RCC_APB1ENR_TIM13EN (1 << 7) /* Bit 7: TIM13 clock enable */ +#define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: TIM14 clock enable */ +#define RCC_APB1ENR_RTCAPBEN (1 << 10) /* Bit 10: RTCAPB clock enable */ +#define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window watchdog clock enable */ +#define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI2 clock enable */ +#define RCC_APB1ENR_SPI3EN (1 << 15) /* Bit 15: SPI3 clock enable */ + + +#define RCC_APB1ENR_USART2EN (1 << 17) /* Bit 17: USART 2 clock enable */ +#define RCC_APB1ENR_USART3EN (1 << 18) /* Bit 18: USART3 clock enable */ +#define RCC_APB1ENR_UART4EN (1 << 19) /* Bit 19: UART4 clock enable */ +#define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART5 clock enable */ +#define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C1 clock enable */ +#define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C2 clock enable */ +#define RCC_APB1ENR_I2C3EN (1 << 23) /* Bit 23: I2C3 clock enable */ + + +#define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN 1 clock enable */ +#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_DAC1EN (1 << 29) /* Bit 29: DAC1 interface clock enable */ + +# define RCC_APB1ENR_UART7EN (1 << 30) /* Bit 30: UART7 clock enable */ +# define RCC_APB1ENR_UART8EN (1 << 31) /* Bit 31: UART8 clock enable */ + +/* APB2 Peripheral Clock enable register */ + +#define RCC_APB2ENR_TIM1EN (1 << 0) /* Bit 0: TIM1 clock enable */ +#define RCC_APB2ENR_TIM8EN (1 << 1) /* Bit 1: TIM8 clock enable */ +#define RCC_APB2ENR_USART1EN (1 << 4) /* Bit 4: USART1 clock enable */ +#define RCC_APB2ENR_USART6EN (1 << 5) /* Bit 5: USART6 clock enable */ +#define RCC_APB2ENR_ADC1EN (1 << 8) /* Bit 8: ADC1 clock enable */ +#define RCC_APB2ENR_ADC2EN (1 << 9) /* Bit 9: ADC2 clock enable */ +#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 */ + +# define RCC_APB2ENR_SPI4EN (1 << 13) /* Bit 13: SPI4 clock enable */ + +#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 */ + +# define RCC_APB2ENR_SPI5EN (1 << 20) /* Bit 20: SPI5 clock enable */ + + +# define RCC_APB2ENR_SPI6EN (1 << 21) /* Bit 21: SPI6 clock enable */ + + +# define RCC_APB2ENR_SAI1EN (1 << 22) /* Bit 22: SAI1 clock enable */ + + +/* RCC AHB1 low power mode peripheral clock enable register */ + +#define RCC_AHB1LPENR_GPIOLPEN(n) (1 << (n)) +#define RCC_AHB1LPENR_GPIOALPEN (1 << 0) /* Bit 0: IO port A clock enable during Sleep mode */ +#define RCC_AHB1LPENR_GPIOBLPEN (1 << 1) /* Bit 1: IO port B clock enable during Sleep mode */ +#define RCC_AHB1LPENR_GPIOCLPEN (1 << 2) /* Bit 2: IO port C clock enable during Sleep mode */ +#define RCC_AHB1LPENR_GPIODLPEN (1 << 3) /* Bit 3: IO port D clock enable during Sleep mode */ +#define RCC_AHB1LPENR_GPIOELPEN (1 << 4) /* Bit 4: IO port E clock enable during Sleep mode */ +#define RCC_AHB1LPENR_GPIOFLPEN (1 << 5) /* Bit 5: IO port F clock enable during Sleep mode */ +#define RCC_AHB1LPENR_GPIOGLPEN (1 << 6) /* Bit 6: IO port G clock enable during Sleep mode */ +#define RCC_AHB1LPENR_GPIOHLPEN (1 << 7) /* Bit 7: IO port H clock enable during Sleep mode */ + + +# define RCC_AHB1LPENR_GPIOILPEN (1 << 8) /* Bit 8: IO port I clock enable during Sleep mode */ + +#define RCC_AHB1LPENR_CRCLPEN (1 << 12) /* Bit 12: CRC clock enable during Sleep mode */ +#define RCC_AHB1LPENR_FLITFLPEN (1 << 15) /* Bit 15: Flash interface clock enable during Sleep mode */ +#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 */ + +# define RCC_AHB1LPENR_SRAM3LPEN (1 << 19) /* Bit 19: SRAM 3 interface 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 */ + +# define RCC_AHB1LPENR_DMA2DLPEN (1 << 23) /* Bit 23: DMA2D clock enable during Sleep mode */ +# define RCC_AHB1LPENR_ETHMACLPEN (1 << 25) /* Bit 25: Ethernet MAC clock enable during Sleep mode */ +# define RCC_AHB1LPENR_ETHMACTXLPEN (1 << 26) /* Bit 26: Ethernet Transmission clock enable during Sleep mode */ +# define RCC_AHB1LPENR_ETHMACRXLPEN (1 << 27) /* Bit 27: Ethernet Reception clock enable during Sleep mode */ +# define RCC_AHB1LPENR_ETHMACPTPLPEN (1 << 28) /* Bit 28: Ethernet PTP clock enable during Sleep mode */ + +#define RCC_AHB1LPENR_OTGHSLPEN (1 << 29) /* Bit 29: USB OTG HS clock enable during Sleep mode */ +#define RCC_AHB1LPENR_OTGHSULPILPEN (1 << 30) /* Bit 30: USB OTG HSULPI clock enable during Sleep mode */ + +/* RCC AHB2 low power mode peripheral clock enable register */ + +#define RCC_AHB2LPENR_DCMILPEN (1 << 0) /* Bit 0: Camera interface enable during Sleep mode */ + +# define RCC_AHB2LPENR_CRYPLPEN (1 << 4) /* Bit 4: Cryptographic modules clock enable during Sleep mode */ +# define RCC_AHB2LPENR_HASHLPEN (1 << 5) /* Bit 5: Hash modules clock enable during Sleep mode */ +# define RCC_AHB2LPENR_RNGLPEN (1 << 6) /* Bit 6: Random number generator clock enable during Sleep mode */ + +#define RCC_AHB2LPENR_OTGFLPSEN (1 << 7) /* Bit 7: USB OTG FS clock enable during Sleep mode */ + +/* RCC AHB3 low power mode peripheral clock enable register */ + +#define RCC_AHB3LPENR_FSMCLPEN (1 << 0) /* Bit 0: Flexible static memory controller module clock */ +/* enable during Sleep mode */ + + +/* RCC APB1 low power mode peripheral clock enable register */ + +#define RCC_APB1LPENR_TIM2LPEN (1 << 0) /* Bit 0: TIM2 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM3LPEN (1 << 1) /* Bit 1: TIM3 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM4LPEN (1 << 2) /* Bit 2: TIM4 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM5LPEN (1 << 3) /* Bit 3: TIM5 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM6LPEN (1 << 4) /* Bit 4: TIM6 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM7LPEN (1 << 5) /* Bit 5: TIM7 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM12LPEN (1 << 6) /* Bit 6: TIM12 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM13LPEN (1 << 7) /* Bit 7: TIM13 clock enable during Sleep mode */ +#define RCC_APB1LPENR_TIM14LPEN (1 << 8) /* Bit 8: TIM14 clock enable during Sleep mode */ +#define RCC_APB1LPENR_RTCAPBEN (1 << 10) /* Bit 10: RTC APB clock enable during Sleep mode */ +#define RCC_APB1LPENR_WWDGLPEN (1 << 11) /* Bit 11: Window watchdog clock enable during Sleep mode */ +#define RCC_APB1LPENR_SPI2LPEN (1 << 14) /* Bit 14: SPI2 clock enable during Sleep mode */ +#define RCC_APB1LPENR_SPI3LPEN (1 << 15) /* Bit 15: SPI3 clock enable during Sleep mode */ + + +#define RCC_APB1LPENR_USART2LPEN (1 << 17) /* Bit 17: USART 2 clock enable during Sleep mode */ +#define RCC_APB1LPENR_USART3LPEN (1 << 18) /* Bit 18: USART3 clock enable during Sleep mode */ +#define RCC_APB1LPENR_UART4LPEN (1 << 19) /* Bit 19: UART4 clock enable during Sleep mode */ +#define RCC_APB1LPENR_UART5LPEN (1 << 20) /* Bit 20: UART5 clock enable during Sleep mode */ +#define RCC_APB1LPENR_I2C1LPEN (1 << 21) /* Bit 21: I2C1 clock enable during Sleep mode */ +#define RCC_APB1LPENR_I2C2LPEN (1 << 22) /* Bit 22: I2C2 clock enable during Sleep mode */ +#define RCC_APB1LPENR_I2C3LPEN (1 << 23) /* Bit 23: I2C3 clock enable during Sleep mode */ + + +#define RCC_APB1LPENR_CAN1LPEN (1 << 25) /* Bit 25: CAN 1 clock enable during Sleep mode */ +#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 */ + +# 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 */ + + +/* RCC APB2 low power mode peripheral clock enable register */ + +#define RCC_APB2LPENR_TIM1LPEN (1 << 0) /* Bit 0: TIM1 clock enable during Sleep mode */ +#define RCC_APB2LPENR_TIM8LPEN (1 << 1) /* Bit 1: TIM8 clock enable during Sleep mode */ +#define RCC_APB2LPENR_USART1LPEN (1 << 4) /* Bit 4: USART1 clock enable during Sleep mode */ +#define RCC_APB2LPENR_USART6LPEN (1 << 5) /* Bit 5: USART6 clock enable during Sleep mode */ +#define RCC_APB2LPENR_ADC1LPEN (1 << 8) /* Bit 8: ADC1 clock enable during Sleep mode */ +#define RCC_APB2LPENR_ADC2LPEN (1 << 9) /* Bit 9: ADC2 clock enable during Sleep mode */ +#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 */ + +# define RCC_APB2LPENR_SPI4LPEN (1 << 13) /* Bit 13: SPI4 clock enable during Sleep mode */ + +#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 */ + +# 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 */ + + +# define RCC_APB2LPENR_SAI1LPEN (1 << 22) /* Bit 22: SAI1 clock enable during Sleep mode */ + + +/* Backup domain control register */ + +#define RCC_BDCR_LSEON (1 << 0) /* Bit 0: External Low Speed oscillator enable */ +#define RCC_BDCR_LSERDY (1 << 1) /* Bit 1: External Low Speed oscillator Ready */ +#define RCC_BDCR_LSEBYP (1 << 2) /* Bit 2: External Low Speed oscillator Bypass */ + + +#define RCC_BDCR_RTCSEL_SHIFT (8) /* Bits 9:8: RTC clock source selection */ +#define RCC_BDCR_RTCSEL_MASK (3 << RCC_BDCR_RTCSEL_SHIFT) +# define RCC_BDCR_RTCSEL_NOCLK (0 << RCC_BDCR_RTCSEL_SHIFT) /* 00: No clock */ +# define RCC_BDCR_RTCSEL_LSE (1 << RCC_BDCR_RTCSEL_SHIFT) /* 01: LSE oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_LSI (2 << RCC_BDCR_RTCSEL_SHIFT) /* 10: LSI oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_HSE (3 << RCC_BDCR_RTCSEL_SHIFT) /* 11: HSE oscillator clock divided by 128 used as RTC clock */ + +#define RCC_BDCR_RTCEN (1 << 15) /* Bit 15: RTC clock enable */ + +#define RCC_BDCR_BDRST (1 << 16) /* Bit 16: Backup domain software reset */ + +/* Control/status register */ + +#define RCC_CSR_LSION (1 << 0) /* Bit 0: Internal Low Speed oscillator enable */ +#define RCC_CSR_LSIRDY (1 << 1) /* Bit 1: Internal Low Speed oscillator Ready */ +#define RCC_CSR_RMVF (1 << 24) /* Bit 24: Remove reset flag */ +#define RCC_CSR_BORRSTF (1 << 25) /* Bit 25: BOR reset flag */ +#define RCC_CSR_PINRSTF (1 << 26) /* Bit 26: PIN reset flag */ +#define RCC_CSR_PORRSTF (1 << 27) /* Bit 27: POR/PDR reset flag */ +#define RCC_CSR_SFTRSTF (1 << 28) /* Bit 28: Software Reset flag */ +#define RCC_CSR_IWDGRSTF (1 << 29) /* Bit 29: Independent Watchdog reset flag */ +#define RCC_CSR_WWDGRSTF (1 << 30) /* Bit 30: Window watchdog reset flag */ +#define RCC_CSR_LPWRRSTF (1 << 31) /* Bit 31: Low-Power reset flag */ + +/* Spread spectrum clock generation register */ + +#define RCC_SSCGR_MODPER_SHIFT (0) /* Bit 0-12: Modulation period */ +#define RCC_SSCGR_MODPER_MASK (0x1fff << RCC_SSCGR_MODPER_SHIFT) +# define RCC_SSCGR_MODPER(n) ((n) << RCC_SSCGR_MODPER_SHIFT) +#define RCC_SSCGR_INCSTEP_SHIFT (13) /* Bit 13-27: Incrementation step */ +#define RCC_SSCGR_INCSTEP_MASK (0x7fff << RCC_SSCGR_INCSTEP_SHIFT) +# define RCC_SSCGR_INCSTEP(n) ((n) << RCC_SSCGR_INCSTEP_SHIFT) +#define RCC_SSCGR_SPREADSEL (1 << 30) /* Bit 30: Spread Select */ +#define RCC_SSCGR_SSCGEN (1 << 31) /* Bit 31: Spread spectrum modulation enable */ + +/* PLLI2S configuration register */ + +#define RCC_PLLI2SCFGR_PLLI2SN_SHIFT (6) /* Bits 6-14: PLLI2S N multiplication factor for VCO */ +#define RCC_PLLI2SCFGR_PLLI2SN_MASK (0x1ff << RCC_PLLI2SCFGR_PLLI2SN_SHIFT) +# define RCC_PLLI2SCFGR_PLLI2SN(n) ((n) << RCC_PLLI2SCFGR_PLLI2SN_SHIFT) + + + +# define RCC_PLLI2SCFGR_PLLI2SQ_SHIFT (24) /* Bits 24-27: PLLI2S division factor for SAI1 clock */ +# define RCC_PLLI2SCFGR_PLLI2SQ_MASK (0xf << RCC_PLLI2SCFGR_PLLI2SQ_SHIFT) +# define RCC_PLLI2SCFGR_PLLI2SQ(n) ((n) << RCC_PLLI2SCFGR_PLLI2SQ_SHIFT) + +#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) +# define RCC_PLLI2SCFGR_PLLI2SR(n) ((n) << RCC_PLLI2SCFGR_PLLI2SR_SHIFT) + +/* PLLSAI configuration register */ + + +# define RCC_PLLSAICFGR_PLLSAIN_SHIFT (6) /* Bits 6-14: PLLSAI divider (N) for VCO */ +# define RCC_PLLSAICFGR_PLLSAIN_MASK (0x1ff << RCC_PLLSAICFGR_PLLSAIN_SHIFT) +# define RCC_PLLSAICFGR_PLLSAIN(n) ((n) << RCC_PLLSAICFGR_PLLSAIN_SHIFT) + +# define RCC_PLLSAICFGR_PLLSAIQ_SHIFT (24) /* Bits 24-27: PLLSAI division factor for SAI clock */ +# define RCC_PLLSAICFGR_PLLSAIQ_MASK (0x0F << RCC_PLLSAICFGR_PLLSAIQ_SHIFT) +# define RCC_PLLSAICFGR_PLLSAIQ(n) ((n) << RCC_PLLSAICFGR_PLLSAIQ_SHIFT) + +# define RCC_PLLSAICFGR_PLLSAIR_SHIFT (28) /* Bits 28-30: PLLSAI division factor for LCD clock */ +# define RCC_PLLSAICFGR_PLLSAIR_MASK (7 << RCC_PLLSAICFGR_PLLSAIR_SHIFT) +# define RCC_PLLSAICFGR_PLLSAIR(n) ((n) << RCC_PLLSAICFGR_PLLSAIR_SHIFT) + + +/* Dedicated clocks configuration register */ + + +# define RCC_DCKCFGR_PLLI2SDIVQ_SHIFT (0) /* Bits 0-4: PLLI2S division 1..32 factor for I2S clock */ +# define RCC_DCKCFGR_PLLI2SDIVQ_MASK (0x1f << RCC_DCKCFGR_PLLI2SDIVQ_SHIFT) +# define RCC_DCKCFGR_PLLI2SDIVQ(n) (((n)-1) << RCC_DCKCFGR_PLLI2SDIVQ_SHIFT) +# define RCC_DCKCFGR_PLLSAIDIVQ_SHIFT (8) /* Bits 8-12: PLLSAI division 1..32 factor for SAI clock */ +# define RCC_DCKCFGR_PLLSAIDIVQ_MASK (0x1f << RCC_DCKCFGR_PLLSAIDIVQ_SHIFT) +# define RCC_DCKCFGR_PLLSAIDIVQ(n) (((n)-1) << RCC_DCKCFGR_PLLSAIDIVQ_SHIFT) + +# define RCC_DCKCFGR_PLLSAIDIVR_SHIFT (16) /* Bits 16-17: PLLSAI division factor for LCD_CLK clock */ +# define RCC_DCKCFGR_PLLSAIDIVR_MASK (0x3 << RCC_DCKCFGR_PLLSAIDIVR_SHIFT) +# define RCC_DCKCFGR_PLLSAIDIVR_DIV2 (0 << RCC_DCKCFGR_PLLSAIDIVR_SHIFT) +# define RCC_DCKCFGR_PLLSAIDIVR_DIV4 (1 << RCC_DCKCFGR_PLLSAIDIVR_SHIFT) +# define RCC_DCKCFGR_PLLSAIDIVR_DIV8 (2 << RCC_DCKCFGR_PLLSAIDIVR_SHIFT) +# define RCC_DCKCFGR_PLLSAIDIVR_DIV16 (3 << RCC_DCKCFGR_PLLSAIDIVR_SHIFT) +# define RCC_DCKCFGR_SAI1ASRC_SHIFT (20) /* Bits 20-21: SAI1-A clock source selection */ +# define RCC_DCKCFGR_SAI1ASRC_MASK (0x3 << RCC_DCKCFGR_SAI1ASRC_SHIFT) +# define RCC_DCKCFGR_SAI1ASRC_PLLSAI (0 << RCC_DCKCFGR_SAI1ASRC_SHIFT) +# define RCC_DCKCFGR_SAI1ASRC_PLLI2S (1 << RCC_DCKCFGR_SAI1ASRC_SHIFT) +# define RCC_DCKCFGR_SAI1ASRC_ALTERNATE (2 << RCC_DCKCFGR_SAI1ASRC_SHIFT) +# define RCC_DCKCFGR_SAI1BSRC_SHIFT (22) /* Bits 22-23: SAI1-B clock source selection */ +# define RCC_DCKCFGR_SAI1BSRC_MASK (0x3 << RCC_DCKCFGR_SAI1BSRC_SHIFT) +# define RCC_DCKCFGR_SAI1BSRC_PLLSAI (0 << RCC_DCKCFGR_SAI1BSRC_SHIFT) +# define RCC_DCKCFGR_SAI1BSuRC_PLLI2S (1 << RCC_DCKCFGR_SAI1BSRC_SHIFT) +# define RCC_DCKCFGR_SAI1BSRC_ALTERNATE (2 << RCC_DCKCFGR_SAI1BSRC_SHIFT) + +# define RCC_DCKCFGR_TIMPRE (1 << 24) /* Bit 24: Timer clock prescaler selection */ + +#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_RCC_H */ diff --git a/arch/arm/src/stm32/hardware/stm32f427ax_syscfg.h b/arch/arm/src/stm32/hardware/stm32f427ax_syscfg.h new file mode 100644 index 00000000000..3d35f47f2b5 --- /dev/null +++ b/arch/arm/src/stm32/hardware/stm32f427ax_syscfg.h @@ -0,0 +1,153 @@ +/**************************************************************************** + * arch/arm/src/stm32/hardware/stm32f427xx_syscfg.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_SYSCFG_H +#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_SYSCFG_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Offsets *********************************************************/ + +#define STM32_SYSCFG_MEMRMP_OFFSET 0x0000 /* SYSCFG memory remap register */ +#define STM32_SYSCFG_PMC_OFFSET 0x0004 /* SYSCFG peripheral mode configuration register */ + +#define STM32_SYSCFG_EXTICR_OFFSET(p) (0x0008 + ((p) & 0x000c)) /* Registers are displaced by 4! */ +#define STM32_SYSCFG_EXTICR1_OFFSET 0x0008 /* SYSCFG external interrupt configuration register 1 */ +#define STM32_SYSCFG_EXTICR2_OFFSET 0x000c /* SYSCFG external interrupt configuration register 2 */ +#define STM32_SYSCFG_EXTICR3_OFFSET 0x0010 /* SYSCFG external interrupt configuration register 3 */ +#define STM32_SYSCFG_EXTICR4_OFFSET 0x0014 /* SYSCFG external interrupt configuration register 4 */ + +#define STM32_SYSCFG_CMPCR_OFFSET 0x0020 /* Compensation cell control register */ + +/* Register Addresses *******************************************************/ + +#define STM32_SYSCFG_MEMRMP (STM32_SYSCFG_BASE+STM32_SYSCFG_MEMRMP_OFFSET) +#define STM32_SYSCFG_PMC (STM32_SYSCFG_BASE+STM32_SYSCFG_PMC_OFFSET) + +#define STM32_SYSCFG_EXTICR(p) (STM32_SYSCFG_BASE+STM32_SYSCFG_EXTICR_OFFSET(p)) +#define STM32_SYSCFG_EXTICR1 (STM32_SYSCFG_BASE+STM32_SYSCFG_EXTICR1_OFFSET) +#define STM32_SYSCFG_EXTICR2 (STM32_SYSCFG_BASE+STM32_SYSCFG_EXTICR2_OFFSET) +#define STM32_SYSCFG_EXTICR3 (STM32_SYSCFG_BASE+STM32_SYSCFG_EXTICR3_OFFSET) +#define STM32_SYSCFG_EXTICR4 (STM32_SYSCFG_BASE+STM32_SYSCFG_EXTICR4_OFFSET) + +#define STM32_SYSCFG_CMPCR (STM32_SYSCFG_BASE+STM32_SYSCFG_CMPCR_OFFSET) + +/* Register Bitfield Definitions ********************************************/ + +/* SYSCFG memory remap register */ + +#define SYSCFG_MEMRMP_SHIFT (0) /* Bits 1:0 MEM_MODE: Memory mapping selection */ +#define SYSCFG_MEMRMP_MASK (3 << SYSCFG_MEMRMP_SHIFT) +# define SYSCFG_MEMRMP_FLASH (0 << SYSCFG_MEMRMP_SHIFT) /* 00: Main Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SYSTEM (1 << SYSCFG_MEMRMP_SHIFT) /* 01: System Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_FSMC (2 << SYSCFG_MEMRMP_SHIFT) /* 10: FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SRAM (3 << SYSCFG_MEMRMP_SHIFT) /* 11: Embedded SRAM (112kB) mapped at 0x0000 0000 */ + + +# define SYSCFG_FBMODE_SHIFT (8) /* Bit 8 FB_MODE: Flash Bank mode selection */ +# define SYSCFG_FBMODE_MASK (1 << SYSCFG_FBMODE_SHIFT) +# define SYSCFG_FBMODE_FB12 (0 << SYSCFG_FBMODE_SHIFT) /* 0: Flash Bank 1 is mapped at 0x0800 0000 and*/ + /* Flash Bank 2 is mapped at 0x0810 0000 */ +# define SYSCFG_FBMODE_FB21 (1 << SYSCFG_FBMODE_SHIFT) /* 1: Flash Bank 2 is mapped at 0x0800 0000 and */ + /* Flash Bank 1 is mapped at 0x0810 0000 */ + +#define SYSCFG_SWPFMC_SHIFT (10) /* Bits 10:11 SWP_FMC: FMC memory mapping swap */ +#define SYSCFG_SWPFMC_MASK (3 << SYSCFG_SWPFMC_SHIFT) +# define SYSCFG_SWPFMC_NOSWAP (0 << SYSCFG_SWPFMC_SHIFT) /* 00: No FMC memory mapping swap */ +# define SYSCFG_SWPFMC_SWAP (1 << SYSCFG_SWPFMC_SHIFT) /* 01: SDRAM banks and NAND Bank 2/PCCARD mapping are swapped */ + +/* SYSCFG peripheral mode configuration register */ + +#define SYSCFG_PMC_ADC1DC2 (1 << 16) /* Bit 16: See AN4073 */ +#define SYSCFG_PMC_ADC2DC2 (1 << 17) /* Bit 17: See AN4073 */ +#define SYSCFG_PMC_ADC3DC2 (1 << 18) /* Bit 18: See AN4073 */ + +# define SYSCFG_PMC_MII_RMII_SEL (1 << 23) /* Bit 23: Ethernet PHY interface selection */ + +/* SYSCFG external interrupt configuration register 1-4 */ + +#define SYSCFG_EXTICR_PORTA (0) /* 0000: PA[x] pin */ +#define SYSCFG_EXTICR_PORTB (1) /* 0001: PB[x] pin */ +#define SYSCFG_EXTICR_PORTC (2) /* 0010: PC[x] pin */ +#define SYSCFG_EXTICR_PORTD (3) /* 0011: PD[x] pin */ +#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */ +#define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[C] pin */ +#define SYSCFG_EXTICR_PORTG (6) /* 0110: PG[x] pin */ +#define SYSCFG_EXTICR_PORTH (7) /* 0111: PH[x] pin */ + + +# define SYSCFG_EXTICR_PORTI (8) /* 1000: PI[x] pin */ + +#define SYSCFG_EXTICR_PORT_MASK (15) +#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2) +#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g))) + +#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-3: EXTI 0 configuration */ +#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT) +#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-7: EXTI 1 configuration */ +#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT) +#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-11: EXTI 2 configuration */ +#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT) +#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-15: EXTI 3 configuration */ +#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT) + +#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-3: EXTI 4 configuration */ +#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT) +#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-7: EXTI 5 configuration */ +#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT) +#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-11: EXTI 6 configuration */ +#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT) +#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-15: EXTI 7 configuration */ +#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT) + +#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-3: EXTI 8 configuration */ +#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT) +#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-7: EXTI 9 configuration */ +#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT) +#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-11: EXTI 10 configuration */ +#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT) +#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-15: EXTI 11 configuration */ +#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT) + +#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-3: EXTI 12 configuration */ +#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT) +#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-7: EXTI 13 configuration */ +#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT) +#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-11: EXTI 14 configuration */ +#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT) +#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-15: EXTI 15 configuration */ +#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT) + +/* Compensation cell control register */ + +#define SYSCFG_CMPCR_CMPPD (1 << 0) /* Bit 0: Compensation cell power-down */ +#define SYSCFG_CMPCR_READY (1 << 8) /* Bit 8: Compensation cell ready flag */ + + +#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427XX_SYSCFG_H */ diff --git a/arch/arm/src/stm32/hardware/stm32f427ax_uart.h b/arch/arm/src/stm32/hardware/stm32f427ax_uart.h new file mode 100644 index 00000000000..01413795724 --- /dev/null +++ b/arch/arm/src/stm32/hardware/stm32f427ax_uart.h @@ -0,0 +1,224 @@ +/**************************************************************************** + * arch/arm/src/stm32/hardware/stm32f427xx_uart.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427AX_UART_H +#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427AX_UART_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Offsets *********************************************************/ + +#define STM32_USART_SR_OFFSET 0x0000 /* Status register (32-bits) */ +#define STM32_USART_DR_OFFSET 0x0004 /* Data register (32-bits) */ +#define STM32_USART_BRR_OFFSET 0x0008 /* Baud Rate Register (32-bits) */ +#define STM32_USART_CR1_OFFSET 0x000c /* Control register 1 (32-bits) */ +#define STM32_USART_CR2_OFFSET 0x0010 /* Control register 2 (32-bits) */ +#define STM32_USART_CR3_OFFSET 0x0014 /* Control register 3 (32-bits) */ +#define STM32_USART_GTPR_OFFSET 0x0018 /* Guard time and prescaler register (32-bits) */ + +/* Register Addresses *******************************************************/ + +# define STM32_USART1_SR (STM32_USART1_BASE+STM32_USART_SR_OFFSET) +# define STM32_USART1_DR (STM32_USART1_BASE+STM32_USART_DR_OFFSET) +# define STM32_USART1_BRR (STM32_USART1_BASE+STM32_USART_BRR_OFFSET) +# define STM32_USART1_CR1 (STM32_USART1_BASE+STM32_USART_CR1_OFFSET) +# define STM32_USART1_CR2 (STM32_USART1_BASE+STM32_USART_CR2_OFFSET) +# define STM32_USART1_CR3 (STM32_USART1_BASE+STM32_USART_CR3_OFFSET) +# define STM32_USART1_GTPR (STM32_USART1_BASE+STM32_USART_GTPR_OFFSET) + +# define STM32_USART2_SR (STM32_USART2_BASE+STM32_USART_SR_OFFSET) +# define STM32_USART2_DR (STM32_USART2_BASE+STM32_USART_DR_OFFSET) +# define STM32_USART2_BRR (STM32_USART2_BASE+STM32_USART_BRR_OFFSET) +# define STM32_USART2_CR1 (STM32_USART2_BASE+STM32_USART_CR1_OFFSET) +# define STM32_USART2_CR2 (STM32_USART2_BASE+STM32_USART_CR2_OFFSET) +# define STM32_USART2_CR3 (STM32_USART2_BASE+STM32_USART_CR3_OFFSET) +# define STM32_USART2_GTPR (STM32_USART2_BASE+STM32_USART_GTPR_OFFSET) + + +# define STM32_USART3_SR (STM32_USART3_BASE+STM32_USART_SR_OFFSET) +# define STM32_USART3_DR (STM32_USART3_BASE+STM32_USART_DR_OFFSET) +# define STM32_USART3_BRR (STM32_USART3_BASE+STM32_USART_BRR_OFFSET) +# define STM32_USART3_CR1 (STM32_USART3_BASE+STM32_USART_CR1_OFFSET) +# define STM32_USART3_CR2 (STM32_USART3_BASE+STM32_USART_CR2_OFFSET) +# define STM32_USART3_CR3 (STM32_USART3_BASE+STM32_USART_CR3_OFFSET) +# define STM32_USART3_GTPR (STM32_USART3_BASE+STM32_USART_GTPR_OFFSET) + + +# define STM32_UART4_SR (STM32_UART4_BASE+STM32_USART_SR_OFFSET) +# define STM32_UART4_DR (STM32_UART4_BASE+STM32_USART_DR_OFFSET) +# define STM32_UART4_BRR (STM32_UART4_BASE+STM32_USART_BRR_OFFSET) +# define STM32_UART4_CR1 (STM32_UART4_BASE+STM32_USART_CR1_OFFSET) +# define STM32_UART4_CR2 (STM32_UART4_BASE+STM32_USART_CR2_OFFSET) +# define STM32_UART4_CR3 (STM32_UART4_BASE+STM32_USART_CR3_OFFSET) + + +# define STM32_UART5_SR (STM32_UART5_BASE+STM32_USART_SR_OFFSET) +# define STM32_UART5_DR (STM32_UART5_BASE+STM32_USART_DR_OFFSET) +# define STM32_UART5_BRR (STM32_UART5_BASE+STM32_USART_BRR_OFFSET) +# define STM32_UART5_CR1 (STM32_UART5_BASE+STM32_USART_CR1_OFFSET) +# define STM32_UART5_CR2 (STM32_UART5_BASE+STM32_USART_CR2_OFFSET) +# define STM32_UART5_CR3 (STM32_UART5_BASE+STM32_USART_CR3_OFFSET) + + +# define STM32_USART6_SR (STM32_USART6_BASE+STM32_USART_SR_OFFSET) +# define STM32_USART6_DR (STM32_USART6_BASE+STM32_USART_DR_OFFSET) +# define STM32_USART6_BRR (STM32_USART6_BASE+STM32_USART_BRR_OFFSET) +# define STM32_USART6_CR1 (STM32_USART6_BASE+STM32_USART_CR1_OFFSET) +# define STM32_USART6_CR2 (STM32_USART6_BASE+STM32_USART_CR2_OFFSET) +# define STM32_USART6_CR3 (STM32_USART6_BASE+STM32_USART_CR3_OFFSET) +# define STM32_USART6_GTPR (STM32_USART6_BASE+STM32_USART_GTPR_OFFSET) + + +# 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) + + +# 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) + +/* Register Bitfield Definitions ********************************************/ + +/* Status register */ + +#define USART_SR_PE (1 << 0) /* Bit 0: Parity Error */ +#define USART_SR_FE (1 << 1) /* Bit 1: Framing Error */ +#define USART_SR_NE (1 << 2) /* Bit 2: Noise Error Flag */ +#define USART_SR_ORE (1 << 3) /* Bit 3: OverRun Error */ +#define USART_SR_IDLE (1 << 4) /* Bit 4: IDLE line detected */ +#define USART_SR_RXNE (1 << 5) /* Bit 5: Read Data Register Not Empty */ +#define USART_SR_TC (1 << 6) /* Bit 6: Transmission Complete */ +#define USART_SR_TXE (1 << 7) /* Bit 7: Transmit Data Register Empty */ +#define USART_SR_LBD (1 << 8) /* Bit 8: LIN Break Detection Flag */ +#define USART_SR_CTS (1 << 9) /* Bit 9: CTS Flag */ + +#define USART_SR_ALLBITS (0x03ff) +#define USART_SR_CLRBITS (USART_SR_CTS|USART_SR_LBD) /* Cleared by SW write to SR */ + +/* Data register */ + +#define USART_DR_SHIFT (0) /* Bits 8:0: Data value */ +#define USART_DR_MASK (0xff << USART_DR_SHIFT) + +/* Baud Rate Register */ + +#define USART_BRR_FRAC_SHIFT (0) /* Bits 3-0: fraction of USARTDIV */ +#define USART_BRR_FRAC_MASK (0x0f << USART_BRR_FRAC_SHIFT) +#define USART_BRR_MANT_SHIFT (4) /* Bits 15-4: mantissa of USARTDIV */ +#define USART_BRR_MANT_MASK (0x0fff << USART_BRR_MANT_SHIFT) + +/* Control register 1 */ + +#define USART_CR1_SBK (1 << 0) /* Bit 0: Send Break */ +#define USART_CR1_RWU (1 << 1) /* Bit 1: Receiver wakeup */ +#define USART_CR1_RE (1 << 2) /* Bit 2: Receiver Enable */ +#define USART_CR1_TE (1 << 3) /* Bit 3: Transmitter Enable */ +#define USART_CR1_IDLEIE (1 << 4) /* Bit 4: IDLE Interrupt Enable */ +#define USART_CR1_RXNEIE (1 << 5) /* Bit 5: RXNE Interrupt Enable */ +#define USART_CR1_TCIE (1 << 6) /* Bit 6: Transmission Complete Interrupt Enable */ +#define USART_CR1_TXEIE (1 << 7) /* Bit 7: TXE Interrupt Enable */ +#define USART_CR1_PEIE (1 << 8) /* Bit 8: PE Interrupt Enable */ +#define USART_CR1_PS (1 << 9) /* Bit 9: Parity Selection */ +#define USART_CR1_PCE (1 << 10) /* Bit 10: Parity Control Enable */ +#define USART_CR1_WAKE (1 << 11) /* Bit 11: Wakeup method */ +#define USART_CR1_M (1 << 12) /* Bit 12: word length */ +#define USART_CR1_UE (1 << 13) /* Bit 13: USART Enable */ +#define USART_CR1_OVER8 (1 << 15) /* Bit 15: Oversampling mode */ + +#define USART_CR1_ALLINTS (USART_CR1_IDLEIE|USART_CR1_RXNEIE|USART_CR1_TCIE|USART_CR1_PEIE) + +/* Control register 2 */ + +#define USART_CR2_ADD_SHIFT (0) /* Bits 3-0: Address of the USART node */ +#define USART_CR2_ADD_MASK (0x0f << USART_CR2_ADD_SHIFT) +#define USART_CR2_LBDL (1 << 5) /* Bit 5: LIN Break Detection Length */ +#define USART_CR2_LBDIE (1 << 6) /* Bit 6: LIN Break Detection Interrupt Enable */ +#define USART_CR2_LBCL (1 << 8) /* Bit 8: Last Bit Clock pulse */ +#define USART_CR2_CPHA (1 << 9) /* Bit 9: Clock Phase */ +#define USART_CR2_CPOL (1 << 10) /* Bit 10: Clock Polarity */ +#define USART_CR2_CLKEN (1 << 11) /* Bit 11: Clock Enable */ +#define USART_CR2_STOP_SHIFT (12) /* Bits 13-12: STOP bits */ +#define USART_CR2_STOP_MASK (3 << USART_CR2_STOP_SHIFT) +# define USART_CR2_STOP1 (0 << USART_CR2_STOP_SHIFT) /* 00: 1 Stop bit */ +# define USART_CR2_STOP0p5 (1 << USART_CR2_STOP_SHIFT) /* 01: 0.5 Stop bit */ +# define USART_CR2_STOP2 (2 << USART_CR2_STOP_SHIFT) /* 10: 2 Stop bits */ +# define USART_CR2_STOP1p5 (3 << USART_CR2_STOP_SHIFT) /* 11: 1.5 Stop bit */ + +#define USART_CR2_LINEN (1 << 14) /* Bit 14: LIN mode enable */ + +/* Control register 3 */ + +#define USART_CR3_EIE (1 << 0) /* Bit 0: Error Interrupt Enable */ +#define USART_CR3_IREN (1 << 1) /* Bit 1: IrDA mode Enable */ +#define USART_CR3_IRLP (1 << 2) /* Bit 2: IrDA Low-Power */ +#define USART_CR3_HDSEL (1 << 3) /* Bit 3: Half-Duplex Selection */ +#define USART_CR3_NACK (1 << 4) /* Bit 4: Smartcard NACK enable */ +#define USART_CR3_SCEN (1 << 5) /* Bit 5: Smartcard mode enable */ +#define USART_CR3_DMAR (1 << 6) /* Bit 6: DMA Enable Receiver */ +#define USART_CR3_DMAT (1 << 7) /* Bit 7: DMA Enable Transmitter */ +#define USART_CR3_RTSE (1 << 8) /* Bit 8: RTS Enable */ +#define USART_CR3_CTSE (1 << 9) /* Bit 9: CTS Enable */ +#define USART_CR3_CTSIE (1 << 10) /* Bit 10: CTS Interrupt Enable */ +#define USART_CR3_ONEBIT (1 << 11) /* Bit 11: One sample bit method enable */ + +/* Guard time and prescaler register */ + +#define USART_GTPR_PSC_SHIFT (0) /* Bits 0-7: Prescaler value */ +#define USART_GTPR_PSC_MASK (0xff << USART_GTPR_PSC_SHIFT) +#define USART_GTPR_GT_SHIFT (8) /* Bits 8-15: Guard time value */ +#define USART_GTPR_GT_MASK (0xff << USART_GTPR_GT_SHIFT) + +/* Compatibility definitions ************************************************/ + +/* F3 Transmit/Read registers */ + +#define STM32_USART_RDR_OFFSET STM32_USART_DR_OFFSET /* Receive data register */ +#define STM32_USART_TDR_OFFSET STM32_USART_DR_OFFSET /* Transmit data register */ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Public Functions Prototypes + ****************************************************************************/ + +#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32F427AX_UART_H */ diff --git a/arch/arm/src/stm32/stm32_gpio.h b/arch/arm/src/stm32/stm32_gpio.h index f5c468f7b8e..2aebd07499a 100644 --- a/arch/arm/src/stm32/stm32_gpio.h +++ b/arch/arm/src/stm32/stm32_gpio.h @@ -46,7 +46,11 @@ defined(CONFIG_STM32_STM32F37XX) # include "hardware/stm32f30xxx_gpio.h" #elif defined(CONFIG_STM32_STM32F4XXX) -# include "hardware/stm32f40xxx_gpio.h" +# if defined(CONFIG_STM32_STM32F427A) +# include "hardware/stm32f427ax_gpio.h" +# else +# include "hardware/stm32f40xxx_gpio.h" +# endif #elif defined(CONFIG_STM32_STM32G4XXX) # include "hardware/stm32g4xxxx_gpio.h" #else diff --git a/arch/arm/src/stm32/stm32_rcc.h b/arch/arm/src/stm32/stm32_rcc.h index bb9e3e9f245..0a5629fe227 100644 --- a/arch/arm/src/stm32/stm32_rcc.h +++ b/arch/arm/src/stm32/stm32_rcc.h @@ -43,7 +43,11 @@ #elif defined(CONFIG_STM32_STM32F37XX) # include "hardware/stm32f37xxx_rcc.h" #elif defined(CONFIG_STM32_STM32F4XXX) -# include "hardware/stm32f40xxx_rcc.h" +# if defined(CONFIG_STM32_STM32F427A) +# include "hardware/stm32f427ax_rcc.h" +# else +# include "hardware/stm32f40xxx_rcc.h" +# endif #elif defined(CONFIG_STM32_STM32G4XXX) # include "hardware/stm32g4xxxx_rcc.h" #else diff --git a/arch/arm/src/stm32/stm32_syscfg.h b/arch/arm/src/stm32/stm32_syscfg.h index 28fb24a39cb..55198dddfa8 100644 --- a/arch/arm/src/stm32/stm32_syscfg.h +++ b/arch/arm/src/stm32/stm32_syscfg.h @@ -39,7 +39,11 @@ #elif defined(CONFIG_STM32_STM32F37XX) # include "hardware/stm32f37xxx_syscfg.h" #elif defined(CONFIG_STM32_STM32F4XXX) -# include "hardware/stm32f40xxx_syscfg.h" +# if defined(CONFIG_STM32_STM32F427A) +# include "hardware/stm32f427ax_syscfg.h" +# else +# include "hardware/stm32f40xxx_syscfg.h" +# endif #elif defined(CONFIG_STM32_STM32G4XXX) # include "hardware/stm32g4xxxx_syscfg.h" #endif diff --git a/arch/arm/src/stm32/stm32_uart.h b/arch/arm/src/stm32/stm32_uart.h index c27c19e4e2b..0e5397ad5e0 100644 --- a/arch/arm/src/stm32/stm32_uart.h +++ b/arch/arm/src/stm32/stm32_uart.h @@ -40,7 +40,11 @@ defined(CONFIG_STM32_STM32F37XX) # include "hardware/stm32f30xxx_uart.h" #elif defined(CONFIG_STM32_STM32F4XXX) -# include "hardware/stm32f40xxx_uart.h" +# if defined(CONFIG_STM32_STM32F427A) +# include "hardware/stm32f427ax_uart.h" +# else +# include "hardware/stm32f40xxx_uart.h" +# endif #elif defined(CONFIG_STM32_STM32G4XXX) # include "hardware/stm32g4xxxx_uart.h" #else diff --git a/arch/arm/src/stm32/stm32f427ax_rcc.c b/arch/arm/src/stm32/stm32f427ax_rcc.c new file mode 100644 index 00000000000..6c7714c42ac --- /dev/null +++ b/arch/arm/src/stm32/stm32f427ax_rcc.c @@ -0,0 +1,1014 @@ +/**************************************************************************** + * arch/arm/src/stm32/stm32f427ax_rcc.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "chip.h" +#include "stm32_pwr.h" +#include "itm_syslog.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Allow up to 100 milliseconds for the high speed clock to become ready. + * that is a very long delay, but if the clock does not become ready we are + * hosed anyway. Normally this is very fast, but I have seen at least one + * board that required this long, long timeout for the HSE to be ready. + */ + +#define HSERDY_TIMEOUT (100 * CONFIG_BOARD_LOOPSPERMSEC) + +/* Same for HSI */ + +#define HSIRDY_TIMEOUT HSERDY_TIMEOUT + +/* HSE divisor to yield ~1MHz RTC clock */ + +#define HSE_DIVISOR (STM32_HSE_FREQUENCY + 500000) / 1000000 + +/* The FLASH latency depends on the system clock, and voltage input + * of the microcontroller. The following macros calculate the correct + * wait cycles for every STM32_SYSCLK_FREQUENCY & BOARD_STM32F4_VDD + * combination. BOARD_STM32F4_VDD is defined in mV. + */ + +#ifndef BOARD_STM32F4_VDD +# define BOARD_STM32F4_VDD 3300 +#endif + +#if (BOARD_STM32F4_VDD <= 2100) +# if (STM32_SYSCLK_FREQUENCY <= 20000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_0 +# elif (STM32_SYSCLK_FREQUENCY <= 40000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_1 +# elif (STM32_SYSCLK_FREQUENCY <= 60000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_2 +# elif (STM32_SYSCLK_FREQUENCY <= 800000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_3 +# elif (STM32_SYSCLK_FREQUENCY <= 100000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_4 +# elif (STM32_SYSCLK_FREQUENCY <= 120000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_5 +# elif (STM32_SYSCLK_FREQUENCY <= 140000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_6 +# elif (STM32_SYSCLK_FREQUENCY <= 160000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_7 +# elif (STM32_SYSCLK_FREQUENCY <= 168000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_8 +# else +# error "STM32_SYSCLK_FREQUENCY is out of range!" +# endif +#elif (BOARD_STM32F4_VDD <= 2400) +# if (STM32_SYSCLK_FREQUENCY <= 22000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_0 +# elif (STM32_SYSCLK_FREQUENCY <= 44000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_1 +# elif (STM32_SYSCLK_FREQUENCY <= 66000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_2 +# elif (STM32_SYSCLK_FREQUENCY <= 880000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_3 +# elif (STM32_SYSCLK_FREQUENCY <= 110000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_4 +# elif (STM32_SYSCLK_FREQUENCY <= 132000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_5 +# elif (STM32_SYSCLK_FREQUENCY <= 154000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_6 +# elif (STM32_SYSCLK_FREQUENCY <= 168000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_7 +# elif (STM32_SYSCLK_FREQUENCY <= 176000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_7 +# elif (STM32_SYSCLK_FREQUENCY <= 180000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_8 +# else +# error "STM32_SYSCLK_FREQUENCY is out of range!" +# endif +#elif (BOARD_STM32F4_VDD <= 2700) +# if (STM32_SYSCLK_FREQUENCY <= 24000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_0 +# elif (STM32_SYSCLK_FREQUENCY <= 48000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_1 +# elif (STM32_SYSCLK_FREQUENCY <= 72000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_2 +# elif (STM32_SYSCLK_FREQUENCY <= 960000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_3 +# elif (STM32_SYSCLK_FREQUENCY <= 120000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_4 +# elif (STM32_SYSCLK_FREQUENCY <= 144000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_5 +# elif (STM32_SYSCLK_FREQUENCY <= 168000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_6 +# elif (STM32_SYSCLK_FREQUENCY <= 180000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_7 +# else +# error "STM32_SYSCLK_FREQUENCY is out of range!" +# endif +#elif (BOARD_STM32F4_VDD <= 3600) +# if (STM32_SYSCLK_FREQUENCY <= 30000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_0 +# elif (STM32_SYSCLK_FREQUENCY <= 60000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_1 +# elif (STM32_SYSCLK_FREQUENCY <= 90000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_2 +# elif (STM32_SYSCLK_FREQUENCY <= 120000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_3 +# elif (STM32_SYSCLK_FREQUENCY <= 150000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_4 +# elif (STM32_SYSCLK_FREQUENCY <= 168000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_5 +# elif (STM32_SYSCLK_FREQUENCY <= 180000000) +# define FLASH_ACR_LATENCY_SETTING FLASH_ACR_LATENCY_5 +# else +# error "STM32_SYSCLK_FREQUENCY is out of range!" +# endif +#else +# error "BOARD_STM32F4_VDD is out of range!" +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: rcc_reset + * + * Description: + * Reset the RCC clock configuration to the default reset state + * + ****************************************************************************/ + +static inline void rcc_reset(void) +{ + uint32_t regval; + + /* Enable the Internal High Speed clock (HSI) */ + + regval = getreg32(STM32_RCC_CR); + regval |= RCC_CR_HSION; + putreg32(regval, STM32_RCC_CR); + + /* Reset CFGR register */ + + putreg32(0x00000000, STM32_RCC_CFGR); + + /* Reset HSEON, CSSON and PLLON bits */ + + regval = getreg32(STM32_RCC_CR); + regval &= ~(RCC_CR_HSEON | RCC_CR_CSSON | RCC_CR_PLLON); + putreg32(regval, STM32_RCC_CR); + + /* Reset PLLCFGR register to reset default */ + + putreg32(RCC_PLLCFG_RESET, STM32_RCC_PLLCFG); + + /* Reset HSEBYP bit */ + + regval = getreg32(STM32_RCC_CR); + regval &= ~RCC_CR_HSEBYP; + putreg32(regval, STM32_RCC_CR); + + /* Disable all interrupts */ + + putreg32(0x00000000, STM32_RCC_CIR); +} + +/**************************************************************************** + * Name: rcc_enableahb1 + * + * Description: + * Enable selected AHB1 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb1(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB1ENR register to enabled the + * selected AHB1 peripherals. + */ + + regval = getreg32(STM32_RCC_AHB1ENR); + + /* Enable GPIOA, GPIOB, .... GPIOI */ + +#if STM32_NGPIO_PORTS > 0 + regval |= (RCC_AHB1ENR_GPIOAEN +#if STM32_NGPIO_PORTS > 1 + | RCC_AHB1ENR_GPIOBEN +#endif +#if STM32_NGPIO_PORTS > 2 + | RCC_AHB1ENR_GPIOCEN +#endif +#if STM32_NGPIO_PORTS > 3 + | RCC_AHB1ENR_GPIODEN +#endif +#if STM32_NGPIO_PORTS > 4 + | RCC_AHB1ENR_GPIOEEN +#endif +#if STM32_NGPIO_PORTS > 5 + | RCC_AHB1ENR_GPIOFEN +#endif +#if STM32_NGPIO_PORTS > 6 + | RCC_AHB1ENR_GPIOGEN +#endif +#if STM32_NGPIO_PORTS > 7 + | RCC_AHB1ENR_GPIOHEN +#endif +#if STM32_NGPIO_PORTS > 8 + | RCC_AHB1ENR_GPIOIEN +#endif +#if STM32_NGPIO_PORTS > 9 + | RCC_AHB1ENR_GPIOJEN +#endif +#if STM32_NGPIO_PORTS > 10 + | RCC_AHB1ENR_GPIOKEN +#endif + ); +#endif + +#ifdef CONFIG_STM32_CRC + /* CRC clock enable */ + + regval |= RCC_AHB1ENR_CRCEN; +#endif + +#ifdef CONFIG_STM32_BKPSRAM + /* Backup SRAM clock enable */ + + regval |= RCC_AHB1ENR_BKPSRAMEN; +#endif + +#ifdef CONFIG_STM32_CCMDATARAM + /* CCM data RAM clock enable */ + + regval |= RCC_AHB1ENR_CCMDATARAMEN; +#endif + +#ifdef CONFIG_STM32_DMA1 + /* DMA 1 clock enable */ + + regval |= RCC_AHB1ENR_DMA1EN; +#endif + +#ifdef CONFIG_STM32_DMA2 + /* DMA 2 clock enable */ + + regval |= RCC_AHB1ENR_DMA2EN; +#endif + +#ifdef CONFIG_STM32_ETHMAC + /* Ethernet MAC clocking */ + + regval |= (RCC_AHB1ENR_ETHMACEN | RCC_AHB1ENR_ETHMACTXEN + | RCC_AHB1ENR_ETHMACRXEN); + +#ifdef CONFIG_STM32_ETH_PTP + /* Precision Time Protocol (PTP) */ + + regval |= RCC_AHB1ENR_ETHMACPTPEN; + +#endif +#endif + +#ifdef CONFIG_STM32_OTGHS +#ifdef BOARD_ENABLE_USBOTG_HSULPI + /* Enable clocking for USB OTG HS and external PHY */ + + regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); +#else + /* Enable only clocking for USB OTG HS */ + + regval |= RCC_AHB1ENR_OTGHSEN; +#endif +#endif /* CONFIG_STM32_OTGHS */ + +#ifdef CONFIG_STM32_DMA2D + /* DMA2D clock */ + + regval |= RCC_AHB1ENR_DMA2DEN; +#endif + + putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableahb2 + * + * Description: + * Enable selected AHB2 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb2(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB2ENR register to enabled the + * selected AHB2 peripherals. + */ + + regval = getreg32(STM32_RCC_AHB2ENR); + +#ifdef CONFIG_STM32_DCMI + /* Camera interface enable */ + + regval |= RCC_AHB2ENR_DCMIEN; +#endif + +#ifdef CONFIG_STM32_CRYP + /* Cryptographic modules clock enable */ + + regval |= RCC_AHB2ENR_CRYPEN; +#endif + +#ifdef CONFIG_STM32_HASH + /* Hash modules clock enable */ + + regval |= RCC_AHB2ENR_HASHEN; +#endif + +#ifdef CONFIG_STM32_RNG + /* Random number generator clock enable */ + + regval |= RCC_AHB2ENR_RNGEN; +#endif + +#ifdef CONFIG_STM32_OTGFS + /* USB OTG FS clock enable */ + + regval |= RCC_AHB2ENR_OTGFSEN; +#endif + + putreg32(regval, STM32_RCC_AHB2ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableahb3 + * + * Description: + * Enable selected AHB3 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb3(void) +{ +#ifdef CONFIG_STM32_FSMC + uint32_t regval; + + /* Set the appropriate bits in the AHB3ENR register to enabled the + * selected AHB3 peripherals. + */ + + regval = getreg32(STM32_RCC_AHB3ENR); + + /* Flexible static memory controller module clock enable */ + + regval |= RCC_AHB3ENR_FSMCEN; + + putreg32(regval, STM32_RCC_AHB3ENR); /* Enable peripherals */ +#endif +} + +/**************************************************************************** + * Name: rcc_enableapb1 + * + * Description: + * Enable selected APB1 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableapb1(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the APB1ENR register to enabled the + * selected APB1 peripherals. + */ + + regval = getreg32(STM32_RCC_APB1ENR); + +#ifdef CONFIG_STM32_TIM2 + /* TIM2 clock enable */ + + regval |= RCC_APB1ENR_TIM2EN; +#endif + +#ifdef CONFIG_STM32_TIM3 + /* TIM3 clock enable */ + + regval |= RCC_APB1ENR_TIM3EN; +#endif + +#ifdef CONFIG_STM32_TIM4 + /* TIM4 clock enable */ + + regval |= RCC_APB1ENR_TIM4EN; +#endif + +#ifdef CONFIG_STM32_TIM5 + /* TIM5 clock enable */ + + regval |= RCC_APB1ENR_TIM5EN; +#endif + +#ifdef CONFIG_STM32_TIM6 + /* TIM6 clock enable */ + + regval |= RCC_APB1ENR_TIM6EN; +#endif + +#ifdef CONFIG_STM32_TIM7 + /* TIM7 clock enable */ + + regval |= RCC_APB1ENR_TIM7EN; +#endif + +#ifdef CONFIG_STM32_TIM12 + /* TIM12 clock enable */ + + regval |= RCC_APB1ENR_TIM12EN; +#endif + +#ifdef CONFIG_STM32_TIM13 + /* TIM13 clock enable */ + + regval |= RCC_APB1ENR_TIM13EN; +#endif + +#ifdef CONFIG_STM32_TIM14 + /* TIM14 clock enable */ + + regval |= RCC_APB1ENR_TIM14EN; +#endif + +#ifdef CONFIG_STM32_WWDG + /* Window watchdog clock enable */ + + regval |= RCC_APB1ENR_WWDGEN; +#endif + +#ifdef CONFIG_STM32_SPI2 + /* SPI2 clock enable */ + + regval |= RCC_APB1ENR_SPI2EN; +#endif + +#ifdef CONFIG_STM32_SPI3 + /* SPI3 clock enable */ + + regval |= RCC_APB1ENR_SPI3EN; +#endif + +#ifdef CONFIG_STM32_USART2 + /* USART 2 clock enable */ + + regval |= RCC_APB1ENR_USART2EN; +#endif + +#ifdef CONFIG_STM32_USART3 + /* USART3 clock enable */ + + regval |= RCC_APB1ENR_USART3EN; +#endif + +#ifdef CONFIG_STM32_UART4 + /* UART4 clock enable */ + + regval |= RCC_APB1ENR_UART4EN; +#endif + +#ifdef CONFIG_STM32_UART5 + /* UART5 clock enable */ + + regval |= RCC_APB1ENR_UART5EN; +#endif + +#ifdef CONFIG_STM32_I2C1 + /* I2C1 clock enable */ + + regval |= RCC_APB1ENR_I2C1EN; +#endif + +#ifdef CONFIG_STM32_I2C2 + /* I2C2 clock enable */ + + regval |= RCC_APB1ENR_I2C2EN; +#endif + +#ifdef CONFIG_STM32_I2C3 + /* I2C3 clock enable */ + + regval |= RCC_APB1ENR_I2C3EN; +#endif + +#ifdef CONFIG_STM32_CAN1 + /* CAN 1 clock enable */ + + regval |= RCC_APB1ENR_CAN1EN; +#endif + +#ifdef CONFIG_STM32_CAN2 + /* CAN2 clock enable. NOTE: CAN2 needs CAN1 clock as well. */ + + regval |= (RCC_APB1ENR_CAN1EN | RCC_APB1ENR_CAN2EN); +#endif + + /* Power interface clock enable. The PWR block is always enabled so that + * we can set the internal voltage regulator for maximum performance. + */ + + regval |= RCC_APB1ENR_PWREN; + +#if defined (CONFIG_STM32_DAC1) + /* DAC1 interface clock enable */ + + regval |= RCC_APB1ENR_DAC1EN; +#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 */ +} + +/**************************************************************************** + * Name: rcc_enableapb2 + * + * Description: + * Enable selected APB2 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableapb2(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the APB2ENR register to enabled the + * selected APB2 peripherals. + */ + + regval = getreg32(STM32_RCC_APB2ENR); + +#ifdef CONFIG_STM32_TIM1 + /* TIM1 clock enable */ + + regval |= RCC_APB2ENR_TIM1EN; +#endif + +#ifdef CONFIG_STM32_TIM8 + /* TIM8 clock enable */ + + regval |= RCC_APB2ENR_TIM8EN; +#endif + +#ifdef CONFIG_STM32_USART1 + /* USART1 clock enable */ + + regval |= RCC_APB2ENR_USART1EN; +#endif + +#ifdef CONFIG_STM32_USART6 + /* USART6 clock enable */ + + regval |= RCC_APB2ENR_USART6EN; +#endif + +#ifdef CONFIG_STM32_ADC1 + /* ADC1 clock enable */ + + regval |= RCC_APB2ENR_ADC1EN; +#endif + +#ifdef CONFIG_STM32_ADC2 + /* ADC2 clock enable */ + + regval |= RCC_APB2ENR_ADC2EN; +#endif + +#ifdef CONFIG_STM32_ADC3 + /* ADC3 clock enable */ + + regval |= RCC_APB2ENR_ADC3EN; +#endif + +#ifdef CONFIG_STM32_SDIO + /* SDIO clock enable */ + + regval |= RCC_APB2ENR_SDIOEN; +#endif + +#ifdef CONFIG_STM32_SPI1 + /* SPI1 clock enable */ + + 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 */ + + regval |= RCC_APB2ENR_SYSCFGEN; +#endif + +#ifdef CONFIG_STM32_TIM9 + /* TIM9 clock enable */ + + regval |= RCC_APB2ENR_TIM9EN; +#endif + +#ifdef CONFIG_STM32_TIM10 + /* TIM10 clock enable */ + + regval |= RCC_APB2ENR_TIM10EN; +#endif + +#ifdef CONFIG_STM32_TIM11 + /* TIM11 clock enable */ + + 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 + +#ifdef CONFIG_STM32_LTDC + /* LTDC clock enable */ + + regval |= RCC_APB2ENR_LTDCEN; +#endif + + putreg32(regval, STM32_RCC_APB2ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: stm32_stdclockconfig + * + * Description: + * Called to change to new clock based on settings in board.h + * + * NOTE: This logic would need to be extended if you need to select low- + * power clocking modes! + ****************************************************************************/ + +#ifndef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG +static void stm32_stdclockconfig(void) +{ + uint32_t regval; + volatile int32_t timeout; + +#ifdef STM32_BOARD_USEHSI + + /* Wait until the HSI is ready (or until a timeout elapsed) */ + + for (timeout = HSIRDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the HSIRDY flag is the set in the CR */ + + if ((getreg32(STM32_RCC_CR) & RCC_CR_HSIRDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + +#else /* if STM32_BOARD_USEHSE */ + /* Enable External High-Speed Clock (HSE) */ + +#ifdef STM32_RCC_CR_HSEBYP + /* Bypass HSE oscillator when using an external oscillator module + * Do NOT define STM32_RCC_CR_HSEBYP when using a crystal with HSE + */ + + regval = getreg32(STM32_RCC_CR); + regval |= RCC_CR_HSEBYP; + putreg32(regval, STM32_RCC_CR); +#endif + + regval = getreg32(STM32_RCC_CR); + regval |= RCC_CR_HSEON; /* Enable HSE */ + putreg32(regval, STM32_RCC_CR); + + /* Wait until the HSE is ready (or until a timeout elapsed) */ + + for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the HSERDY flag is the set in the CR */ + + if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } +#endif + + /* Check for a timeout. If this timeout occurs, then we are hosed. We + * have no real back-up plan, although the following logic makes it look + * as though we do. + */ + + if (timeout > 0) + { + /* Select regulator voltage output Scale 1 mode to support system + * frequencies up to 168 MHz. + */ + + regval = getreg32(STM32_RCC_APB1ENR); + regval |= RCC_APB1ENR_PWREN; + putreg32(regval, STM32_RCC_APB1ENR); + + regval = getreg32(STM32_PWR_CR); + + regval &= ~PWR_CR_VOS_MASK; + regval |= PWR_CR_VOS_SCALE_1; + + putreg32(regval, STM32_PWR_CR); + + /* Set the HCLK source/divider */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_HPRE_MASK; + regval |= STM32_RCC_CFGR_HPRE; + putreg32(regval, STM32_RCC_CFGR); + + /* Set the PCLK2 divider */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE2_MASK; + regval |= STM32_RCC_CFGR_PPRE2; + putreg32(regval, STM32_RCC_CFGR); + + /* Set the PCLK1 divider */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE1_MASK; + regval |= STM32_RCC_CFGR_PPRE1; + putreg32(regval, STM32_RCC_CFGR); + +#ifdef CONFIG_STM32_RTC_HSECLOCK + /* Set the RTC clock divisor */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_RTCPRE_MASK; + regval |= RCC_CFGR_RTCPRE(HSE_DIVISOR); + putreg32(regval, STM32_RCC_CFGR); +#endif + + /* Set the PLL dividers and multipliers to configure the main PLL */ + + regval = (STM32_PLLCFG_PLLM | STM32_PLLCFG_PLLN | STM32_PLLCFG_PLLP + | STM32_PLLCFG_PLLQ +#ifdef STM32_BOARD_USEHSI + | RCC_PLLCFG_PLLSRC_HSI +#else /* if STM32_BOARD_USEHSE */ + | RCC_PLLCFG_PLLSRC_HSE +#endif +#if defined(STM32_PLLCFG_PLLR) + | STM32_PLLCFG_PLLR +#endif + ); + putreg32(regval, STM32_RCC_PLLCFG); + + /* Enable the main PLL */ + + regval = getreg32(STM32_RCC_CR); + regval |= RCC_CR_PLLON; + putreg32(regval, STM32_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0) + { + } + +#if defined(CONFIG_STM32_HAVE_OVERDRIVE) && (STM32_SYSCLK_FREQUENCY > 168000000) + + /* Enable the Over-drive to extend the clock frequency to 180 MHz */ + + regval = getreg32(STM32_PWR_CR); + regval |= PWR_CR_ODEN; + putreg32(regval, STM32_PWR_CR); + while ((getreg32(STM32_PWR_CSR) & PWR_CSR_ODRDY) == 0) + { + } + + regval = getreg32(STM32_PWR_CR); + regval |= PWR_CR_ODSWEN; + putreg32(regval, STM32_PWR_CR); + while ((getreg32(STM32_PWR_CSR) & PWR_CSR_ODSWRDY) == 0) + { + } +#endif + + /* Enable FLASH prefetch, instruction cache, data cache, + * and set FLASH wait states. + */ + + regval = (FLASH_ACR_LATENCY_SETTING +#ifdef CONFIG_STM32_FLASH_ICACHE + | FLASH_ACR_ICEN +#endif +#ifdef CONFIG_STM32_FLASH_DCACHE + | FLASH_ACR_DCEN +#endif +#if defined(CONFIG_STM32_FLASH_PREFETCH) && (BOARD_STM32F4_VDD > 2100) + | FLASH_ACR_PRFTEN +#endif + ); + putreg32(regval, STM32_FLASH_ACR); + + /* Select the main PLL as system clock source */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_SW_MASK; + regval |= RCC_CFGR_SW_PLL; + putreg32(regval, STM32_RCC_CFGR); + + /* Wait until the PLL source is used as the system clock source */ + + while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) + != RCC_CFGR_SWS_PLL) + { + } + +#if defined(CONFIG_STM32_LTDC) || defined(CONFIG_STM32_SAIPLL) + + /* Configure PLLSAI */ + + regval = getreg32(STM32_RCC_PLLSAICFGR); + + regval &= ~(RCC_PLLSAICFGR_PLLSAIN_MASK + | RCC_PLLSAICFGR_PLLSAIQ_MASK + | RCC_PLLSAICFGR_PLLSAIR_MASK); + regval |= (STM32_RCC_PLLSAICFGR_PLLSAIN + | STM32_RCC_PLLSAICFGR_PLLSAIQ + | STM32_RCC_PLLSAICFGR_PLLSAIR); + + putreg32(regval, STM32_RCC_PLLSAICFGR); + + regval = getreg32(STM32_RCC_DCKCFGR); + + + regval &= ~RCC_DCKCFGR_PLLSAIDIVR_MASK; + regval |= STM32_RCC_DCKCFGR_PLLSAIDIVR; + + putreg32(regval, STM32_RCC_DCKCFGR); + + /* Enable PLLSAI */ + + regval = getreg32(STM32_RCC_CR); + regval |= RCC_CR_PLLSAION; + putreg32(regval, STM32_RCC_CR); + + /* Wait until the PLLSAI is ready */ + + while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLSAIRDY) == 0) + { + } +#endif + +#if defined(CONFIG_STM32_I2SPLL) + + /* Configure PLLI2S */ + + regval = getreg32(STM32_RCC_PLLI2SCFGR); + + regval &= ~(RCC_PLLI2SCFGR_PLLI2SN_MASK + | RCC_PLLI2SCFGR_PLLI2SQ_MASK + | RCC_PLLI2SCFGR_PLLI2SR_MASK); + regval |= (STM32_RCC_PLLI2SCFGR_PLLI2SN + | STM32_RCC_PLLI2SCFGR_PLLI2SQ + | STM32_RCC_PLLI2SCFGR_PLLI2SR); + + putreg32(regval, STM32_RCC_PLLI2SCFGR); + +# if defined(STM32_RCC_DCKCFGR2) + + regval = getreg32(STM32_RCC_DCKCFGR2); + + putreg32(regval, STM32_RCC_DCKCFGR2); +# endif + + /* Enable PLLI2S */ + + regval = getreg32(STM32_RCC_CR); + regval |= RCC_CR_PLLI2SON; + putreg32(regval, STM32_RCC_CR); + + /* Wait until the PLLI2S is ready */ + + while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLI2SRDY) == 0) + { + } +#endif + +#if defined(CONFIG_STM32_IWDG) || defined(CONFIG_STM32_RTC_LSICLOCK) + /* Low speed internal clock source LSI */ + + stm32_rcc_enablelsi(); +#endif + +#if defined(CONFIG_STM32_RTC_LSECLOCK) + /* Low speed external clock source LSE + * + * TODO: There is another case where the LSE needs to + * be enabled: if the MCO1 pin selects LSE as source. + */ + + stm32_rcc_enablelse(); +#endif + } +} +#endif + +/**************************************************************************** + * Name: efm32_itm_syslog + * + * Description: + * Enable Serial wire output pin, configure debug clocking, and enable + * ITM syslog support. + * + ****************************************************************************/ + +#ifdef CONFIG_ARMV7M_ITMSYSLOG +static inline void rcc_itm_syslog(void) +{ + /* Enable SWO output */ + + modifyreg32(STM32_DBGMCU_CR, DBGMCU_CR_TRACEMODE_MASK, DBGMCU_CR_ASYNCH | + DBGMCU_CR_TRACEIOEN); +} +#else +# define rcc_itm_syslog() +#endif + +/**************************************************************************** + * Name: rcc_enableperiphals + ****************************************************************************/ + +static inline void rcc_enableperipherals(void) +{ + rcc_enableahb1(); + rcc_enableahb2(); + rcc_enableahb3(); + rcc_enableapb1(); + rcc_enableapb2(); + rcc_itm_syslog(); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ diff --git a/boards/Kconfig b/boards/Kconfig index 041cdb4231d..dab6aa62e0c 100644 --- a/boards/Kconfig +++ b/boards/Kconfig @@ -2825,6 +2825,7 @@ config ARCH_BOARD default "spresense" if ARCH_BOARD_SPRESENSE default "xx3803" if ARCH_BOARD_XX3803 default "xx3823" if ARCH_BOARD_XX3823 + default "stm32f427a_Cubus" if ARCH_BOARD_STM32F427A_CUBUS comment "Common Board Options" @@ -3625,6 +3626,9 @@ endif if ARCH_BOARD_TLSR8278ADK80D source "boards/arm/tlsr82/tlsr8278adk80d/Kconfig" endif +if ARCH_BOARD_STM32F427A_CUBUS +source "boards/arm/stm32/stm32f427a_Cubus/Kconfig" +endif comment "Board-Common Options" diff --git a/boards/arm/stm32/stm32f427a_Cubus/Kconfig b/boards/arm/stm32/stm32f427a_Cubus/Kconfig new file mode 100644 index 00000000000..5abc1bb5d3e --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/Kconfig @@ -0,0 +1,7 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if ARCH_BOARD_STM32F427A_CUBUS +endif diff --git a/boards/arm/stm32/stm32f427a_Cubus/README.txt b/boards/arm/stm32/stm32f427a_Cubus/README.txt new file mode 100644 index 00000000000..09b47f1b5fc --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/README.txt @@ -0,0 +1,2427 @@ +README +====== + +This README discusses issues unique to NuttX configurations for the +STMicro STM32F4Discovery development board featuring the STM32F407VGT6 +MCU. The STM32F407VGT6 is a 168MHz Cortex-M4 operation with 1Mbit Flash +memory and 128kbytes. The board features: + + - On-board ST-LINK/V2 for programming and debugging, + - LIS302DL, ST MEMS motion sensor, 3-axis digital output accelerometer, + - MP45DT02, ST MEMS audio sensor, omni-directional digital microphone, + - CS43L22, audio DAC with integrated class D speaker driver, + - Four user LEDs and two push-buttons, + - USB OTG FS with micro-AB connector, and + - Easy access to most MCU pins. + +Refer to http://www.st.com/internet/evalboard/product/252419.jsp for +further information about this board. + +NOTE: This port was developed on the original board, order code +STM32F4DISCOVERY. That board has been replaced with the new order code +STM32F407VG-DISC1. The new version of the board differs in at least these +ways: + + - The ST-LINK/V2 has been updated to ST-LINK/V2-A on STM32F407G-DISC1 + with a Virtual Com port and Mass storage. + - LIS3DSH ST MEMS 3-axis accelerometer + +Contents +======== + + - LEDs + - RGB LED Driver + - PWM + - UARTs + - Timer Inputs/Outputs + - Nintendo Wii Nunchuck + - Quadrature Encoder + - FPU + - STM32F4DIS-BB + - RTC DS1307 + - SSD1289 + - UG-2864AMBAG01 / UG-2864HSWEG01 + - NiceRF LoRa (2AD66-LoRa V2) + - Ethernet SPI Module ENC28J60 + - HCI UART + - STM32F4Discovery-specific Configuration Options + - BASIC + - Testing LLVM LIBC++ with NuttX + - Configurations + +LEDs +==== + +The STM32F4Discovery board has four LEDs; green, orange, red and blue on the +board. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is +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 + green orange red blue + ------------------- ----------------------- ------- ------- ------- ------ + 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 + ** The normal state is LED3 ON and LED1 faintly glowing. This faint glow + is because of timer interrupts that result in the LED being illuminated + on a small proportion of the time. +*** LED2 may also flicker normally if signals are processed. + +RGB LED Driver +============== + +Alan Carvalho de Assis has used the STM32F4-Discovery to drive an RGB LED +using PWM output. The external RGB connected this way: + + R = TIM1 CH1 on PE9 + G = TIM2 CH2 on PA1 + B = TIM3 CH3 on PB0 + +The RGB LED driver that uses PWM to control the red, green, and blue color +components can be enabled with the following configuration settings: + + +CONFIG_RGBLED=y + + +CONFIG_PWM + + +CONFIG_STM32_TIM1 + +CONFIG_STM32_TIM2 + +CONFIG_STM32_TIM3 + +CONFIG_STM32_TIM1_PWM=y + +CONFIG_STM32_TIM1_MODE=0 + +CONFIG_STM32_TIM1_CHANNEL=1 + +CONFIG_STM32_TIM1_CHMODE=0 + +CONFIG_STM32_TIM2_PWM=y + +CONFIG_STM32_TIM2_MODE=0 + +CONFIG_STM32_TIM2_CHANNEL=2 + +CONFIG_STM32_TIM2_CHMODE=0 + +CONFIG_STM32_TIM3_PWM=y + +CONFIG_STM32_TIM3_MODE=0 + +CONFIG_STM32_TIM3_CHANNEL=3 + +CONFIG_STM32_TIM3_CHMODE=0 + +PWM +=== + +The STM32F4Discovery has no real on-board PWM devices, but the board can be +configured to output a pulse train using TIM4 CH2 on PD3. This pin is +available next to the audio jack. + +UARTs +===== + +UART/USART PINS +--------------- + +USART1 + CK PA8 + CTS PA11* + RTS PA12* + RX PA10*, PB7 + TX PA9*, PB6* +USART2 + CK PA4*, PD7 + CTS PA0*, PD3 + RTS PA1, PD4* + RX PA3, PD6 + TX PA2, PD5* +USART3 + CK PB12, PC12*, PD10 + CTS PB13, PD11 + RTS PB14, PD12* + RX PB11, PC11, PD9 + TX PB10*, PC10*, PD8 +UART4 + RX PA1, PC11 + TX PA0*, PC10* +UART5 + RX PD2 + TX PC12* +USART6 + CK PC8, PG7** + CTS PG13**, PG15** + RTS PG12**, PG8** + RX PC7*, PG9** + TX PC6, PG14** + + * Indicates pins that have other on-board functions and should be used only + with care (See table 5 in the STM32F4Discovery User Guide). The rest are + free I/O pins. +** Port G pins are not supported by the MCU + +Default USART/UART Configuration +-------------------------------- + +USART2 is enabled in most configurations (see */defconfig). RX and TX are +configured on pins PA3 and PA2, respectively (see include/board.h). + +These pins selections, however, conflict with Ethernet pin usage on the +STM32F4DIS-BB base board. The STM32F4DIS-BB base board provides RS-232 +drivers and a DB9 connector for USART6. USART6 is the preferred serial +console for use with the STM32F4DIS-BB. + +Timer Inputs/Outputs +==================== + +TIM1 + CH1 PA8, PE9 + CH2 PA9*, PE11 + CH3 PA10*, PE13 + CH4 PA11*, PE14 +TIM2 + CH1 PA0*, PA15, PA5* + CH2 PA1, PB3* + CH3 PA2, PB10* + CH4 PA3, PB11 +TIM3 + CH1 PA6*, PB4, PC6 + CH2 PA7*, PB5, PC7* + CH3 PB0, PC8 + CH4 PB1, PC9 +TIM4 + CH1 PB6*, PD12* + CH2 PB7, PD13* + CH3 PB8, PD14* + CH4 PB9*, PD15* +TIM5 + CH1 PA0*, PH10** + CH2 PA1, PH11** + CH3 PA2, PH12** + CH4 PA3, PI0 +TIM8 + CH1 PC6, PI5 + CH2 PC7*, PI6 + CH3 PC8, PI7 + CH4 PC9, PI2 +TIM9 + CH1 PA2, PE5 + CH2 PA3, PE6 +TIM10 + CH1 PB8, PF6 +TIM11 + CH1 PB9*, PF7 +TIM12 + CH1 PH6**, PB14 + CH2 PC15, PH9** +TIM13 + CH1 PA6*, PF8 +TIM14 + CH1 PA7*, PF9 + + * Indicates pins that have other on-board functions and should be used only + with care (See table 5 in the STM32F4Discovery User Guide). The rest are + free I/O pins. +** Port H pins are not supported by the MCU + +Nintendo Wii Nunchuck: +====================== + + There is a driver on NuttX to support Nintendo Wii Nunchuck Joystick. If you + want to use it please select these options: + + - Enable the I2C1 at System Type -> STM32 Peripheral Support, it will enable: + + CONFIG_STM32_I2C1=y + + - Enable to Custom board/driver initialization at RTOS Features -> RTOS hooks + + CONFIG_BOARD_LATE_INITIALIZE=y + + - Enable the I2C Driver Support at Device Drivers, it will enable this symbol: + + CONFIG_I2C=y + + - Nintendo Wii Nunchuck Joystick at Device Drivers -> [*] Input Device Support + + CONFIG_INPUT=y + CONFIG_INPUT_NUNCHUCK=y + + - Enable the Nunchuck joystick example at Application Configuration -> Examples + + CONFIG_EXAMPLES_NUNCHUCK=y + CONFIG_EXAMPLES_NUNCHUCK_DEVNAME="/dev/nunchuck0" + + You need to connect GND and +3.3V pins from Nunchuck connector to GND and 3V + of stm32f4discovery respectively (Nunchuck also can work connected to 5V, but + I don't recommend it). Connect I2C Clock from Nunchuck to SCK (PB6) and the + I2C Data to SDA (PB9). + +Quadrature Encoder: +=================== + + The nsh configuration has been used to test the Quadrture Encoder + (QEncoder, QE) with the following modifications to the configuration + file: + + - These setting enable support for the common QEncode upper half driver: + + CONFIG_BOARD_LATE_INITIALIZE=y + + CONFIG_SENSORS=y + CONFIG_SENSORS_QENCODER=y + + - The timer 2 needs to be enabled: + + CONFIG_STM32_TIM2=y + + - This is a board setting that selected timer 2 for use with the + quadrature encode: + + CONFIG_STM32F4DISCO_QETIMER=2 + + - These settings enable the STM32 Quadrature encoder on timer 2: + + CONFIG_STM32_TIM2_QE=y + CONFIG_STM32_TIM4_QECLKOUT=2800000 + CONFIG_STM32_QENCODER_FILTER=y + CONFIG_STM32_QENCODER_SAMPLE_EVENT_6=y + CONFIG_STM32_QENCODER_SAMPLE_FDTS_4=y + + - These settings enable the test case at apps/examples/qencoder: + + CONFIG_EXAMPLES_QENCODER=y + CONFIG_EXAMPLES_QENCODER_DELAY=100 + CONFIG_EXAMPLES_QENCODER_DEVPATH="/dev/qe0" + + In this configuration, the QEncoder inputs will be on the TIM2 inputs of + PA15 and PA1 (CH1 and CH2 respectively). + + You can also use QEncoder with other timers, but keep in mind that only TIM2 + and TIM5 are 32bits timers, all other timers are 16-bit then the QE counter + will overflow after 65535. + + If TIM4 is selected, then PB6 and PB7 will be used for CH1 and CH2. + If TIM8 is selected, then PC6 and PI5 will be used for CH1 and CH2. + +FPU +=== + +FPU Configuration Options +------------------------- + +There are two version of the FPU support built into the STM32 port. + +1. Non-Lazy Floating Point Register Save + + In this configuration floating point register save and restore is + implemented on interrupt entry and return, respectively. In this + case, you may use floating point operations for interrupt handling + logic if necessary. This FPU behavior logic is enabled by default + with: + + CONFIG_ARCH_FPU=y + +2. Lazy Floating Point Register Save. + + An alternative implementation only saves and restores FPU registers only + on context switches. This means: (1) floating point registers are not + stored on each context switch and, hence, possibly better interrupt + performance. But, (2) since floating point registers are not saved, + you cannot use floating point operations within interrupt handlers. + + This logic can be enabled by simply adding the following to your .config + file: + + CONFIG_ARCH_FPU=y + +STM32F4DIS-BB +============= + +On-board PIO usage: + + ---------- ------------- ------------------------------ + PIO SIGNAL FUNCTION + ---------- ------------- ------------------------------ + PB11 TXEN LAN8720 + PB12 TXD0 + PB13 TXD1 + PC4 RXD0/MODE0 + PC5 RXD1/MODE1 + PA7 RXDR/PHYAD0 + PA2 MDIO + PC1 MDC + PA1 NINT/REFCLK0 + PE2 NRST + ---------- ------------- ------------------------------ + PC6 D2 DCMI + PC7 D3 + PE0 D4 + PE1 D5 + PE4 D6 + PB6 D7 + PE5 D8 + PE6 D9 + PA6 PCLK + PA4 HS + PB7 VS + PD6 PWR_EN + PD12 RST + PB9 SDA + PB8 SCL + ---------- ------------- ------------------------------ + USART6_TX T1IN SP3232EEY-L + USART6_RX T2OUT + ---------- ------------- ------------------------------ + PB15 NCD MicroSD + PC9 DAT1 + PC8 DAT0 + PC12 CLK + PD2 CMD + PC11 CD/DAT3 + PC10 DAT2 + ---------- ------------- ------------------------------ + +RTC DS1307 +========== + +It is possible to use a low cost extern DS1307 RTC to keep date and time +always updated. These DS1307 RTC modules come with a 3V button battery, then +even when the board is turned OFF the Date/Time registers keep running. + +You can connect the module this way (STM32F4Discovery to DS1307 board): GND +to GND; 5V to VCC; PB9 to SDA; PB6 to SCL. In the NuttX menuconfig you need +to enable these options: + +System Type ---> + STM32 Peripheral Support ---> + [*] I2C1 + +Device Drivers ---> + Timer Driver Support ---> + [*] RTC Driver Support ---> + -*- Date/Time RTC Support + [*] External RTC Support + [*] DS130x/DS323x RTC Driver + Maxim Integrated RTC (DS1307) ---> + (100000) DS1307/DS323x I2C frequency + +Application Configuration ---> + NSH Library ---> + Disable Individual commands ---> + [ ] Disable date ( <-- Deselect ) + +It is also a good idea to enable the DEBUG to RTC initially, you will see: + +ABCDF +stm32_ds1307_init: Initialize I2C1 +stm32_ds1307_init: Bind the DS1307 RTC driver to I2C1 +rtc_dumptime: Returning: +rtc_dumptime: tm_sec: 00000039 +rtc_dumptime: tm_min: 00000001 +rtc_dumptime: tm_hour: 00000009 +rtc_dumptime: tm_mday: 00000016 +rtc_dumptime: tm_mon: 00000008 +rtc_dumptime: tm_year: 00000077 + +NuttShell (NSH) +nsh> date +Sep 22 09:01:58 2019 + +SSD1289 +======= + +I purchased an LCD display on eBay from China. The LCD is 320x240 RGB565 and +is based on an SSD1289 LCD controller and an XPT2046 touch IC. The pin out +from the 2x16 connect on the LCD is labelled as follows: + +LCD CONNECTOR: SSD1289 MPU INTERFACE PINS: + + +------+------+ DEN I Display enable pin +1 | GND | 3V3 | 2 VSYNC I Frame synchronization signal + +------+------+ HSYNC I Line synchronization signal +3 | D1 | D0 | 4 DOTCLK I Dot clock and OSC source + +------+------+ DC I Data or command +5 | D3 | D2 | 6 E (~RD) I Enable/Read strobe + +------+------+ R (~WR) I Read/Write strobe +7 | D5 | D4 | 8 D0-D17 IO For parallel mode, 8/9/16/18 bit interface + +------+------+ WSYNC O RAM write synchronizatin output +9 | D7 | D6 | 10 ~RES I System reset + +------+------+ ~CS I Chip select of serial interface +11 | D9 | D8 | 12 SCK I Clock of serial interface + +------+------+ SDI I Data input in serial mode +13 | D11 | D10 | 14 SDO O Data output in serial moce + +------+------+ +15 | D13 | D12 | 16 + +------+------+ +17 | D15 | D14 | 18 + +------+------+ +19 | RS | CS | 20 + +------+------+ +21 | RD | WR | 22 NOTES: + +------+------+ +23 |BL_CNT|RESET | 24 BL_CNT is the PWM backlight level control. + +------+------+ +25 |TP_RQ |TP_S0 | 26 These pins are for the touch panel: TP_REQ + +------+------+ TP_S0, TP_SI, TP_SCX, and TP_CS +27 | NC |TP_SI | 28 + +------+------+ +29 | NC |TP_SCX| 30 + +------+------+ +31 | NC |TP_CS | 32 + +------+------+ + +MAPPING TO STM32 F4: + + ---------------- -------------- ---------------------------------- + STM32 FUNCTION LCD PIN STM32F4Discovery PIN + ---------------- -------------- ---------------------------------- + FSMC_D0 D0 pin 4 PD14 P1 pin 46 Conflict (Note 1) + FSMC_D1 D1 pin 3 PD15 P1 pin 47 Conflict (Note 2) + FSMC_D2 D2 pin 6 PD0 P2 pin 36 Free I/O + FSMC_D3 D3 pin 5 PD1 P2 pin 33 Free I/O + FSMC_D4 D4 pin 8 PE7 P1 pin 25 Free I/O + FSMC_D5 D5 pin 7 PE8 P1 pin 26 Free I/O + FSMC_D6 D6 pin 10 PE9 P1 pin 27 Free I/O + FSMC_D7 D7 pin 9 PE10 P1 pin 28 Free I/O + FSMC_D8 D8 pin 12 PE11 P1 pin 29 Free I/O + FSMC_D9 D9 pin 11 PE12 P1 pin 30 Free I/O + FSMC_D10 D10 pin 14 PE13 P1 pin 31 Free I/O + FSMC_D11 D11 pin 13 PE14 P1 pin 32 Free I/O + FSMC_D12 D12 pin 16 PE15 P1 pin 33 Free I/O + FSMC_D13 D13 pin 15 PD8 P1 pin 40 Free I/O + FSMC_D14 D14 pin 18 PD9 P1 pin 41 Free I/O + FSMC_D15 D15 pin 17 PD10 P1 pin 42 Free I/O + FSMC_A16 RS pin 19 PD11 P1 pin 27 Free I/O + FSMC_NE1 ~CS pin 10 PD7 P2 pin 27 Free I/O + FSMC_NWE ~WR pin 22 PD5 P2 pin 29 Conflict (Note 3) + FSMC_NOE ~RD pin 21 PD4 P2 pin 32 Conflict (Note 4) + PC6 RESET pin 24 PC6 P2 pin 47 Free I/O + Timer output BL_CNT pin 23 (to be determined) + ---------------- -------------- ---------------------------------- + + 1 Used for the RED LED + 2 Used for the BLUE LED + 3 Used for the RED LED and for OTG FS Overcurrent. It may be okay to use + for the parallel interface if PC0 is held high (or floating). PC0 enables + the STMPS2141STR IC power switch that drives the OTG FS host VBUS. + 4 Also the reset pin for the CS43L22 audio Codec. + +NOTE: The configuration to test this LCD configuration is available at +boards/arm/stm32/stm32f4discovery/nxlines. As of this writing, I have not seen the +LCD working so I probably have some things wrong. + +I might need to use a bit-banging interface. Below is the pin configuration +of a similar LCD to support a (write-only), bit banging interface: + + LCD PIN BOARD CONNECTION + LEDA 5V + VCC 5V + RD 3.3V + GND GND + DB0-7 Port C pins configured as outputs + DB8-15 Port A pins configured as outputs + RS Pin configured as output + WR Pin configured as output + CS Pin configured as output + RSET Pin configured as output + +The following summarize the bit banging operations: + + /* Rese the LCD */ + void Reset(void) + { + Set RSET output + delay + Clear RSET output + delay + Set RSET output + } + + /* Write 16-bits of whatever */ + void Write16(uint8_t ms, uint8_t ls) + { + Set port A to ms + Set port B to ls + + Clear WR pin + Set WR pin + } + + /* Set the index register to an LCD register address */ + void Index(uint8_t address) + { + Clear RS + Write16(0, address); + } + + /* Write data to the LCD register or GRAM memory */ + void WriteData(uin16_t data) + { + Set RS + Write16(data >> 8, data & 0xff); + } + + /* Write to a register */ + void WriteRegister(uint8_t address, uint16_t data) + { + Index(address); + WriteData(data); + } + +UG-2864AMBAG01 / UG-2864HSWEG01 +=============================== + +I purchased an OLED display on eBay. The OLED is 128x64 monochrome and +is based on an UG-2864AMBAG01 OLED controller. The OLED can run in either +parallel or SPI mode. I am using SPI mode. In SPI mode, the OLED is +write only so the driver keeps a 128*64/8 = 1KB framebuffer to remember +the display contents: + +Here is how I have the OLED connected. But you can change this with the +settings in include/board.h and src/stm324fdiscovery.h. Connector +pinout for the UG-2864AMBAG01 is specific to the theO.net display board +that I am using: + + --------------------------+---------------------------------------------- + Connector CON10 J1: | STM32F4Discovery + --------------+-----------+---------------------------------------------- + CON10 J1: | CON20 J2: | P1/P2: + --------------+-----------+---------------------------------------------- + 1 3v3 | 3,4 3v3 | P2 3V + 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) + 5 /CS | 7 /CS | P2 PB7 (Arbitrary selection) + 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection) + 9 LED+ (N/C) | ----- | ----- + 2 5V Vcc | 1,2 Vcc | P2 5V + 4 DI | 18 D1/SI | P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1 (1)) + 6 SCLK | 19 D0/SCL | P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1 (1)) + 8 LED- (N/C) | ----- | ------ + 10 GND | 20 GND | P2 GND + --------------+-----------+---------------------------------------------- + (1) Required because of on-board MEMS + ------------------------------------------------------------------------- + +Darcy Gong recently added support for the UG-2864HSWEG01 OLED which is also +an option with this configuration. I have little technical information about +the UG-2864HSWEG01 interface (see boards/arm/stm32/stm32f4discovery/src/up_ug2864hsweg01.c). + +NiceRF LoRa (2AD66-LoRa V2) +=========================== + +It is possible to wire an external LoRa module to STM32F4Discovery board. + +First connect the GND and VCC (to 3.3V) and then connect the SCK label to PA5, +connect the MISO to PA6, connect the MOSI to PA7, connect the NSS to PD8, +connect DIO0 to PD0 and finally connect NRESET to PD4. + +Ethernet SPI Module ENC28J60 +============================ + +You can use an external Ethernet SPI Module ENC28J60 with STM32F4Discovery board. + +First connect the GND and VCC (to 3.3V). Note: according with ENC28J60 datasheet +the Operating Voltage should be between 3.1V to 3.6V, but STM32F4Discover only +supply 3.0V. You can modify your board to supply 3.3V: just remove the D3 diode +and short-circuit the board pads where it was soldered). + +Connect the SCK label to PA5, connect the SO to PA6, connect the SI to PA7, +connect the CS to PA4, connect RST to PE1 and finally connect INT to PE4. + +The next step is to enable the ENC28J60 in the menuconfig ("make menuconfig") +and the necessary Network configuration, you can use the +boards/arm/stm32/fire-stm32v2/configs/nsh/defconfig as reference. + +HCI UART +======== + +BT860 +----- + + I have been testing with the DVK_BT960_SA board via J10 as follows: + + DVK_BT860-SA J10 STM32F4 Discovery P1 + pin 1 GND P1 pin 49 + pin 2 Module_RTS_O USART3_CTS PB13, P1 pin 37 + pin 3 N/C + pin 4 Module_RX_I USART3_TXD PB10, P1 pin 34 + pin 5 Module_TX_O USART3_RX PB11, P1 pin 35 + pin 6 Module_CTS_I USART3_RTS PB14, P1 pin 38 + + Due to conflicts, USART3 many not be used if Ethernet is enabled with + the STM32F4DIS-BB base board: + + PB-11 conflicts with Ethernet TXEN + PB-13 conflicts with Ethernet TXD1 + + If you need to use the HCI uart with Ethernet, then you will need to + configure a new U[S]ART and/or modify the pin selections in + include/board.h. + +CC2564 +------ + + [To be provided] + + One confusing thing compared with the BT860 is in the naming of the pins + at the 4-pin RS232 TTL interface: The BT860 uses BT860-centric naming, + the Rx pin is for BT860 receive and needs to connect with the STM32 Tx + pin, the Tx pin is for BT860 transmit an needs to be connected with the + STM32 Rx pin, etc. The CC2564, on the hand, uses host-centric naming so + that the CC2564 Rx pin connects to the STM32 Rx pin, Tx to Tx pin, etc. + +Troubleshooting +--------------- + + First you should enable CONFIG_DEBUG_WIRELESS_ERR, WARN, and INFO options + so that you can see what the driver is doing. + + The bring-up problems that I encountered mostly involved setting up the + 4-wire UART interface: Remember to cross Rx/Tx and RTS/CTS. The active + state for RTS and CTS is low. For bringup of the BT860, I used a Seleae + logic analyzer connected to the Tx, Rx, RTS, and CTS pins. When the + BT860 is working correctly you would see this: + + 1. All signals high initially, + 2. When NuttX starts, RTS goes low + 3. The BT860 sees RTS go low and responds by setting CTS low after a + delay. This is when it selects between USB and UART. + 4. After another delay, the STM32 sends the 4 Tx bytes. + 5. The BT860 responds with 3 bytes. + 6. If successful, additional commands and responses follow. + + Some of these steps may be different for other HCI UARTs. Steps 4-5 are + the reset sequence. the 4 Tx bytes comes from the code in the function + hci_initialize() in the file wireless/bluetooth/bt_hcicore.c: + + /* Send HCI_RESET */ + + bt_hci_cmd_send(BT_HCI_OP_RESET, NULL); + + The code is actually working one command ahead. It has already queued up + the reset command and is requesting the HCI UART device features while the + reset command is being sent: + + ret = bt_hci_cmd_send_sync(BT_HCI_OP_READ_LOCAL_FEATURES, NULL, &rsp); + if (ret < 0) + { + wlerr("ERROR: bt_hci_cmd_send_sync failed: %d\n", ret); + return ret; + } + + A common failure is to see a timeout error (-116) due to a Tx flow control + failure (CTS is high). There is no timeout on the first command, the + timeout actually occurs on the second command in bt_hci_cmd_send_sync(): + + do + { + /* The timed wait could also be awakened by a signal */ + + ret = nxsem_timedwait(&sync_sem, &abstime); + } + while (ret == -EINTR); + + The above times out and generates the 116 error. + + In the case of the timeout, the second command is stuck in the message queue + is never processed because the Tx thread is waiting for the BT_HCI_OP_RESET + command to complete. It is blocked in hci_tx_thread() kernel thread. + + The Tx occurs on a kernel thread. The Tx send of the first command causes + the hci_tx_kthread() to block. It waits here until what the HCI UART + receives the command and responses with the command complete event: + + /* Wait until ncmd > 0 */ + + do + { + ret = nxsem_wait(&g_btdev.ncmd_sem); + } + while (ret == -EINTR); + + bt_hci_cmd_send() will block on the first BT_HCI_OP_RESET until until it + gets the 3-byte event (BT_EVT) that indicates that the command was + completed and provides the command status. See the function + hci_command_complete() where it posts g_btdev.ncmd_sem. + + g_btdev.ncmd = 1; + nxsem_post(&g_btdev.ncmd_sem); + + You can see such a hange in the wireless debug output + + bt_hci_cmd_send: opcode 0c03 len 3 <<< BT_HCI_OP_RESET command is queue + hci_tx_kthread: Sending command 0c03 buf 20002a40 to driver <<< Sent to driver from the Tx thread + hciuart_write: config 801d924 buffer 20002760 buflen 4 <<< Goes to STM32 HCI UART driver + + bt_hci_cmd_send_sync: opcode 1003 len 3 <<< next command is queued. + hciuart_copytotxfifo: txhead 1 txtail 4 nbytes 1 <<< One byte of first command written to Tx HR + hciuart_enableints: CR1 000020ac CR2 00000301 <<< Tx interrupts enabled + +!!!! No Tx interrupts, probably because of Tx flow control (CTS is high) !!! + + hci_initialize: ERROR: bt_hci_cmd_send_sync failed: -116 <<< Times out on second message + +STM32F4Discovery-specific Configuration Options +=============================================== + + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: + + CONFIG_ARCH=arm + + CONFIG_ARCH_family - For use in C code: + + CONFIG_ARCH_ARM=y + + CONFIG_ARCH_architecture - For use in C code: + + CONFIG_ARCH_CORTEXM4=y + + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + + CONFIG_ARCH_CHIP=stm32 + + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: + + CONFIG_ARCH_CHIP_STM32F407VG=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 boards/ subdirectory and + hence, the board that supports the particular chip or SoC. + + CONFIG_ARCH_BOARD=STM32F4Discovery (for the STM32F4Discovery development board) + + CONFIG_ARCH_BOARD_name - For use in C code + + CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y + + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops + + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) + + CONFIG_RAM_SIZE - Describes the installed RAM + + CONFIG_RAM_SIZE=0x00010000 (64Kb) + + CONFIG_RAM_START - The start address of installed RAM + + CONFIG_RAM_START=0x20000000 + + CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP + + CONFIG_ARCH_FPU - The STM32F4Discovery supports a floating point unit (FPU) + + CONFIG_ARCH_FPU=y + + 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_STACKDUMP - Do stack dumps after assertions + + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + + 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 + + Timer devices may be used for different purposes. One special purpose is + to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn + is defined (as above) then the following may also be defined to indicate that + the timer is intended to be used for pulsed output modulation, ADC conversion, + or DAC conversion. Note that ADC/DAC require two definition: Not only do you have + 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 + + 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} + + 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. + + JTAG Enable settings (by default only SW-DP is 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 + + STM32F4Discovery specific device driver settings + + 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 + + STM32F4Discovery CAN Configuration + + CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or + CONFIG_STM32_CAN2 must also be defined) + CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default + Standard 11-bit IDs. + 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_STM32_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 + is defined. + CONFIG_STM32_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 + is defined. + CONFIG_STM32_CAN_TSEG1 - The number of CAN time quanta in segment 1. + Default: 6 + CONFIG_STM32_CAN_TSEG2 - the number of CAN time quanta in segment 2. + Default: 7 + CONFIG_STM32_CAN_REGDEBUG - If CONFIG_DEBUG_FEATURES is set, this will generate an + dump of all CAN registers. + + STM32F4Discovery SPI Configuration + + 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_SPIx_DMA - Use DMA to improve SPIx transfer performance. + Cannot be used with CONFIG_STM32_SPI_INTERRUPT. + + STM32F4Discovery DMA Configuration + + CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO + and CONFIG_STM32_DMA2. + CONFIG_STM32_SDIO_PRI - Select SDIO interrupt priority. Default: 128 + CONFIG_STM32_SDIO_DMAPRIO - Select SDIO DMA interrupt priority. + Default: Medium + CONFIG_STM32_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default: + 4-bit transfer mode. + + STM32 USB OTG FS Host Driver Support + + Pre-requisites + + CONFIG_USBDEV - Enable USB device support + CONFIG_USBHOST - Enable USB host support + CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block + CONFIG_STM32_SYSCFG - Needed + CONFIG_SCHED_WORKQUEUE - Worker thread support is required + + Options: + + CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words. + Default 128 (512 bytes) + CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO + in 32-bit words. Default 96 (384 bytes) + CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit + words. Default 96 (384 bytes) + CONFIG_STM32_OTGFS_DESCSIZE - Maximum size of a descriptor. Default: 128 + CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever + want to do that? + CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access + debug. Depends on CONFIG_DEBUG_FEATURES. + CONFIG_STM32_USBHOST_PKTDUMP - Dump all incoming and outgoing USB + packets. Depends on CONFIG_DEBUG_FEATURES. + +BASIC +===== + I have used the stm32f4discovery/nsh configuration to test Michael Haardt's + BASIC interpreter that you can find at apps/interpreters/bas. + + Bas is an interpreter for the classic dialect of the programming language + BASIC. It is pretty compatible to typical BASIC interpreters of the 1980s, + unlike some other UNIX BASIC interpreters, that implement a different + syntax, breaking compatibility to existing programs. Bas offers many ANSI + BASIC statements for structured programming, such as procedures, local + variables and various loop types. Further there are matrix operations, + automatic LIST indentation and many statements and functions found in + specific classic dialects. Line numbers are not required. + + There is also a test suite for the interpreter that can be found at + apps/examples/bastest. + + Configuration + ------------- + Below are the recommended configuration changes to use BAS with the + stm32f4discovery/nsh configuration: + + Dependencies: + CONFIG_LIBC_EXECFUNCS=y : exec*() functions are required + CONFIG_LIBM=y : Some floating point library is required + CONFIG_LIBC_FLOATINGPOINT=y : Floating point printing support is required + CONFIG_LIBC_TMPDIR="/tmp" : Writable temporary files needed for some commands + CONFIG_FS_FAT=y : With FAT you create a RAMDISK at /tmp + CONFIG_FAT_LFN=y : FAT is difficult to use with long file names + + Enable the BASIC interpreter. Other default options should be okay: + CONFIG_INTERPRETERS_BAS=y : Enables the interpreter + CONFIG_INTERPRETER_BAS_VT100=y + + The BASIC test suite can be included: + CONFIG_FS_ROMFS=y : ROMFS support is needed + CONFIG_EXAMPLES_BASTEST=y : Enables the BASIC test setup + CONFIG_EXAMPLES_BASTEST_DEVMINOR=0 + CONFIG_EXAMPLES_BASTEST_DEVPATH="/dev/ram0" + + Usage + ----- + This setup will initialize the BASIC test (optional): This will mount + a ROMFS file system at /mnt/romfs that contains the BASIC test files: + + nsh> bastest + Registering romdisk at /dev/ram0 + Mounting ROMFS filesystem at target=/mnt/romfs with source=/dev/ram0 + nsh> + + These steps will create and mount a RAMDISK at /tmp (required only for a + few BASIC commands). This will create a RAMDISK device at /dev/ram1 with + size = 512 * 64 = 32KiB and mount it at /tmp: + + nsh> mkrd -m 1 -s 512 64 + nsh> mkfatfs /dev/ram1 + nsh> mount -t vfat /dev/ram1 /tmp + nsh> + + The interactive interpreter is started like: + + nsh> bas + bas 2.4 + Copyright 1999-2014 Michael Haardt. + This is free software with ABSOLUTELY NO WARRANTY. + > + + Ctrl-D exits the interpreter. + + The test programs can be ran like this: + + nsh> bastest + Registering romdisk at /dev/ram0 + Mounting ROMFS filesystem at target=/mnt/romfs with source=/dev/ram0 + nsh> bas /mnt/romfs/test01.bas + 1 + hello + 0.0002 + 0.0000020 + 0.0000002 + + nsh> + + Or you can load a test into memory and execute it interactively: + + nsh> bas + bas 2.4 + Copyright 1999-2014 Michael Haardt. + This is free software with ABSOLUTELY NO WARRANTY. + > load "/mnt/romfs/test01.bas" + > run + 1 + hello + 0.0002 + 0.0000020 + 0.0000002 + > + +Testing LLVM LIBC++ with NuttX +============================== + +You can use LLVM LIBC++ on NuttX to get a C++ compiler with C++11 features. +Follow these steps to get it working: + +Clone the needed repositories: + + $ git clone https://www.bitbucket.org/acassis/libcxx + + $ git clone https://www.bitbucket.org/nuttx/apps + + $ git clone https://www.bitbucket.org/nuttx/nuttx + +Install the libcxx files on NuttX: + + $ cd libcxx + + $ ./install.sh ../nuttx + Installing LLVM/libcxx in the NuttX source tree + Installation succeeded + +Enter inside NuttX and compile it: + + $ cd ../nuttx + + $ tools/configure.sh stm32f4discovery:testlibcxx + Copy files + Refreshing... + + $ ls -l nuttx.bin + -rwxrwxr-x 1 alan alan 58112 Ago 8 11:08 nuttx.bin + +Plug the MiniUSB cable in the STM32F4Discovery board and flash the firmware: + + $ sudo openocd -f interface/stlink-v2.cfg -f target/stm32f4x.cfg -c init \ + -c "reset halt" -c "flash write_image erase nuttx.bin 0x08000000" + + ... + + Info : device id = 0x10036413 + Info : flash size = 1024kbytes + target halted due to breakpoint, current mode: Thread + xPSR: 0x61000000 pc: 0x20000046 msp: 0x20001d60 + wrote 65536 bytes from file nuttx.bin in 2.959432s (21.626 KiB/s) + +Connect the USB/Serial 3.3V dongle to PA2(board TX) and PA3(board RX) use +minicom or other serial console configured to 115200 8n1. + +Press Reset pin of the board and you will see: + + NuttShell (NSH) + nsh> ? + help usage: help [-v] [] + + [ cmp free mh source usleep + ? dirname help mv sleep xd + basename dd hexdump mw test + break echo kill pwd time + cat exec ls rm true + cd exit mb rmdir uname + cp false mkdir set unset + + Builtin Apps: + helloxx + + nsh> + +Just type helloxx: + + nsh> helloxx + helloxx_main: Saying hello from the dynamically constructed instance + CHelloWorld::HelloWorld: Hello, World!! + helloxx_main: Saying hello from the instance constructed on the stack + CHelloWorld::HelloWorld: Hello, World!! + helloxx_main: Saying hello from the statically constructed instance + CHelloWorld::HelloWorld: Hello, World!! + + nsh> + +Configurations +============== + +Common Information +------------------ + +Each STM32F4Discovery configuration is maintained in a sub-directory and +can be selected as follow: + + tools/configure.sh STM32F4Discovery: + +Where is one of the sub-directories listed in the next paragraph + + NOTES (common for all configurations): + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + +Configuration Sub-directories +------------------------- + + audio: + ----- + + This configuration is a variant of the NSH configuration used for + demonstrating PCM audio using the CS43L22 stereo DAC/amplifier on board + the STM32F4 Discovery and the STM32 I2S DMA interface. It uses the + file player at apps/system/nxplayer. The serial console is on USART2. + + The original CS43L22 and STM32 I2S drivers were contribued by Taras + Drozdovsky in May of 2017. The audio configuration was contributed by + Alan Carvalho de Assis and derives, in part, from the work of Taras at + https://github.com/tdrozdovskiy/CS43L22-Audio-driver. + + Usage instructions from the README file at the location: + + 1. Prepare USB flash storage. This configuration depends on .WAV files + provided to the system via a USB flash stick. There are some sample + audio files at https://github.com/tdrozdovskiy/CS43L22-Audio-driver + and these steps will put those sample .WAV files onto the USB flash: + + a. Format the USB flash storage into FAT. For example by next command + + $ mkfs.vfat /dev/sdb1 + + b. Create folder /music + + $ mkdir music + + c. Copy files from /audio_samples/ to /music folder of USB flash storage + + $ cp /audio_samples/* /mnt/media/music/ + + You should be able to use either Taras' .wav files like that or, if + you like, your own compatible .wav files. + + 2. Example usage CS43L22 Audio driver + + a. Power On or reset the STM32F4 Discovery board. We can see the NuttX + command line prompt: + + NuttShell (NSH) + nsh> + + b. Mount the usb flash device into our file system + + nsh> mount -t vfat /dev/sda/ /mnt/sda + + c. Start the NxPlayer program and Enter the help command to view the list + of commands + + nsh> nxplayer + NxPlayer version 1.04 + h for commands, q to exit + nxplayer> h + NxPlayer commands + ================ + balance d% : Set balance percentage (< 50% means more left) + device devfile : Specify a preferred audio device + h : Display help for commands + help : Display help for commands + mediadir path : Change the media directory + play filename : Play a media file + pause : Pause playback + resume : Resume playback + stop : Stop playback + tone freq secs : Produce a pure tone + q : Exit NxPlayer + quit : Exit NxPlayer + volume d% : Set volume to level specified + + d. Play the test sample track (cu44k.wav - 44100Hz, 16bit, stereo). + + nxplayer> play cu44k.wav + + e. Set the volume value to 50%. + + nxplayer> volume 50 + + f. Stop the current track and play another one + + nxplayer> stop + nxplayer> play hn.wav + + cxxtest: + ------- + + The C++ standard library test at apps/testing/cxxtest configuration. This + test is used to verify the uClibc++ port to NuttX. This configuration may + be selected as follows: + + tools/configure.sh sim:cxxtest + + NOTES: + + 1. Before you can use this example, you must first install the uClibc++ + C++ library. This is located outside of the NuttX source tree in the + NuttX uClibc++ GIT repository. See the README.txt file there for + instructions on how to install uClibc++ + + 2. Ideally, you should build with a toolchain based on GLIBC or + uClibc++. It you use a toolchain based on newlib, you may see + an error like the following: + + .../lib/libsupc++.a(vterminate.o): In function `__gnu_cxx::__verbose_terminate_handler()': + vterminate.cc:(....): undefined reference to `_impure_ptr' + + Here is a quick'n'dirty fix: + + 1. Get the directory where you can find libsupc++: + + arm-none-eabi-gcc -mcpu=cortex-m4 -mthumb -print-file-name=libsupc++.a + + 2. Go to that directory and save a copy of vterminate.o (in case you + want to restore it later: + + cd + arm-none-eabi-ar.exe -x libsupc++.a vterminate.o + + 3. Then remove vterminate.o from the library. At build time, the + uClibc++ package will provide a usable replacement vterminate.o. + + Steps 2 and 3 will require root privileges on most systems (not Cygwin). + + Now NuttX should link with no problem. If you want to restore the + vterminate.o that you removed from libsupc++, you can do that with: + + arm-none-eabi-ar.exe rcs libsupc++.a vterminate.o + + 3. Exceptions are enabled and workking (CONFIG_CXX_EXCEPTION=y) + + elf: + --- + + This configuration uses apps/examples/elf in order to test the ELF + loader. + + NOTES: + + 1. Default platform/toolchain: + + CONFIG_HOST_WINDOWS=y : Windows + CONFIG_WINDOWS_CYGWIN=y : Cygwin environment on Windows + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : GNU EABI toolchain for Windows + + 2. By default, this project assumes that you are *NOT* using the DFU + bootloader. + + 3. It appears that you cannot execute from CCM RAM. This is why the + following definition appears in the defconfig file: + + CONFIG_STM32_CCMEXCLUDE=y + + 4. This configuration requires that you have the genromfs tool installed + on your system and that you have the full path to the installed genromfs + executable in PATH variable (see apps/examples/README.txt) + + 5. This configuration can be extended to use the hello++4 example and to + build uClibc with the following additions to the configuration file + (from Leo aloe3132): + + CONFIG_HAVE_CXXINITIALIZE=y + + CONFIG_UCLIBCXX=y + CONFIG_CXX_EXCEPTION=y + CONFIG_LIBSUPCXX=y + CONFIG_UCLIBCXX_BUFSIZE=32 + + CONFIG_EXAMPLES_ELF_CXX=y + + 6. By default, this configuration uses the ROMFS file system. It can also + be modified to use the compressed CROMFS: + + -CONFIG_PATH_INITIAL="/mnt/romfs" + +CONFIG_PATH_INITIAL="/mnt/cromfs" + + -CONFIG_FS_ROMFS=y + +CONFIG_FS_CROMFS=y + + -CONFIG_EXAMPLES_ELF_ROMFS=y + +CONFIG_EXAMPLES_ELF_CROMFS=y + + 7. The network initialization thread is enabled in this configuration. + As a result, networking initialization is performed asynchronously with + NSH bring-up. + + The network monitor is not enabled in this configuration, however, so + the firmware will not know when the network is disconnected or + reconnected. The NSH Network Monitor cannot be used with the + STM32F4DIS-BB base board because the LAN8720 is configured in REF_CLK + OUT mode. In that mode, the PHY interrupt is not supported. The NINT + pin serves as REFLCK0 in that case. + + hciuart: + ------- + + This configuration was used for test the HCI UART driver. The HCI UART + is enabled on USART3 as well as the test application at + apps/wireless/bluetoot/btsak. + + NOTES: + + 1. This configuration assumes that that you are using the STM32F4DIS-BB + base board with serial console on USART6. If you are not using the + STM32F4DIS-BB, then you will want to disable support for the base + board. + + -CONFIG_STM32F4DISBB=y + +# CONFIG_STM32F4DISBB is not set + + You may also want to reconfigure the serial console to USART1. + + 2. The HCI UART is assumed to connect to the UART3 on the following pins: + + USART3 TX : PB10 + USART3 RX : PB11 + USART3 CTS: PB13 + USART3 RTS: PB14 + + The HCI UART selection can be changed by re-configuring and assigning + the different U[S]ART to the HCI. The U[S]ART pin selections can be + changed by modifying the disambiguation definitions in + boards/arm/stm32/stm32f4discovery/include/board.h + + I have been testing with the DVK_BT960_SA board via J10 as follows: + + DVK_BT860-SA J10 STM32F4 Discovery P1 + pin 1 GND P1 pin 49 + pin 2 Module_RTS_O USART3_CTS PB13, P1 pin 37 + pin 3 N/C + pin 4 Module_RX_I USART3_TXD PB10, P1 pin 34 + pin 5 Module_TX_O USART3_RX PB11, P1 pin 35 + pin 6 Module_CTS_I USART3_RTS PB14, P1 pin 38 + + NOTICE that the BT860 uses BT860-centric naming, the Rx pin is for + BT860 receive and needs to connect with the STM32 Tx pin, the Tx pin + is for BT860 transmit an needs to be connected with the STM32 Rx pin, + etc. Other parts may use host-centric naming so that the HCI UART Rx + pin connects to the STM32 Rx pin, Tx to Tx pin, etc. + + 3. Due to conflicts, USART3 many not be used if Ethernet is enabled with + the STM32F4DIS-BB base board: + + PB-11 conflicts with Ethernet TXEN + PB-13 conflicts with Ethernet TXD1 + + If you need to use the HCI uart with Ethernet, then you will need to + configure a new U[S]ART and/or modify the pin selections in + include/board.h. + + 4. Stack sizes are large and non-optimal. Don't judge memory usage + without tuning. + + 5. I tested using the Laird DVK_BT860. The BT860 defaults to 115200 + BAUD but is capable of transfers up to 4M. The documentation says + that the part supports auto baudrate detection, but I have found no + documentation on how to use that. + + Currently the "generic" HCI UART upper half is used with the BT860 + and that upper half driver supports only a fixed (but configurable + BAUD) is used and this must be set to the BT860 default (115200). + + A custom BT860 upper half driver is needed that can use vendor + specific command: Baud rate can be set with such a vendor-specific + command. Ideally, the sequence would be: (1) start at default baud + rate, (2) get local version info, (3) send the vendor-specific baud + rate change command, (4) wait for response, and (5) set the local + UART to the matching, higher baud rate. + + The custom, vendor-specific BT860 command is: + + {0x18, 0xfc, 0x06, 0x00, 0x00, NN, NN, NN, NN} + + where {NN, NN, NN, NN} is the requested baud in little endian byte order. + + If an initialization script is used then (5) then send initialization + scripts script. After sending the last command from the + initialization script, (6) reset the local UART. Finally, (7) send + vendor-specific baud rate change command, (8) wait for response, and + (9) set local UART to high baud rate. + + The command to write the initialization script into NVRAM is another + story for another time and another place. + + If you use a different HCI UART, you will need to modify this setting: + + CONFIG_BLUETOOTH_UART_GENERIC=y + + and you may have to add some support in drivers/wireless/bluetooth. + + ipv6: + ---- + This is another version of the NuttShell configuration for the + STM32F4-Discovery with the STM32F4DIS-BB base board. It is very similar + to the netnsh configuration except that it has IPv6 enabled and IPv4 + disabled. Several network utilities that are not yet available when + IPv6 is disabled. + + NOTES: + + 1. As of 2015-02-05, this configuration was identical to the netnsh + configuration other than using IPv6. So all of the notes above + regarding the netnsh configuration apply. + + a. Telnet does work with IPv6 but is not enabled in this + configuration (but could be). + b. The network initialization thread was enabled in the netnsh + configuration on 2015-09-28, but not in the ipv6 configuration. + + 2. This configuration can be modified to that both IPv4 and IPv6 + are support. Here is a summary of the additional configuration + settings required to support both IPv4 and IPv6: + + CONFIG_NET_IPv4=y + CONFIG_NET_ARP=y + CONFIG_NET_ARP_SEND=y (optional) + CONFIG_NET_ICMP=y + CONFIG_NET_ICMP_SOCKET=y + + CONFIG_NETDB_DNSCLIENT=y + CONFIG_NETUTILS_TELNETD=y + + CONFIG_NSH_IPADDR=0x0a000002 + CONFIG_NSH_DRIPADDR=0x0a000001 + CONFIG_NSH_NETMASK=0xffffff00 + CONFIG_NSH_TELNET=y + + Then from NSH, you have both ping and ping6 commands: + + nsh> ping 10.0.0.1 + nsh> ping6 fc00::1 + + And from the host you can do similar: + + ping 10.0.0.2 + ping6 fc00::2 (Linux) + ping -6 fc00::2 (Windows cmd) + + and Telnet is now enabled and works from the host... but only using + IPv6 addressing: + + telnet fc00::2 + + That is because the Telnet daemon will default to IPv6 and there is + no Telnet option to let you select which if both IPv4 and IPv6 are + enabled. + + 3. I have used this configuration to serve up IP address prefixes + in a local network with these modifications to the configuration: + + +CONFIG_NET_ICMPv6_ROUTER=y + +CONFIG_NET_ICMPv6_PREFLEN=64 + +CONFIG_NET_ICMPv6_PREFIX_1=0xfc00 + +CONFIG_NET_ICMPv6_PREFIX_2=0x0000 + +CONFIG_NET_ICMPv6_PREFIX_3=0x0000 + +CONFIG_NET_ICMPv6_PREFIX_4=0x0000 + +CONFIG_NET_ICMPv6_PREFIX_5=0x0000 + +CONFIG_NET_ICMPv6_PREFIX_6=0x0000 + +CONFIG_NET_ICMPv6_PREFIX_7=0x0000 + +CONFIG_NET_ICMPv6_PREFIX_8=0x0000 + + +CONFIG_NSH_IPv6NETMASK_5=0x0000 + -CONFIG_NSH_IPv6NETMASK_5=0xffff + + +CONFIG_NSH_IPv6NETMASK_6=0x0000 + -CONFIG_NSH_IPv6NETMASK_6=0xffff + + +CONFIG_NSH_IPv6NETMASK_7=0x0000 + -CONFIG_NSH_IPv6NETMASK_7=0xffff + + +CONFIG_NSH_IPv6NETMASK_8=0x0000 + -CONFIG_NSH_IPv6NETMASK_8=0xff80 + + kostest: + ------- + This is identical to the ostest configuration below except that NuttX + is built as a kernel-mode, monolithic module and the user applications + are built separately. Is is recommended to use a special make command; + not just 'make' but make with the following two arguments: + + make pass1 pass2 + + In the normal case (just 'make'), make will attempt to build both user- + and kernel-mode blobs more or less interleaved. This actual works! + However, for me it is very confusing so I prefer the above make command: + Make the user-space binaries first (pass1), then make the kernel-space + binaries (pass2) + + NOTES: + + 1. This is the default platform/toolchain in the configuration: + + CONFIG_HOST_WINDOWS=y : Windows + CONFIG_WINDOWS_CYGWIN=y : Cygwin environment on Windows + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : GNU EABI toolchain for Windows + + This is easily changed by modifying the configuration. + + 2. At the end of the build, there will be several files in the top-level + NuttX build directory: + + PASS1: + nuttx_user.elf - The pass1 user-space ELF file + nuttx_user.hex - The pass1 Intel HEX format file (selected in defconfig) + User.map - Symbols in the user-space ELF file + + PASS2: + nuttx - The pass2 kernel-space ELF file + nuttx.hex - The pass2 Intel HEX file (selected in defconfig) + System.map - Symbols in the kernel-space ELF file + + 3. Combining .hex files. If you plan to use the STM32 ST-Link Utility to + load the .hex files into FLASH, then you need to combine the two hex + files into a single .hex file. Here is how you can do that. + + a. The 'tail' of the nuttx.hex file should look something like this + (with my comments added): + + $ tail nuttx.hex + # 00, data records + ... + :10 9DC0 00 01000000000800006400020100001F0004 + :10 9DD0 00 3B005A0078009700B500D400F300110151 + :08 9DE0 00 30014E016D0100008D + # 05, Start Linear Address Record + :04 0000 05 0800 0419 D2 + # 01, End Of File record + :00 0000 01 FF + + Use an editor such as vi to remove the 05 and 01 records. + + b. The 'head' of the nuttx_user.hex file should look something like + this (again with my comments added): + + $ head nuttx_user.hex + # 04, Extended Linear Address Record + :02 0000 04 0801 F1 + # 00, data records + :10 8000 00 BD89 01084C800108C8110208D01102087E + :10 8010 00 0010 00201C1000201C1000203C16002026 + :10 8020 00 4D80 01085D80010869800108ED83010829 + ... + + Nothing needs to be done here. The nuttx_user.hex file should + be fine. + + c. Combine the edited nuttx.hex and un-edited nuttx_user.hex + file to produce a single combined hex file: + + $ cat nuttx.hex nuttx_user.hex >combined.hex + + Then use the combined.hex file with the STM32 ST-Link tool. If + you do this a lot, you will probably want to invest a little time + to develop a tool to automate these steps. + + module: + ------ + + A simple stripped down NSH configuration that was used for testing NuttX + OS modules using the test at apps/examples/module. Key difference from + other NSH configurations include these additions to the configuration file: + + CONFIG_BOARDCTL_OS_SYMTAB=y + CONFIG_EXAMPLES_MODULE=y + CONFIG_EXAMPLES_MODULE_BUILTINFS=y + CONFIG_EXAMPLES_MODULE_DEVMINOR=0 + CONFIG_EXAMPLES_MODULE_DEVPATH="/dev/ram0" + CONFIG_FS_ROMFS=y + CONFIG_LIBC_ARCH_ELF=y + CONFIG_MODULE=y + CONFIG_LIBC_MODLIB=y + CONFIG_MODLIB_MAXDEPEND=2 + CONFIG_MODLIB_ALIGN_LOG2=2 + CONFIG_MODLIB_BUFFERSIZE=128 + CONFIG_MODLIB_BUFFERINCR=32 + + The could be followed may be added for testing shared libraries in the + FLAT build using apps/examples/sotest (assuming that you also have SD + card support enabled and that the SD card is mount at /mnt/sdcard): + + CONFIG_LIBC_DLFCN=y + CONFIG_EXAMPLES_SOTEST=y + CONFIG_EXAMPLES_SOTEST_BINDIR="/mnt/sdcard" + + NOTE: You must always have: + + CONFIG_STM32_CCMEXCLUDE=y + + because code cannot be executed from CCM memory. + + STATUS: + 2018-06-02: Configuration added by Alan Carvalho de Assis. + + netnsh: + ------ + This is a special version of the NuttShell (nsh) configuration that is + tailored to work with the STM32F4DIS-BB base board. This version + derives from nsh configuration so all of the notes apply there except as + noted below. + + NOTES: + + 1. This example uses USART6 for the serial console. The STM32F4DIS-BB + provides RS-232 drivers for USART6 and allows access via the DB9 + connector on the base board. USART6 is, therefore, the more + convenient UART to use for the serial console. + + 2. Networking is enabled. The STM32F4DIS-BB has an SMC LAN2870 PHY + and RJ5 network connector. Support is enabled for ICMP, TCP/IP, + UDP, and ARP. + + 3. SD card support is enabled. The STM32F4DIS-BB has an on-board + microSD slot that should be automatically registered as the block + device /dev/mmcsd0 when an SD card is present. The SD card can + then be mounted by the NSH command: + + nsh> mount -t /dev/mmcsd0 /mnt/sdcard + + 4. CCM memory is not included in the heap in this configuration. That + is because the SD card uses DMA and if DMA memory is allocated from + the CCM memory, the DMA will failure. This is an STM32 hardware + limitation. + + If you want to get the CCM memory back in the heap, then you can + + a) Disable microSD support (and DMAC2 which is then no longer + needed). If you reduce the clocking by a huge amount, it might + be possible to use microSD without DMA. This, however, may + not be possible. + b) Develop a strategy to manage CCM memory and DMA memory. Look + at this discussion on the NuttX Wiki: + https://cwiki.apache.org/confluence/display/NUTTX/STM32+CCM+Allocator + + To put the CCM memory back into the heap you would need to change + the following in the NuttX configuration: + + CONFIG_STM32_CCMEXCLUDE=n : Don't exclude CCM memory from the heap + CONFIG_MM_REGIONS=2 : With CCM, there will be two memory regions + + nsh: + --- + Configures the NuttShell (nsh) located at apps/examples/nsh. The + Configuration enables the serial interfaces on USART2. Support for + builtin applications is enabled, but in the base configuration no + builtin applications are selected (see NOTES below). + + NOTES: + + 1. By default, this configuration uses the ARM EABI toolchain + for Windows and builds under Cygwin (or probably MSYS). That + can easily be reconfigured, of course. + + CONFIG_HOST_WINDOWS=y : Builds under Windows + CONFIG_WINDOWS_CYGWIN=y : Using Cygwin + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : GNU EABI toolchain for Windows + + 2. To use this configuration with the STM32F4DIS-BB baseboard you + should: + + - Select the STM32F4DIS-BB baseboard in the board configuration + menu + - Disable USART2 and select USART6 in the STM32 peripheral selection + menu + - Select USART6 as the serial console at 115200 8N1 in the + Drivers menus + + 3. This example supports the PWM test (apps/examples/pwm) but this must + be manually enabled by selecting: + + CONFIG_PWM=y : Enable the generic PWM infrastructure + CONFIG_STM32_TIM4=y : Enable TIM4 + CONFIG_STM32_TIM4_PWM=y : Use TIM4 to generate PWM output + + See also apps/examples/README.txt + + Special PWM-only debug options: + + CONFIG_DEBUG_PWM_INFO + + 4. This example supports the Quadrature Encode test (apps/examples/qencoder) + but this must be manually enabled by selecting: + + CONFIG_EXAMPLES_QENCODER=y : Enable the apps/examples/qencoder + CONFIG_SENSORS=y : Enable support for sensors + CONFIG_SENSORS_QENCODER=y : Enable the generic Quadrature Encoder infrastructure + CONFIG_STM32_TIM8=y : Enable TIM8 + CONFIG_STM32_TIM2=n : (Or optionally TIM2) + CONFIG_STM32_TIM8_QE=y : Use TIM8 as the quadrature encoder + CONFIG_STM32_TIM2_QE=y : (Or optionally TIM2) + + See also apps/examples/README.tx. Special debug options: + + CONFIG_DEBUG_SENSORS + + 5. This example supports the watchdog timer test (apps/examples/watchdog) + but this must be manually enabled by selecting: + + CONFIG_EXAMPLES_WATCHDOG=y : Enable the apps/examples/watchdog + CONFIG_WATCHDOG=y : Enables watchdog timer driver support + CONFIG_STM32_WWDG=y : Enables the WWDG timer facility, OR + CONFIG_STM32_IWDG=y : Enables the IWDG timer facility (but not both) + + The WWDG watchdog is driven off the (fast) 42MHz PCLK1 and, as result, + has a maximum timeout value of 49 milliseconds. For WWDG watchdog, you + should also add the following to the configuration file: + + CONFIG_EXAMPLES_WATCHDOG_PINGDELAY=20 + CONFIG_EXAMPLES_WATCHDOG_TIMEOUT=49 + + The IWDG timer has a range of about 35 seconds and should not be an issue. + + 6. USB Support (CDC/ACM device) + + CONFIG_STM32_OTGFS=y : STM32 OTG FS support + CONFIG_USBDEV=y : USB device support must be enabled + CONFIG_CDCACM=y : The CDC/ACM driver must be built + CONFIG_NSH_BUILTIN_APPS=y : NSH built-in application support must be enabled + CONFIG_NSH_ARCHINIT=y : To perform USB initialization + + 7. Using the USB console. + + The STM32F4Discovery NSH configuration can be set up to use a USB CDC/ACM + (or PL2303) USB console. The normal way that you would configure the + the USB console would be to change the .config file like this: + + CONFIG_STM32_OTGFS=y : STM32 OTG FS support + CONFIG_USART2_SERIAL_CONSOLE=n : Disable the USART2 console + CONFIG_DEV_CONSOLE=n : Inhibit use of /dev/console by other logic + CONFIG_USBDEV=y : USB device support must be enabled + CONFIG_CDCACM=y : The CDC/ACM driver must be built + CONFIG_CDCACM_CONSOLE=y : Enable the CDC/ACM USB console. + + NOTE: When you first start the USB console, you have hit ENTER a few + times before NSH starts. The logic does this to prevent sending USB data + before there is anything on the host side listening for USB serial input. + + 8. Here is an alternative USB console configuration. The following + configuration will also create a NSH USB console but this version + will use /dev/console. Instead, it will use the normal /dev/ttyACM0 + USB serial device for the console: + + CONFIG_STM32_OTGFS=y : STM32 OTG FS support + CONFIG_USART2_SERIAL_CONSOLE=y : Keep the USART2 console + CONFIG_DEV_CONSOLE=y : /dev/console exists (but NSH won't use it) + CONFIG_USBDEV=y : USB device support must be enabled + CONFIG_CDCACM=y : The CDC/ACM driver must be built + CONFIG_CDCACM_CONSOLE=n : Don't use the CDC/ACM USB console. + CONFIG_NSH_USBCONSOLE=y : Instead use some other USB device for the console + + The particular USB device that is used is: + + CONFIG_NSH_USBCONDEV="/dev/ttyACM0" + + The advantage of this configuration is only that it is easier to + bet working. This alternative does has some side effects: + + - When any other device other than /dev/console is used for a user + interface, linefeeds (\n) will not be expanded to carriage return / + linefeeds (\r\n). You will need to set your terminal program to account + for this. + + - /dev/console still exists and still refers to the serial port. So + you can still use certain kinds of debug output (see include/debug.h, all + of the debug output from interrupt handlers will be lost. + + - But don't enable USB debug output! Since USB is console is used for + USB debug output and you are using a USB console, there will be + infinite loops and deadlocks: Debug output generates USB debug + output which generatates USB debug output, etc. If you want USB + debug output, you should consider enabling USB trace + (CONFIG_USBDEV_TRACE) and perhaps the USB monitor (CONFIG_USBMONITOR). + + See the usbnsh configuration below for more information on configuring + USB trace output and the USB monitor. + + 9. USB OTG FS Host Support. The following changes will enable support for + a USB host on the STM32F4Discovery, including support for a mass storage + class driver: + + Device Drivers -> + CONFIG_USBDEV=n : Make sure the USB device support is disabled + CONFIG_USBHOST=y : Enable USB host support + CONFIG_USBHOST_ISOC_DISABLE=y + + Device Drivers -> USB Host Driver Support + CONFIG_USBHOST_MSC=y : Enable the mass storage class + + System Type -> STM32 Peripheral Support + CONFIG_STM32_OTGFS=y : Enable the STM32 USB OTG FS block + CONFIG_STM32_SYSCFG=y : Needed for all USB OTF FS support + + RTOS Features -> Work Queue Support + CONFIG_SCHED_WORKQUEUE=y : High priority worker thread support is required + CONFIG_SCHED_HPWORK=y : for the mass storage class driver. + + File Systems -> + CONFIG_FS_FAT=y : Needed by the USB host mass storage class. + + Board Selection -> + CONFIG_BOARDCTL=y : Needed for CONFIG_NSH_ARCHINIT + + Application Configuration -> NSH Library + CONFIG_NSH_ARCHINIT=y : Architecture specific USB initialization + : is needed for NSH + + With those changes, you can use NSH with a FLASH pen driver as shown + belong. Here NSH is started with nothing in the USB host slot: + + NuttShell (NSH) NuttX-x.yy + nsh> ls /dev + /dev: + console + null + ttyS0 + + After inserting the FLASH drive, the /dev/sda appears and can be + mounted like this: + + nsh> ls /dev + /dev: + console + null + sda + ttyS0 + nsh> mount -t vfat /dev/sda /mnt/stuff + nsh> ls /mnt/stuff + /mnt/stuff: + -rw-rw-rw- 16236 filea.c + + And files on the FLASH can be manipulated to standard interfaces: + + nsh> echo "This is a test" >/mnt/stuff/atest.txt + nsh> ls /mnt/stuff + /mnt/stuff: + -rw-rw-rw- 16236 filea.c + -rw-rw-rw- 16 atest.txt + nsh> cat /mnt/stuff/atest.txt + This is a test + nsh> cp /mnt/stuff/filea.c fileb.c + nsh> ls /mnt/stuff + /mnt/stuff: + -rw-rw-rw- 16236 filea.c + -rw-rw-rw- 16 atest.txt + -rw-rw-rw- 16236 fileb.c + + To prevent data loss, don't forget to un-mount the FLASH drive + before removing it: + + nsh> umount /mnt/stuff + + 10. I used this configuration to test the USB hub class. I did this + testing with the following changes to the configuration (in addition + to those listed above for base USB host/mass storage class support): + + Drivers -> USB Host Driver Support + CONFIG_USBHOST_HUB=y : Enable the hub class + CONFIG_USBHOST_ASYNCH=y : Asynchronous I/O supported needed for hubs + + System Type -> USB host configuration + To be determined + + Board Selection -> + CONFIG_STM32F4DISCO_USBHOST_STACKSIZE=2048 (bigger than it needs to be) + + RTOS Features -> Work Queue Support + CONFIG_SCHED_LPWORK=y : Low priority queue support is needed + CONFIG_SCHED_LPNTHREADS=1 + CONFIG_SCHED_LPWORKSTACKSIZE=1024 + + NOTES: + + 1. It is necessary to perform work on the low-priority work queue + (vs. the high priority work queue) because deferred hub-related + work requires some delays and waiting that is not appropriate on + the high priority work queue. + + 2. Stack usage make increase when USB hub support is enabled because + the nesting depth of certain USB host class logic can increase. + + STATUS: + 2015-04-30 + Appears to be fully functional. + + 11. Using USB Device as a Mass Storage for the host computer: + + System Type ---> + STM32 Peripheral Support ---> + [*] OTG FS + + Device Drivers ---> + [*] USB Device Driver Support ---> + [*] USB Mass storage class device ---> + [*] Mass storage removable + + [*] RAM Disk Support + + Board Selection ---> + [*] Enable boardctl() interface + [*] Enable USB device controls + + File Systems ---> + [*] FAT file system + [*] FAT upper/lower names + [*] FAT long file names + + [*] PROCFS File System + + Application Configuration ---> + System Libraries and NSH Add-Ons ---> + [*] USB Mass Storage Device Commands ---> + (/dev/ram0) LUN1 Device Path + + Compile and flash the firmware in the board as usual, then in the nsh: + + nsh> mkrd -m 0 -s 512 64 + + nsh> ls /dev + /dev: + console + null + ram0 + ttyS0 + + nsh> mkfatfs /dev/ram0 + + Connect a USB cable to STM32F4Discovery board (connector CN5) and run: + + nsh> msconn + mcsonn_main: Creating block drivers + mcsonn_main: Configuring with NLUNS=1 + mcsonn_main: handle=1000a550 + mcsonn_main: Bind LUN=0 to /dev/ram0 + mcsonn_main: Connected + + In this moment a 33KB disk should appear in your host computer. If you + saved some file on this small disk you can now run disconnect command: + + nsh> msdis + msdis: Disconnected + + Remove the USB cable from microUSB connector and run: + + nsh> mount -t vfat /dev/ram0 /mnt + + nsh> ls /mnt + /mnt: + TEST.TXT + + nsh> cat /mnt/TEST.TXT + Testing + + nxlines: + ------ + An example using the NuttX graphics system (NX). This example focuses on + placing lines on the background in various orientations. + + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : GNU EABI toolchain for Windows + CONFIG_LCD_LANDSCAPE=y : 320x240 landscape orientation + + The STM32F4Discovery board does not have any graphics capability. This + configuration assumes that you have connected an SD1289-based LCD as + described above under "SSD1289". NOTE: At present, it has not been + proven that the STM32F4Discovery can actually drive an LCD. There are + some issues with how some of the dedicated FSMC pins are used on the + boards. This configuration may not be useful and may only serve as + an illustration of how to build for th SSD1289 LCD. + + NOTES: + + 1. As of this writing, I have not seen the LCD work! + + 2. This configured can be re-configured to use either the + UG-2864AMBAG01 or UG-2864HSWEG01 0.96 inch OLEDs by adding + or changing the following items in the configuration (using + 'make menuconfig'): + + +CONFIG_SPI_CMDDATA=y + + -CONFIG_LCD_MAXCONTRAST=1 + -CONFIG_LCD_MAXPOWER=255 + +CONFIG_LCD_MAXCONTRAST=255 + +CONFIG_LCD_MAXPOWER=1 + + -CONFIG_LCD_SSD1289=y + -CONFIG_SSD1289_PROFILE1=y + +CONFIG_LCD_UG2864AMBAG01=y : For the UG-2964AMBAG01 + +CONFIG_UG2864AMBAG01_SPIMODE=3 + +CONFIG_UG2864AMBAG01_FREQUENCY=3500000 + +CONFIG_UG2864AMBAG01_NINTERFACES=1 + + -CONFIG_NX_DISABLE_1BPP=y + +CONFIG_NX_DISABLE_16BPP=y + +CONFIG_NXSTART_EXTERNINIT=y + + -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_BGCOLOR=0x00 + +CONFIG_EXAMPLES_NXLINES_LINEWIDTH=4 + +CONFIG_EXAMPLES_NXLINES_LINECOLOR=0x01 + +CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=2 + +CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0x01 + +CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0x00 + +CONFIG_EXAMPLES_NXLINES_BPP=1 + +CONFIG_EXAMPLES_NXLINES_EXTERNINIT=y + + There are some issues with the presentation... some tuning of the + configuration could fix that. Lower resolution displays are also more + subject to the "fat, flat line bug" that I need to fix someday. See + https://cwiki.apache.org/confluence/pages/viewpage.action?pageId=139629474 + for a description of the fat, flat line bug. + + pm: + -- + This is a configuration that is used to test STM32 power management, i.e., + to test that the board can go into lower and lower states of power usage + as a result of inactivity. This configuration is based on the nsh2 + configuration with modifications for testing power management. This + configuration should provide some guidelines for power management in your + STM32 application. + + NOTES: + + 1. Default configuration is Cygwin under windows using the AM EABI GCC + toolchain: + + CONFIG_HOST_WINDOWS=y : Windows + CONFIG_WINDOWS_CYGWIN=y : Cygwin + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : GNU EABI toolchain for Windows + + 2. CONFIG_ARCH_CUSTOM_PMINIT and CONFIG_ARCH_IDLE_CUSTOM are necessary + parts of the PM configuration: + + CONFIG_ARCH_CUSTOM_PMINIT=y + + CONFIG_ARCH_CUSTOM_PMINIT moves the PM initialization from + arch/arm/src/stm32/stm32_pminitialiaze.c to boards/arm/stm32/stm3210-eval/src/stm32_pm.c. + This allows us to support board-specific PM initialization. + + CONFIG_ARCH_IDLE_CUSTOM=y + + The bulk of the PM activities occur in the IDLE loop. The IDLE loop + is special because it is what runs when there is no other task running. + Therefore when the IDLE executes, we can be assure that nothing else + is going on; this is the ideal condition for doing reduced power + management. + + The configuration CONFIG_ARCH_IDLE_CUSTOM allows us to "steal" the + normal STM32 IDLE loop (of arch/arm/src/stm32/stm32_idle.c) and replace + this with our own custom IDLE loop (at boards/arm/stm32/stm3210-eval/src/up_idle.c). + + 3. Here are some additional things to note in the configuration: + + CONFIG_PM_BUTTONS=y + + CONFIG_PM_BUTTONS enables button support for PM testing. Buttons can + drive EXTI interrupts and EXTI interrupts can be used to wakeup for + certain reduced power modes (STOP mode). The use of the buttons here + is for PM testing purposes only; buttons would normally be part the + application code and CONFIG_PM_BUTTONS would not be defined. + + CONFIG_RTC_ALARM=y + + The RTC alarm is used to wake up from STOP mode and to transition to + STANDBY mode. This used of the RTC alarm could conflict with other + uses of the RTC alarm in your application. + + posix_spawn: + ------------ + This configuration directory, performs a simple test os the posix_spawn + interface using apps/examples/posix_spawn. + + NOTES: + + 1. Default toolchain: + + CONFIG_HOST_WINDOWS=y : Builds under windows + CONFIG_WINDOWS_CYGWIN=y : Using Cygwin and + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : Generic ARM EABI toolchain for Windows + + 2. By default, this project assumes that you are *NOT* using the DFU + bootloader. + + pseudoterm: + ----------- + + This is a configuration to test the Pseudo Terminal support for NuttX. + + To test it you will need two USB/Serial dongles. The first dongle as + usual will be used to main NSH console port in USART2 (PA2 and PA3) and + the second dongle you will connect to UART3 (PB10 and PB11). + + In the main NSH console (in USART2) type: "pts_test &". It will create a + new console in UART3. Just press ENTER and start typing commands on it. + + sporadic + -------- + + This is an NSH configuration that includes apps/testing/ostest as a builtin. + The sporadic scheduler is enabled and the purpose of this configuration is + to investigate an error in that scheduler. See Issue 2035. The serial + console is on USART6. + + testlibcxx + ---------- + + This is a configuration for testing lib++. See the section above entitled + "Testing LLVM LIBC++ with NuttX" for detailed information about this + configuration. + + rgbled: + ------- + + Alan Carvalho de Assis has used the STM32F4-Discovery to drive an RGB LED + using PWM output. The external RGB connected this way: + + R = TIM1 CH1 on PE9 + G = TIM2 CH2 on PA1 + B = TIM3 CH3 on PB0 + + as described about in the section "RGB LED Driver". + + This configuration uses the example at apps/examples/rgbled to drive the + external RGB LED> + + rndis: + ------ + + This is a board configuration to demonstrate how to use Ethernet-over-USB, + in this case using the RNDIS protocol. Using it you can get access to your + board using Telnet or you can use transfer file to it. Both steps will be + explained below. + + Your board will be get IP address from a DHCP server. If you want to use a + fixed IP instead using DHCP, you need to disable the DHCP Client and set + up its IP. For more info watch: www.youtube.com/watch?v=8noH8v7xNgs + + You can access the board's NuttShell just typing in the Linux terminal: + + $ telnet 10.0.0.2 + + You should see something like this: + + Trying 10.0.0.2... + Connected to 10.0.0.2. + Escape character is '^]'. + + NuttShell (NSH) + nsh> + + This board configuration has support to RAMDISK because we need a writable + filesystem to get files from the computer. Then you need to create first a + RAMDISK and mount it using these steps: + + nsh> mkrd 64 + nsh> mkfatfs /dev/ram0 + nsh> mount -t vfat /dev/ram0 /mnt + + Open a new Linux terminal and start a webserver, Python one embedded: + + $ python -m SimpleHTTPServer + + It will create a webserver serving in the port 8000 and will share files + in the current directory where it was executed. + + Then in the NuttShell you can run these commands to download a small file: + + nsh> cd /mnt + nsh> wget http://10.0.0.1:8000/test.txt + nsh> ls -l + /mnt: + -rw-rw-rw- 23 test.txt + + This configuration also supports: + + 1. An NFS file system client. Relevant configuration options: + + CONFIG_NFS=y + CONFIG_NFS_STATISTICS=y + + 2. Loadable ELF modules + + CONFIG_SYMTAB_ORDEREDBYNAME=y + CONFIG_ELF=y + CONFIG_EXAMPLES_HELLO=m + CONFIG_LIBC_EXECFUNCS=y + CONFIG_NSH_FILE_APPS=y + CONFIG_SYSTEM_NSH_SYMTAB=y + CONFIG_SYSTEM_NSH_SYMTAB_ARRAYNAME="g_symtab" + CONFIG_SYSTEM_NSH_SYMTAB_COUNTNAME="g_nsymbols" + + Further, the configuration assumes that executable files reside on the + remotely mounted file system: + + CONFIG_LIBC_ENVPATH=y + CONFIG_PATH_INITIAL="/mnt/nfs/bin" + + 3 'ping' support + + CONFIG_NET_ICMP_SOCKET=y + CONFIG_SYSTEM_PING=y + + usbnsh: + ------- + + This is another NSH example. If differs from other 'nsh' configurations + in that this configurations uses a USB serial device for console I/O. + Such a configuration is useful on the stm32f4discovery which has no + builtin RS-232 drivers. + + NOTES: + + 1. By default, this configuration uses the ARM EABI toolchain + for Windows and builds under Cygwin (or probably MSYS). That + can easily be reconfigured, of course. + + CONFIG_HOST_WINDOWS=y : Builds under Windows + CONFIG_WINDOWS_CYGWIN=y : Using Cygwin + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : GNU EABI toolchain for Windows + + 2. This configuration does have USART2 output enabled and set up as + the system logging device: + + CONFIG_SYSLOG_CHAR=y : Use a character device for system logging + CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" : USART2 will be /dev/ttyS0 + + However, there is nothing to generate SYSLOG output in the default + configuration so nothing should appear on USART2 unless you enable + some debug output or enable the USB monitor. + + NOTE: Using the SYSLOG to get debug output has limitations. Among + those are that you cannot get debug output from interrupt handlers. + So, in particularly, debug output is not a useful way to debug the + USB device controller driver. Instead, use the USB monitor with + USB debug off and USB trace on (see below). + + 3. Enabling USB monitor SYSLOG output. If tracing is enabled, the USB + device will save encoded trace output in in-memory buffer; if the + USB monitor is enabled, that trace buffer will be periodically + emptied and dumped to the system logging device (USART2 in this + configuration): + + CONFIG_USBDEV_TRACE=y : Enable USB trace feature + CONFIG_USBDEV_TRACE_NRECORDS=128 : Buffer 128 records in memory + CONFIG_NSH_USBDEV_TRACE=n : No builtin tracing from NSH + CONFIG_NSH_ARCHINIT=y : Automatically start the USB monitor + CONFIG_USBMONITOR=y : Enable the USB monitor daemon + CONFIG_USBMONITOR_STACKSIZE=2048 : USB monitor daemon stack size + CONFIG_USBMONITOR_PRIORITY=50 : USB monitor daemon priority + CONFIG_USBMONITOR_INTERVAL=2 : Dump trace data every 2 seconds + + CONFIG_USBMONITOR_TRACEINIT=y : Enable TRACE output + CONFIG_USBMONITOR_TRACECLASS=y + CONFIG_USBMONITOR_TRACETRANSFERS=y + CONFIG_USBMONITOR_TRACECONTROLLER=y + CONFIG_USBMONITOR_TRACEINTERRUPTS=y + + 4. By default, this project assumes that you are *NOT* using the DFU + bootloader. + + Using the Prolifics PL2303 Emulation + ------------------------------------ + You could also use the non-standard PL2303 serial device instead of + the standard CDC/ACM serial device by changing: + + CONFIG_CDCACM=n : Disable the CDC/ACM serial device class + CONFIG_CDCACM_CONSOLE=n : The CDC/ACM serial device is NOT the console + CONFIG_PL2303=y : The Prolifics PL2303 emulation is enabled + CONFIG_PL2303_CONSOLE=y : The PL2303 serial device is the console + + winbuild: + -------- + + This is a version of the apps/example/ostest, but configure to build natively + in the Windows CMD shell. + + NOTES: + + 1. The beginnings of a Windows native build are in place but still not full + usable as of this writing. The windows native build logic is currently + separate and must be started by: + + make -f Win.mk + + This build: + + - Uses all Windows style paths + - Uses primarily Windows batch commands from cmd.exe, with + - A few extensions from GNUWin32 (or MSYS is you prefer) + + In this build, you cannot use a Cygwin or MSYS shell. Rather the build must + be performed in a Windows console. Here is a better shell than than the + standard issue, CMD.exe shell: ConEmu which can be downloaded from: + http://code.google.com/p/conemu-maximus5/ + + CONFIG_HOST_WINDOWS=y : Windows + CONFIG_WINDOWS_NATIVE=y : Native Windows environment + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y : GNU EABI toolchain for Windows + + Build Tools. The build still relies on some Unix-like commands. I use + the GNUWin32 tools that can be downloaded from http://gnuwin32.sourceforge.net/. + The MSYS tools are probably also a option but are likely lower performance + since they are based on Cygwin 1.3. + + Host Compiler: I use the MingGW compiler which can be downloaded from + http://www.mingw.org/. If you are using GNUWin32, then it is recommended + the you not install the optional MSYS components as there may be conflicts. diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/adb/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/adb/defconfig new file mode 100644 index 00000000000..fc81a5e0c6b --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/adb/defconfig @@ -0,0 +1,71 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ADBD_FILE_SERVICE=y +CONFIG_ADBD_SHELL_SERVICE=y +CONFIG_ADBD_USB_SERVER=y +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARDCTL_USBDEVCTRL=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEV_URANDOM=y +CONFIG_ELF=y +CONFIG_EXAMPLES_HELLO=m +CONFIG_FAT_LFN=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3072 +CONFIG_INTELHEX_BINARY=y +CONFIG_LIBUV=y +CONFIG_MMCSD=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_WAITPID=y +CONFIG_SENSORS=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=17 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2020 +CONFIG_STM32_DMA2=y +CONFIG_STM32_DMACAPABLE=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI2=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_ADBD=y +CONFIG_SYSTEM_NSH=y +CONFIG_TLS_TASK_NELEM=4 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USBADB=y +CONFIG_USBDEV=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/audio/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/audio/defconfig new file mode 100644 index 00000000000..a3d4f64b27d --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/audio/defconfig @@ -0,0 +1,76 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_AUDIO=y +CONFIG_AUDIO_CS43L22=y +CONFIG_AUDIO_CUSTOM_DEV_PATH=y +CONFIG_AUDIO_EXCLUDE_TONE=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_DRIVERS_AUDIO=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FS_FAT=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_DRIVER=y +CONFIG_I2C_POLLED=y +CONFIG_I2C_RESET=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_NXPLAYER_DEFAULT_MEDIADIR="/mnt/music" +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMACAPABLE=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2S3=y +CONFIG_STM32_I2S3_TX=y +CONFIG_STM32_I2S_MCK=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_OTGFS_SOFINTR=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI3=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USBHOST=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_NXPLAYER=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USBHOST_ISOC_DISABLE=y +CONFIG_USBHOST_MSC=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/canard/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/canard/defconfig new file mode 100644 index 00000000000..69dd919b3cb --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/canard/defconfig @@ -0,0 +1,54 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_CANUTILS_LIBCANARDV0=y +CONFIG_CAN_EXTID=y +CONFIG_EXAMPLES_LIBCANARDV0=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_CAN1=y +CONFIG_STM32_CAN1_BAUD=500000 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_TIME64=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/cxxtest/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/cxxtest/defconfig new file mode 100644 index 00000000000..7ff72a672f4 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/cxxtest/defconfig @@ -0,0 +1,41 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_HAVE_CXX=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="cxxtest_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LIBC_MAX_EXITFUNS=4 +CONFIG_LIBM=y +CONFIG_MM_REGIONS=2 +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_START_DAY=2 +CONFIG_START_MONTH=11 +CONFIG_START_YEAR=2012 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_USART2=y +CONFIG_SYMTAB_ORDEREDBYNAME=y +CONFIG_TESTING_CXXTEST=y +CONFIG_UCLIBCXX=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/elf/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/elf/defconfig new file mode 100644 index 00000000000..66c7cd6e2f0 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/elf/defconfig @@ -0,0 +1,46 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BINFMT_CONSTRUCTORS=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_ROMDISK=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_CONSOLE_SYSLOG=y +CONFIG_ELF=y +CONFIG_ELF_STACKSIZE=4096 +CONFIG_EXAMPLES_ELF=y +CONFIG_FS_ROMFS=y +CONFIG_HAVE_CXX=y +CONFIG_INIT_ENTRYPOINT="elf_main" +CONFIG_INIT_STACKSIZE=4096 +CONFIG_INTELHEX_BINARY=y +CONFIG_LIBC_ENVPATH=y +CONFIG_MM_REGIONS=2 +CONFIG_PATH_INITIAL="/mnt/romfs" +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_STARTHOOK=y +CONFIG_START_DAY=26 +CONFIG_START_MONTH=10 +CONFIG_START_YEAR=2012 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_USART2=y +CONFIG_SYMTAB_ORDEREDBYNAME=y +CONFIG_USART2_SERIAL_CONSOLE=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/ipv6/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/ipv6/defconfig new file mode 100644 index 00000000000..b326192ac8c --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/ipv6/defconfig @@ -0,0 +1,91 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NET_IPv4 is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_ETH0_PHY_LAN8720=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FS_FAT=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LIBC_HOSTNAME="STM32F4-Discovery" +CONFIG_MMCSD=y +CONFIG_MMCSD_MULTIBLOCK_LIMIT=1 +CONFIG_MMCSD_SDIO=y +CONFIG_NET=y +CONFIG_NETINIT_IPv6NETMASK_8=0xff80 +CONFIG_NETINIT_NOMAC=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ICMPv6=y +CONFIG_NET_ICMPv6_NEIGHBOR=y +CONFIG_NET_ICMPv6_SOCKET=y +CONFIG_NET_IPv6=y +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=13 +CONFIG_START_MONTH=9 +CONFIG_START_YEAR=2014 +CONFIG_STM32F4DISBB=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_DMACAPABLE=y +CONFIG_STM32_ETHMAC=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PHYADDR=0 +CONFIG_STM32_PHYSR=31 +CONFIG_STM32_PHYSR_100FD=0x0018 +CONFIG_STM32_PHYSR_100HD=0x0008 +CONFIG_STM32_PHYSR_10FD=0x0014 +CONFIG_STM32_PHYSR_10HD=0x0004 +CONFIG_STM32_PHYSR_ALTCONFIG=y +CONFIG_STM32_PHYSR_ALTMODE=0x001c +CONFIG_STM32_PWR=y +CONFIG_STM32_RMII_EXTCLK=y +CONFIG_STM32_SDIO=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART6=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING6=y +CONFIG_USART6_RXBUFSIZE=64 +CONFIG_USART6_SERIAL_CONSOLE=y +CONFIG_USART6_TXBUFSIZE=64 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/kostest/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/kostest/defconfig new file mode 100644 index 00000000000..d827f8123ba --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/kostest/defconfig @@ -0,0 +1,46 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARM_MPU=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILD_PROTECTED=y +CONFIG_CONSOLE_SYSLOG=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="ostest_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NUTTX_USERSPACE=0x08020000 +CONFIG_PASS1_BUILDIR="boards/arm/stm32/stm32f4discovery/kernel" +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=22 +CONFIG_START_MONTH=3 +CONFIG_START_YEAR=2013 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_USART2=y +CONFIG_SYMTAB_ORDEREDBYNAME=y +CONFIG_TESTING_OSTEST=y +CONFIG_TESTING_OSTEST_NBARRIER_THREADS=3 +CONFIG_TESTING_OSTEST_STACKSIZE=2048 +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/lcd1602/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/lcd1602/defconfig new file mode 100644 index 00000000000..4ef089c06bc --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/lcd1602/defconfig @@ -0,0 +1,57 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_COMMON=y +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_EXAMPLES_SLCD=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LCD_BACKPACK=y +CONFIG_LCD_LCD1602=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_SLCD=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_I2C1=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/lwl/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/lwl/defconfig new file mode 100644 index 00000000000..84b7355ade6 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/lwl/defconfig @@ -0,0 +1,48 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LWL_CONSOLE=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_STANDARD_SERIAL=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_SYSTEM_NSH=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/max31855/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/max31855/defconfig new file mode 100644 index 00000000000..01f9501b354 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/max31855/defconfig @@ -0,0 +1,55 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_COMMON=y +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_MAX31855=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_SENSORS=y +CONFIG_SENSORS_MAX31855=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI2=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/max7219/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/max7219/defconfig new file mode 100644 index 00000000000..89a0f73aa2a --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/max7219/defconfig @@ -0,0 +1,83 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_DISABLE_OS_API is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CMP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +# CONFIG_NX_DISABLE_1BPP is not set +# CONFIG_NX_WRITEONLY is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXAMPLES_NXHELLO=y +CONFIG_EXAMPLES_NXHELLO_BPP=1 +CONFIG_EXAMPLES_NXHELLO_LISTENER_STACKSIZE=1536 +CONFIG_EXAMPLES_NXHELLO_STACKSIZE=1536 +CONFIG_FS_PROCFS=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_LCD=y +CONFIG_LCD_FRAMEBUFFER=y +CONFIG_LCD_MAX7219=y +CONFIG_LCD_NOGETRUN=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_MAX7219_NHORIZONTALBLKS=4 +CONFIG_MM_REGIONS=2 +CONFIG_MQ_MAXMSGSIZE=64 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NX=y +CONFIG_NXFONT_MONO5X8=y +CONFIG_NXSTART_SERVERSTACK=1536 +CONFIG_NX_BLOCKING=y +CONFIG_NX_MXCLIENTMSGS=32 +CONFIG_PREALLOC_MQ_MSGS=16 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_WAITPID=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_START_DAY=21 +CONFIG_START_MONTH=4 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/mmcsdspi/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/mmcsdspi/defconfig new file mode 100644 index 00000000000..11eb3a6fd0b --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/mmcsdspi/defconfig @@ -0,0 +1,72 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_CODECS_HASH_MD5=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_FAT_LFN=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_HEAP_COLORATION=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MMCSD=y +CONFIG_MM_REGIONS=2 +CONFIG_NETUTILS_CODECS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=30 +CONFIG_SCHED_WAITPID=y +CONFIG_SENDFILE_BUFSIZE=1024 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=17 +CONFIG_START_MONTH=10 +CONFIG_START_YEAR=2019 +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI2=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_TESTING_OSTEST=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/modbus_slave/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/modbus_slave/defconfig new file mode 100644 index 00000000000..7d2d779155c --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/modbus_slave/defconfig @@ -0,0 +1,63 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_MB_TCP_ENABLED is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_EXAMPLES_MODBUS=y +CONFIG_EXAMPLES_MODBUS_PORT=1 +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_MODBUS=y +CONFIG_MODBUS_SLAVE=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART1_BAUD=38400 +CONFIG_USART1_PARITY=2 +CONFIG_USART1_RS485=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/module/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/module/defconfig new file mode 100644 index 00000000000..9e34c0d79dc --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/module/defconfig @@ -0,0 +1,53 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARDCTL_ROMDISK=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_MODULE=y +CONFIG_FS_PROCFS=y +CONFIG_FS_ROMFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_MODULE=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/netnsh/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/netnsh/defconfig new file mode 100644 index 00000000000..d89a8ddd6cf --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/netnsh/defconfig @@ -0,0 +1,96 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_ETH0_PHY_LAN8720=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FS_FAT=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LIBC_HOSTNAME="STM32F4-Discovery" +CONFIG_MMCSD=y +CONFIG_MMCSD_MULTIBLOCK_LIMIT=1 +CONFIG_MMCSD_SDIO=y +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_NOMAC=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETUTILS_TELNETD=y +CONFIG_NETUTILS_TFTPC=y +CONFIG_NETUTILS_WEBCLIENT=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=13 +CONFIG_START_MONTH=9 +CONFIG_START_YEAR=2014 +CONFIG_STM32F4DISBB=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_DMACAPABLE=y +CONFIG_STM32_ETHMAC=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PHYADDR=0 +CONFIG_STM32_PHYSR=31 +CONFIG_STM32_PHYSR_100FD=0x0018 +CONFIG_STM32_PHYSR_100HD=0x0008 +CONFIG_STM32_PHYSR_10FD=0x0014 +CONFIG_STM32_PHYSR_10HD=0x0004 +CONFIG_STM32_PHYSR_ALTCONFIG=y +CONFIG_STM32_PHYSR_ALTMODE=0x001c +CONFIG_STM32_PWR=y +CONFIG_STM32_RMII_EXTCLK=y +CONFIG_STM32_SDIO=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART6=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_USART6_RXBUFSIZE=64 +CONFIG_USART6_SERIAL_CONSOLE=y +CONFIG_USART6_TXBUFSIZE=64 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/nsh/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/nsh/defconfig new file mode 100644 index 00000000000..345c93591bf --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/nsh/defconfig @@ -0,0 +1,51 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f427a_Cubus" +CONFIG_ARCH_BOARD_STM32F4A_CUBUS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/nxlines/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/nxlines/defconfig new file mode 100644 index 00000000000..b31b61b69ca --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/nxlines/defconfig @@ -0,0 +1,72 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_EXAMPLES_NXLINES_DEFAULT_COLORS is not set +# CONFIG_NXFONTS_DISABLE_16BPP is not set +# CONFIG_NXTK_DEFAULT_BORDERCOLORS is not set +# CONFIG_NX_DISABLE_16BPP is not set +# CONFIG_NX_PACKEDMSFIRST is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_EXAMPLES_NXLINES=y +CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x0320 +CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0xffe0 +CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=4 +CONFIG_EXAMPLES_NXLINES_BPP=16 +CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0xf7bb +CONFIG_EXAMPLES_NXLINES_LINECOLOR=0xffe0 +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="nxlines_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LCD=y +CONFIG_LCD_MAXCONTRAST=1 +CONFIG_LCD_MAXPOWER=255 +CONFIG_LCD_SSD1289=y +CONFIG_MM_REGIONS=2 +CONFIG_MQ_MAXMSGSIZE=64 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_NX=y +CONFIG_NXFONT_SANS22X29B=y +CONFIG_NXFONT_SANS23X27=y +CONFIG_NXTK_BORDERCOLOR1=0x5cb7 +CONFIG_NXTK_BORDERCOLOR2=0x21c9 +CONFIG_NXTK_BORDERCOLOR3=0xffdf +CONFIG_NX_BLOCKING=y +CONFIG_NX_KBD=y +CONFIG_NX_XYINPUT_MOUSE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_FSMC=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYMTAB_ORDEREDBYNAME=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/pm/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/pm/defconfig new file mode 100644 index 00000000000..015f1ea72b5 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/pm/defconfig @@ -0,0 +1,55 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_ARCH_LEDS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_CUSTOM_PMINIT=y +CONFIG_ARCH_IDLE_CUSTOM=y +CONFIG_ARCH_IRQBUTTONS=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PM=y +CONFIG_PM_BUTTONS=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_RTC_ALARM=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_HPWORKSTACKSIZE=1024 +CONFIG_SCHED_WAITPID=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_RTC=y +CONFIG_STM32_TIM1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/posix_spawn/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/posix_spawn/defconfig new file mode 100644 index 00000000000..7efe0e38580 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/posix_spawn/defconfig @@ -0,0 +1,49 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BINFMT_CONSTRUCTORS=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_APP_SYMTAB=y +CONFIG_BOARDCTL_ROMDISK=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_CONSOLE_SYSLOG=y +CONFIG_ELF=y +CONFIG_EXAMPLES_POSIXSPAWN=y +CONFIG_EXECFUNCS_HAVE_SYMTAB=y +CONFIG_EXECFUNCS_NSYMBOLS_VAR="g_spawn_nexports" +CONFIG_EXECFUNCS_SYMTAB_ARRAY="g_spawn_exports" +CONFIG_FS_ROMFS=y +CONFIG_HAVE_CXX=y +CONFIG_INIT_ENTRYPOINT="posix_spawn_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LIBC_ENVPATH=y +CONFIG_LIBC_EXECFUNCS=y +CONFIG_MM_REGIONS=2 +CONFIG_PATH_INITIAL="/mnt/romfs" +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_STARTHOOK=y +CONFIG_START_DAY=26 +CONFIG_START_MONTH=10 +CONFIG_START_YEAR=2012 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_USART2=y +CONFIG_SYMTAB_ORDEREDBYNAME=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/pseudoterm/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/pseudoterm/defconfig new file mode 100644 index 00000000000..e167a640cf6 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/pseudoterm/defconfig @@ -0,0 +1,53 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_PTYTEST=y +CONFIG_EXAMPLES_PTYTEST_POLL=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_PSEUDOTERM=y +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/rgbled/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/rgbled/defconfig new file mode 100644 index 00000000000..812a216e57a --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/rgbled/defconfig @@ -0,0 +1,63 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_EXAMPLES_RGBLED=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="rgbled_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_PWM=y +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RGBLED=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_TIM1=y +CONFIG_STM32_TIM1_PWM=y +CONFIG_STM32_TIM2=y +CONFIG_STM32_TIM2_CH2OUT=y +CONFIG_STM32_TIM2_CHANNEL=2 +CONFIG_STM32_TIM2_PWM=y +CONFIG_STM32_TIM3=y +CONFIG_STM32_TIM3_CH3OUT=y +CONFIG_STM32_TIM3_CHANNEL=3 +CONFIG_STM32_TIM3_PWM=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/rndis/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/rndis/defconfig new file mode 100644 index 00000000000..5edd7675b01 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/rndis/defconfig @@ -0,0 +1,99 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ALLOW_BSD_COMPONENTS=y +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARDCTL_USBDEVCTRL=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_ELF=y +CONFIG_EXAMPLES_HELLO=m +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FS_FAT=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3072 +CONFIG_INTELHEX_BINARY=y +CONFIG_LIBC_ENVPATH=y +CONFIG_LIBC_EXECFUNCS=y +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSSERVER_IPv4ADDR=0x0 +CONFIG_NETDEVICES=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DRIPADDR=0x0 +CONFIG_NETINIT_MACADDR_1=0xdeadcafe +CONFIG_NETINIT_NETMASK=0x0 +CONFIG_NETINIT_NOMAC=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_IPERF=y +CONFIG_NETUTILS_IPERFTEST_DEVNAME="eth0" +CONFIG_NETUTILS_TELNETD=y +CONFIG_NETUTILS_WEBCLIENT=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_LOOPBACK=y +CONFIG_NET_STATISTICS=y +CONFIG_NET_TCP=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NFS=y +CONFIG_NFS_STATISTICS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_FILE_APPS=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_READLINE=y +CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=3072 +CONFIG_PATH_INITIAL="/mnt/nfs/bin" +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RNDIS=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_WAITPID=y +CONFIG_SENSORS=y +CONFIG_START_DAY=13 +CONFIG_START_MONTH=9 +CONFIG_START_YEAR=2014 +CONFIG_STM32_DMA2=y +CONFIG_STM32_DMACAPABLE=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYMTAB_ORDEREDBYNAME=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_NSH_SYMTAB=y +CONFIG_SYSTEM_NSH_SYMTAB_ARRAYNAME="g_symtab" +CONFIG_SYSTEM_NSH_SYMTAB_COUNTNAME="g_nsymbols" +CONFIG_SYSTEM_PING=y +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USBDEV=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/sporadic/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/sporadic/defconfig new file mode 100644 index 00000000000..77c2f404ef3 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/sporadic/defconfig @@ -0,0 +1,51 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_FS_PROCFS=y +CONFIG_HOST_WINDOWS=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_SCHED_SPORADIC=y +CONFIG_SCHED_SPORADIC_MAXREPL=5 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=3 +CONFIG_START_YEAR=2021 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART6=y +CONFIG_SYSTEM_NSH=y +CONFIG_TESTING_OSTEST=y +CONFIG_USART6_RXBUFSIZE=128 +CONFIG_USART6_SERIAL_CONSOLE=y +CONFIG_USART6_TXBUFSIZE=128 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/st7789/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/st7789/defconfig new file mode 100644 index 00000000000..0d4f2a975e5 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/st7789/defconfig @@ -0,0 +1,66 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_DRIVERS_VIDEO=y +CONFIG_EXAMPLES_FB=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_LCD=y +CONFIG_LCD_FRAMEBUFFER=y +CONFIG_LCD_NOGETRUN=y +CONFIG_LCD_PORTRAIT=y +CONFIG_LCD_ST7789=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_NXFONTS_DISABLE_1BPP=y +CONFIG_NXFONTS_DISABLE_24BPP=y +CONFIG_NXFONTS_DISABLE_2BPP=y +CONFIG_NXFONTS_DISABLE_32BPP=y +CONFIG_NXFONTS_DISABLE_4BPP=y +CONFIG_NXFONTS_DISABLE_8BPP=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_SPI_CMDDATA=y +CONFIG_START_DAY=6 +CONFIG_START_MONTH=12 +CONFIG_START_YEAR=2011 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_VIDEO_FB=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/usbmsc/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/usbmsc/defconfig new file mode 100644 index 00000000000..dd5b6a8d8c7 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/usbmsc/defconfig @@ -0,0 +1,59 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FS_FAT=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_WAITPID=y +CONFIG_START_DAY=27 +CONFIG_START_YEAR=2013 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSLOG_CHAR=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_USBMSC=y +CONFIG_SYSTEM_USBMSC_DEVPATH1="/dev/ram0" +CONFIG_TASK_NAME_SIZE=0 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USBDEV=y +CONFIG_USBMSC=y +CONFIG_USBMSC_REMOVABLE=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/configs/usbnsh/defconfig b/boards/arm/stm32/stm32f427a_Cubus/configs/usbnsh/defconfig new file mode 100644 index 00000000000..bb663d104e2 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/configs/usbnsh/defconfig @@ -0,0 +1,58 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_ARCH_FPU is not set +# CONFIG_DEV_CONSOLE is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="stm32f4discovery" +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F407VG=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARDCTL_USBDEVCTRL=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_RXBUFSIZE=256 +CONFIG_CDCACM_TXBUFSIZE=256 +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_FS_PROCFS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=2048 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INTELHEX_BINARY=y +CONFIG_MM_REGIONS=2 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_PREALLOC_TIMERS=4 +CONFIG_RAMLOG=y +CONFIG_RAMLOG_BUFSIZE=4096 +CONFIG_RAMLOG_SYSLOG=y +CONFIG_RAM_SIZE=114688 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=27 +CONFIG_START_YEAR=2013 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_USART2=y +CONFIG_SYSTEM_NSH=y +CONFIG_USBDEV=y diff --git a/boards/arm/stm32/stm32f427a_Cubus/include/board.h b/boards/arm/stm32/stm32f427a_Cubus/include/board.h new file mode 100644 index 00000000000..0080d63a8b6 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/include/board.h @@ -0,0 +1,351 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/include/board.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __BOARDS_ARM_STM32_STM32F427A_CUBUS_INCLUDE_BOARD_H +#define __BOARDS_ARM_STM32_STM32F427A_CUBUS_INCLUDE_BOARD_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +# include +#endif + +/* Do not include STM32-specific header files here */ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Clocking *****************************************************************/ + +/* The STM32F4 Discovery board features a single 8MHz crystal. + * Space is provided for a 32kHz RTC backup crystal, but it is not stuffed. + * + * This is the canonical configuration: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL + * configuration + * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 8000000 (STM32_BOARD_XTAL) + * PLLM : 8 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PLLQ) + * Main regulator output voltage : Scale1 mode Needed for high speed + * SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 8MHz + * LSE - 32.768 kHz + */ + +#define STM32_BOARD_XTAL 24000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (8,000,000 / 8) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY + +/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ + +#define BOARD_TIM1_FREQUENCY STM32_HCLK_FREQUENCY +#define BOARD_TIM2_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM3_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM4_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM5_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM6_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM7_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM8_FREQUENCY STM32_HCLK_FREQUENCY + +/* SDIO dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(118+2)=400 KHz + */ + +#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* Alternate function pin selections ****************************************/ + +/* CAN */ + +#ifndef CONFIG_STM32_FSMC +# define GPIO_CAN1_RX GPIO_CAN1_RX_3 +# define GPIO_CAN1_TX GPIO_CAN1_TX_3 +#endif + +#ifndef CONFIG_STM32_ETHMAC +# define GPIO_CAN2_RX GPIO_CAN2_RX_1 +# define GPIO_CAN2_TX GPIO_CAN2_TX_1 +#endif + +/* USART1 */ + +#ifdef CONFIG_USART1_RS485 + /* Lets use for RS485 on pins: PB6 and PB7 */ + +# define GPIO_USART1_TX GPIO_USART1_TX_2 +# define GPIO_USART1_RX GPIO_USART1_RX_2 + + /* RS485 DIR pin: PA15 */ + +# define GPIO_USART1_RS485_DIR (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz |\ + GPIO_OUTPUT_CLEAR | GPIO_PORTA | GPIO_PIN15) + +#endif + +/* USART2: + * + * The STM32F4 Discovery has no on-board serial devices, but the console is + * brought out to PA2 (TX) and PA3 (RX) for connection to an external serial + * device. (See the README.txt file for other options) + * + * These pins selections, however, conflict with pin usage on the + * STM32F4DIS-BB. + */ + +#ifndef CONFIG_STM32F4DISBB +# define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3, P1 pin 13 */ +# define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2, P1 pin 14 */ +# define GPIO_USART2_CTS GPIO_USART2_CTS_1 /* PA0, P1 pin 11 */ +# define GPIO_USART2_RTS GPIO_USART2_RTS_1 /* PA1, P1 pin 12 (conflict with USER button) */ +#endif + +/* USART3: + * + * Used in pseudoterm configuration and also with the BT860 HCI UART. + * RTS/CTS Flow control support is needed by the HCI UART. + * + * There are conflicts with the STM32F4DIS-BB Ethernet in this configuration + * when Ethernet is enabled: + * + * PB-11 conflicts with Ethernet TXEN + * PB-13 conflicts with Ethernet TXD1 + * + * UART3 TXD and RXD are available on CON4 PD8 and PD8 of the STM32F4DIS-BB, + * respectively, but not CTS or RTS. For now we assume that Ethernet is not + * enabled if USART3 is used in a configuration with the STM32F4DIS-BB. + */ + +#define GPIO_USART3_TX GPIO_USART3_TX_1 /* PB10, P1 pin 34 (also MP45DT02 CLK_IN) */ +#define GPIO_USART3_RX GPIO_USART3_RX_1 /* PB11, P1 pin 35 */ +#define GPIO_USART3_CTS GPIO_USART3_CTS_1 /* PB13, P1 pin 37 */ +#define GPIO_USART3_RTS GPIO_USART3_RTS_1 /* PB14, P1 pin 38 */ + +/* USART6: + * + * The STM32F4DIS-BB base board provides RS-232 drivers and a DB9 connector + * for USART6. This is the preferred serial console for use with the + * STM32F4DIS-BB. + * + * NOTE: CTS and RTS are not brought out to the RS-232 connector on the + * baseboard. + */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 (also I2S3_MCK and P2 pin 48) */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 (also P2 pin 47) */ + +/* PWM + * + * The STM32F4 Discovery has no real on-board PWM devices, but the board + * can be configured to output a pulse train using TIM4 CH2 on PD13. + */ + +#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2 + +/* Capture + * + * The STM32F4 Discovery has no real on-board pwm capture devices, but the + * board can be configured to capture pwm using TIM3 CH2 PB5. + */ + +#define GPIO_TIM3_CH2IN GPIO_TIM3_CH2IN_2 +#define GPIO_TIM3_CH1IN GPIO_TIM3_CH2IN_2 + +/* RGB LED + * + * R = TIM1 CH1 on PE9 | G = TIM2 CH2 on PA1 | B = TIM3 CH3 on PB0 + */ + +#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2 +#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1 +#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1 + +/* SPI - There is a MEMS device on SPI1 using these pins: */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +/* SPI DMA -- As used for I2S DMA transfer with the audio configuration */ + +#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 +#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 + +/* SPI2 - Test MAX31855 on SPI2 PB10 = SCK, PB14 = MISO */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 + +/* SPI2 DMA -- As used for MMC/SD SPI */ + +#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX +#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX + +/* SPI3 DMA -- As used for I2S DMA transfer with the audio configuration */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_1 + +#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1 +#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_1 + +/* I2S3 - CS43L22 configuration uses I2S3 */ + +#define GPIO_I2S3_SD GPIO_I2S3_SD_2 +#define GPIO_I2S3_CK GPIO_I2S3_CK_2 +#define GPIO_I2S3_WS GPIO_I2S3_WS_1 + +#define DMACHAN_I2S3_RX DMAMAP_SPI3_RX_2 +#define DMACHAN_I2S3_TX DMAMAP_SPI3_TX_2 + +/* I2C. Only I2C1 is available on the stm32f4discovery. I2C1_SCL and + * I2C1_SDA are available on the following pins: + * + * - PB6 is I2C1_SCL + * - PB9 is I2C1_SDA + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 + +/* Timer Inputs/Outputs (see the README.txt file for options) */ + +#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_2 +#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1 + +#define GPIO_TIM8_CH1IN GPIO_TIM8_CH1IN_1 +#define GPIO_TIM8_CH2IN GPIO_TIM8_CH2IN_1 + +/* ZERO CROSS pin definition */ + +#define BOARD_ZEROCROSS_GPIO \ + (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0) + + +#endif /* __BOARDS_ARM_STM32_STM32F4DISCOVERY_INCLUDE_BOARD_H */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/kernel/Makefile b/boards/arm/stm32/stm32f427a_Cubus/kernel/Makefile new file mode 100644 index 00000000000..127caca0137 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/kernel/Makefile @@ -0,0 +1,92 @@ +############################################################################ +# boards/arm/stm32/stm32f4discovery/kernel/Makefile +# +# Licensed to the Apache Software Foundation (ASF) under one or more +# contributor license agreements. See the NOTICE file distributed with +# this work for additional information regarding copyright ownership. The +# ASF licenses this file to you under the Apache License, Version 2.0 (the +# "License"); you may not use this file except in compliance with the +# License. You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT +# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the +# License for the specific language governing permissions and limitations +# under the License. +# +############################################################################ + +include $(TOPDIR)/Make.defs + +# The entry point name (if none is provided in the .config file) + +CONFIG_INIT_ENTRYPOINT ?= user_start +ENTRYPT = $(patsubst "%",%,$(CONFIG_INIT_ENTRYPOINT)) + +# Get the paths to the libraries and the links script path in format that +# is appropriate for the host OS + +USER_LIBPATHS = $(addprefix -L,$(call CONVERT_PATH,$(addprefix $(TOPDIR)$(DELIM),$(dir $(USERLIBS))))) +USER_LDSCRIPT = -T $(call CONVERT_PATH,$(BOARD_DIR)$(DELIM)scripts$(DELIM)memory.ld) +USER_LDSCRIPT += -T $(call CONVERT_PATH,$(BOARD_DIR)$(DELIM)scripts$(DELIM)user-space.ld) +USER_HEXFILE += $(call CONVERT_PATH,$(TOPDIR)$(DELIM)nuttx_user.hex) +USER_SRECFILE += $(call CONVERT_PATH,$(TOPDIR)$(DELIM)nuttx_user.srec) +USER_BINFILE += $(call CONVERT_PATH,$(TOPDIR)$(DELIM)nuttx_user.bin) + +USER_LDFLAGS = --undefined=$(ENTRYPT) --entry=$(ENTRYPT) $(USER_LDSCRIPT) +USER_LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(USERLIBS)))) +USER_LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}" + +# Source files + +CSRCS = stm32_userspace.c +COBJS = $(CSRCS:.c=$(OBJEXT)) +OBJS = $(COBJS) + +# Targets: + +all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map +.PHONY: nuttx_user.elf depend clean distclean + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +# Create the nuttx_user.elf file containing all of the user-mode code + +nuttx_user.elf: $(OBJS) + $(Q) $(LD) -o $@ $(USER_LDFLAGS) $(USER_LIBPATHS) $(OBJS) --start-group $(USER_LDLIBS) $(USER_LIBGCC) --end-group + +$(TOPDIR)$(DELIM)nuttx_user.elf: nuttx_user.elf + @echo "LD: nuttx_user.elf" + $(Q) cp -a nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.elf +ifeq ($(CONFIG_INTELHEX_BINARY),y) + @echo "CP: nuttx_user.hex" + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex nuttx_user.elf $(USER_HEXFILE) +endif +ifeq ($(CONFIG_MOTOROLA_SREC),y) + @echo "CP: nuttx_user.srec" + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec nuttx_user.elf $(USER_SRECFILE) +endif +ifeq ($(CONFIG_RAW_BINARY),y) + @echo "CP: nuttx_user.bin" + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary nuttx_user.elf $(USER_BINFILE) +endif + +$(TOPDIR)$(DELIM)User.map: nuttx_user.elf + @echo "MK: User.map" + $(Q) $(NM) nuttx_user.elf >$(TOPDIR)$(DELIM)User.map + $(Q) $(CROSSDEV)size nuttx_user.elf + +.depend: + +depend: .depend + +clean: + $(call DELFILE, nuttx_user.elf) + $(call DELFILE, "$(TOPDIR)$(DELIM)nuttx_user.*") + $(call DELFILE, "$(TOPDIR)$(DELIM)User.map") + $(call CLEAN) + +distclean: clean diff --git a/boards/arm/stm32/stm32f427a_Cubus/kernel/stm32_userspace.c b/boards/arm/stm32/stm32f427a_Cubus/kernel/stm32_userspace.c new file mode 100644 index 00000000000..f28aca6415a --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/kernel/stm32_userspace.c @@ -0,0 +1,114 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/kernel/stm32_userspace.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include +#include +#include + +#if defined(CONFIG_BUILD_PROTECTED) && !defined(__KERNEL__) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_NUTTX_USERSPACE +# error "CONFIG_NUTTX_USERSPACE not defined" +#endif + +#if CONFIG_NUTTX_USERSPACE != 0x08020000 +# error "CONFIG_NUTTX_USERSPACE must be 0x08020000 to match memory.ld" +#endif + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* These 'addresses' of these values are setup by the linker script. They are + * not actual uint32_t storage locations! They are only used meaningfully in + * the following way: + * + * - The linker script defines, for example, the symbol_sdata. + * - The declaration extern uint32_t _sdata; makes C happy. C will believe + * that the value _sdata is the address of a uint32_t variable _data (it + * is not!). + * - We can recover the linker value then by simply taking the address of + * of _data. like: uint32_t *pdata = &_sdata; + */ + +extern uint32_t _stext; /* Start of .text */ +extern uint32_t _etext; /* End_1 of .text + .rodata */ +extern const uint32_t _eronly; /* End+1 of read only section (.text + .rodata) */ +extern uint32_t _sdata; /* Start of .data */ +extern uint32_t _edata; /* End+1 of .data */ +extern uint32_t _sbss; /* Start of .bss */ +extern uint32_t _ebss; /* End+1 of .bss */ + +/* This is the user space entry point */ + +int CONFIG_INIT_ENTRYPOINT(int argc, char *argv[]); + +const struct userspace_s userspace locate_data(".userspace") = +{ + /* General memory map */ + + .us_entrypoint = (main_t)CONFIG_INIT_ENTRYPOINT, + .us_textstart = (uintptr_t)&_stext, + .us_textend = (uintptr_t)&_etext, + .us_datasource = (uintptr_t)&_eronly, + .us_datastart = (uintptr_t)&_sdata, + .us_dataend = (uintptr_t)&_edata, + .us_bssstart = (uintptr_t)&_sbss, + .us_bssend = (uintptr_t)&_ebss, + + /* Memory manager heap structure */ + + .us_heap = &g_mmheap, + + /* Task/thread startup routines */ + + .task_startup = nxtask_startup, + + /* Signal handler trampoline */ + + .signal_handler = up_signal_handler, + + /* User-space work queue support (declared in include/nuttx/wqueue.h) */ + +#ifdef CONFIG_LIBC_USRWORK + .work_usrstart = work_usrstart, +#endif +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#endif /* CONFIG_BUILD_PROTECTED && !__KERNEL__ */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/scripts/Make.defs b/boards/arm/stm32/stm32f427a_Cubus/scripts/Make.defs new file mode 100644 index 00000000000..11455556844 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/scripts/Make.defs @@ -0,0 +1,59 @@ +############################################################################ +# boards/arm/stm32/stm32f4discovery/scripts/Make.defs +# +# Licensed to the Apache Software Foundation (ASF) under one or more +# contributor license agreements. See the NOTICE file distributed with +# this work for additional information regarding copyright ownership. The +# ASF licenses this file to you under the Apache License, Version 2.0 (the +# "License"); you may not use this file except in compliance with the +# License. You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT +# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the +# License for the specific language governing permissions and limitations +# under the License. +# +############################################################################ + +include $(TOPDIR)/.config +include $(TOPDIR)/tools/Config.mk +include $(TOPDIR)/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = ld.script +ARCHSCRIPT += $(BOARD_DIR)$(DELIM)scripts$(DELIM)$(LDSCRIPT) + +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +ifneq ($(CONFIG_ARMV7M_TOOLCHAIN_CLANG),y) + ARCHCFLAGS += -funwind-tables + ARCHCXXFLAGS += -funwind-tables +endif + +CFLAGS := $(ARCHCFLAGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS := $(ARCHCXXFLAGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS := $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS) +AFLAGS := $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +# Loadable module definitions + +CMODULEFLAGS = $(CFLAGS) -mlong-calls # --target1-abs + +LDMODULEFLAGS = -r -e module_initialize +LDMODULEFLAGS += -T $(call CONVERT_PATH,$(TOPDIR)/libs/libc/modlib/gnu-elf.ld) + +# ELF module definitions + +CELFFLAGS = $(CFLAGS) -mlong-calls # --target1-abs +CXXELFFLAGS = $(CXXFLAGS) -mlong-calls # --target1-abs + +LDELFFLAGS = -r -e main +LDELFFLAGS += -T $(call CONVERT_PATH,$(TOPDIR)/binfmt/libelf/gnu-elf.ld) diff --git a/boards/arm/stm32/stm32f427a_Cubus/scripts/kernel-space.ld b/boards/arm/stm32/stm32f427a_Cubus/scripts/kernel-space.ld new file mode 100644 index 00000000000..7a6a61b111f --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/scripts/kernel-space.ld @@ -0,0 +1,96 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/scripts/kernel-space.ld + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > kflash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > kflash + + .ARM.extab : { + *(.ARM.extab*) + } > kflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > kflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + . = ALIGN(4); + _edata = ABSOLUTE(.); + } > ksram AT > kflash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > ksram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/scripts/ld.script b/boards/arm/stm32/stm32f427a_Cubus/scripts/ld.script new file mode 100644 index 00000000000..cfa333796ff --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/scripts/ld.script @@ -0,0 +1,123 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/scripts/ld.script + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* The STM32F407VG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 192Kb of SRAM. SRAM is split up into three 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 + * the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +EXTERN(_vectors) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : ALIGN(4) { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : ALIGN(4) { + *(.ARM.extab*) + } > flash + + .ARM.exidx : ALIGN(4) { + __exidx_start = ABSOLUTE(.); + *(.ARM.exidx*) + __exidx_end = ABSOLUTE(.); + } > flash + + .tdata : { + _stdata = ABSOLUTE(.); + *(.tdata .tdata.* .gnu.linkonce.td.*); + _etdata = ABSOLUTE(.); + } > flash + + .tbss : { + _stbss = ABSOLUTE(.); + *(.tbss .tbss.* .gnu.linkonce.tb.* .tcommon); + _etbss = ABSOLUTE(.); + } > flash + + _eronly = ABSOLUTE(.); + + .data : ALIGN(4) { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + . = ALIGN(4); + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : ALIGN(4) { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/scripts/memory.ld b/boards/arm/stm32/stm32f427a_Cubus/scripts/memory.ld new file mode 100644 index 00000000000..5e537b6fbe9 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/scripts/memory.ld @@ -0,0 +1,85 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/scripts/memory.ld + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* The STM32F407VG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 192Kb of SRAM. SRAM is split up into three 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 + * the 0x0800:0000 address range. + * + * For MPU support, the kernel-mode NuttX section is assumed to be 128Kb of + * FLASH and 4Kb of SRAM. That is an excessive amount for the kernel which + * should fit into 64KB and, of course, can be optimized as needed (See + * also boards/arm/stm32/stm32f4discovery/scripts/kernel-space.ld). Allowing the + * additional does permit addition debug instrumentation to be added to the + * kernel space without overflowing the partition. + * + * Alignment of the user space FLASH partition is also a critical factor: + * The user space FLASH partition will be spanned with a single region of + * size 2**n bytes. The alignment of the user-space region must be the same. + * As a consequence, as the user-space increases in size, the alignment + * requirement also increases. + * + * This alignment requirement means that the largest user space FLASH region + * you can have will be 512KB at it would have to be positioned at + * 0x08800000. If you change this address, don't forget to change the + * CONFIG_NUTTX_USERSPACE configuration setting to match and to modify + * the check in kernel/userspace.c. + * + * For the same reasons, the maximum size of the SRAM mapping is limited to + * 4KB. Both of these alignment limitations could be reduced by using + * multiple regions to map the FLASH/SDRAM range or perhaps with some + * clever use of subregions. + * + * A detailed memory map for the 112KB SRAM region is as follows: + * + * 0x20000 0000: Kernel .data region. Typical size: 0.1KB + * ------- ---- Kernel .bss region. Typical size: 1.8KB + * 0x20000 0800: Kernel IDLE thread stack (approximate). Size is + * determined by CONFIG_IDLETHREAD_STACKSIZE and + * adjustments for alignment. Typical is 1KB. + * ------- ---- Padded to 4KB + * 0x20000 1000: User .data region. Size is variable. + * ------- ---- User .bss region Size is variable. + * 0x20000 2000: Beginning of kernel heap. Size determined by + * CONFIG_MM_KERNEL_HEAPSIZE. + * ------- ---- Beginning of user heap. Can vary with other settings. + * 0x20001 c000: End+1 of CPU RAM + */ + +MEMORY +{ + /* 1024Kb FLASH */ + + kflash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + uflash (rx) : ORIGIN = 0x08020000, LENGTH = 128K + xflash (rx) : ORIGIN = 0x08040000, LENGTH = 768K + + /* 112Kb of contiguous SRAM */ + + ksram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K + usram (rwx) : ORIGIN = 0x20001000, LENGTH = 4K + xsram (rwx) : ORIGIN = 0x20002000, LENGTH = 104K +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/scripts/user-space.ld b/boards/arm/stm32/stm32f427a_Cubus/scripts/user-space.ld new file mode 100644 index 00000000000..e647964b6fd --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/scripts/user-space.ld @@ -0,0 +1,98 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/scripts/user-space.ld + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ + +OUTPUT_ARCH(arm) +SECTIONS +{ + .userspace : { + *(.userspace) + } > uflash + + .text : { + _stext = ABSOLUTE(.); + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > uflash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > uflash + + .ARM.extab : { + *(.ARM.extab*) + } > uflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > uflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + . = ALIGN(4); + _edata = ABSOLUTE(.); + } > usram AT > uflash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > usram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/Make.defs b/boards/arm/stm32/stm32f427a_Cubus/src/Make.defs new file mode 100644 index 00000000000..1793630ca3e --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/Make.defs @@ -0,0 +1,180 @@ +############################################################################ +# boards/arm/stm32/stm32f4discovery/src/Make.defs +# +# Licensed to the Apache Software Foundation (ASF) under one or more +# contributor license agreements. See the NOTICE file distributed with +# this work for additional information regarding copyright ownership. The +# ASF licenses this file to you under the Apache License, Version 2.0 (the +# "License"); you may not use this file except in compliance with the +# License. You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT +# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the +# License for the specific language governing permissions and limitations +# under the License. +# +############################################################################ + +include $(TOPDIR)/Make.defs + +CSRCS = stm32_boot.c stm32_bringup.c stm32_spi.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_AUDIO_CS43L22),y) +CSRCS += stm32_cs43l22.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_STM32_CAN_CHARDRIVER),y) +CSRCS += stm32_can.c +endif + +ifeq ($(CONFIG_STM32_OTGFS),y) +CSRCS += stm32_usb.c +endif + +ifeq ($(CONFIG_LCD_ST7567),y) +CSRCS += stm32_st7567.c +endif + +ifeq ($(CONFIG_ENC28J60),y) +CSRCS += stm32_enc28j60.c +endif + +ifeq ($(CONFIG_LPWAN_SX127X),y) +CSRCS += stm32_sx127x.c +endif + +ifeq ($(CONFIG_LCD_MAX7219),y) +CSRCS += stm32_max7219.c +endif + +ifeq ($(CONFIG_LCD_ST7032),y) +CSRCS += stm32_st7032.c +endif + +ifeq ($(CONFIG_PCA9635PW),y) +CSRCS += stm32_pca9635.c +endif + +ifeq ($(CONFIG_STM32_SDIO),y) +CSRCS += stm32_sdio.c +endif + +ifeq ($(CONFIG_STM32_ETHMAC),y) +CSRCS += stm32_ethernet.c +endif + +ifeq ($(CONFIG_LEDS_MAX7219),y) +CSRCS += stm32_max7219_leds.c +endif + +ifeq ($(CONFIG_RGBLED),y) +CSRCS += stm32_rgbled.c +endif + +ifeq ($(CONFIG_RTC_DS1307),y) +CSRCS += stm32_ds1307.c +endif + +ifeq ($(CONFIG_PWM),y) +CSRCS += stm32_pwm.c +endif + +ifeq ($(CONFIG_CAPTURE),y) +CSRCS += stm32_capture.c +endif + +ifeq ($(CONFIG_BOARDCTL),y) +CSRCS += stm32_appinit.c +ifeq ($(CONFIG_BOARDCTL_RESET),y) +CSRCS += stm32_reset.c +endif +endif + +ifeq ($(CONFIG_ARCH_CUSTOM_PMINIT),y) +CSRCS += stm32_pm.c +endif + +ifeq ($(CONFIG_PM_BUTTONS),y) +CSRCS += stm32_pmbuttons.c +endif + +ifeq ($(CONFIG_ARCH_IDLE_CUSTOM),y) +CSRCS += stm32_idle.c +endif + +ifeq ($(CONFIG_STM32_FSMC),y) +CSRCS += stm32_extmem.c + +ifeq ($(CONFIG_LCD_SSD1289),y) +CSRCS += stm32_ssd1289.c +endif +endif + +ifeq ($(CONFIG_LCD_SSD1351),y) +CSRCS += stm32_ssd1351.c +endif + +ifeq ($(CONFIG_LCD_UG2864AMBAG01),y) +CSRCS += stm32_ug2864ambag01.c +endif + +ifeq ($(CONFIG_LCD_UG2864HSWEG01),y) +CSRCS += stm32_ug2864hsweg01.c +endif + +ifeq ($(CONFIG_TIMER),y) +CSRCS += stm32_timer.c +endif + +ifeq ($(CONFIG_STM32_HCIUART),y) +ifeq ($(CONFIG_BLUETOOTH_UART),y) +CSRCS += stm32_hciuart.c +endif +endif + +ifeq ($(CONFIG_STM32_ROMFS),y) +CSRCS += stm32_romfs_initialize.c +endif + +ifeq ($(CONFIG_BOARDCTL_UNIQUEID),y) +CSRCS += stm32_uid.c +endif + +ifeq ($(CONFIG_USBMSC),y) +CSRCS += stm32_usbmsc.c +endif + +ifneq ($(CONFIG_STM32_ETHMAC),y) +ifeq ($(CONFIG_NETDEVICES),y) +CSRCS += stm32_netinit.c +endif +endif + +ifeq ($(CONFIG_MMCSD_SPI),y) +CSRCS += stm32_mmcsd.c +endif + +ifeq ($(CONFIG_WL_GS2200M),y) +CSRCS += stm32_gs2200m.c +endif + +ifeq ($(CONFIG_LCD_ST7789),y) +CSRCS += stm32_st7789.c +endif + +DEPPATH += --dep-path board +VPATH += :board +CFLAGS += $(shell $(INCDIR) "$(CC)" $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)board) diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_appinit.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_appinit.c new file mode 100644 index 00000000000..4000c42307a --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_appinit.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_appinit.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef OK +# define OK 0 +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initialization logic and the + * matching application logic. The value could be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ +#ifdef CONFIG_BOARD_LATE_INITIALIZE + /* Board initialization already performed by board_late_initialize() */ + + return OK; +#else + /* Perform board-specific initialization */ + + return stm32_bringup(); +#endif +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_autoleds.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_autoleds.c new file mode 100644 index 00000000000..91abce3bee6 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_autoleds.c @@ -0,0 +1,230 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_autoleds.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" +#include "stm32.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* The following definitions map the encoded LED setting to GPIO settings */ + +#define STM32F4_LED1 (1 << 0) +#define STM32F4_LED2 (1 << 1) +#define STM32F4_LED3 (1 << 2) +#define STM32F4_LED4 (1 << 3) + +#define ON_SETBITS_SHIFT (0) +#define ON_CLRBITS_SHIFT (4) +#define OFF_SETBITS_SHIFT (8) +#define OFF_CLRBITS_SHIFT (12) + +#define ON_BITS(v) ((v) & 0xff) +#define OFF_BITS(v) (((v) >> 8) & 0x0ff) +#define SETBITS(b) ((b) & 0x0f) +#define CLRBITS(b) (((b) >> 4) & 0x0f) + +#define ON_SETBITS(v) (SETBITS(ON_BITS(v)) +#define ON_CLRBITS(v) (CLRBITS(ON_BITS(v)) +#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v)) +#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v)) + +#define LED_STARTED_ON_SETBITS ((STM32F4_LED1) << ON_SETBITS_SHIFT) +#define LED_STARTED_ON_CLRBITS ((STM32F4_LED2|STM32F4_LED3|STM32F4_LED4) << ON_CLRBITS_SHIFT) +#define LED_STARTED_OFF_SETBITS (0 << OFF_SETBITS_SHIFT) +#define LED_STARTED_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2|STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_HEAPALLOCATE_ON_SETBITS ((STM32F4_LED2) << ON_SETBITS_SHIFT) +#define LED_HEAPALLOCATE_ON_CLRBITS ((STM32F4_LED1|STM32F4_LED3|STM32F4_LED4) << ON_CLRBITS_SHIFT) +#define LED_HEAPALLOCATE_OFF_SETBITS ((STM32F4_LED1) << OFF_SETBITS_SHIFT) +#define LED_HEAPALLOCATE_OFF_CLRBITS ((STM32F4_LED2|STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_IRQSENABLED_ON_SETBITS ((STM32F4_LED1|STM32F4_LED2) << ON_SETBITS_SHIFT) +#define LED_IRQSENABLED_ON_CLRBITS ((STM32F4_LED3|STM32F4_LED4) << ON_CLRBITS_SHIFT) +#define LED_IRQSENABLED_OFF_SETBITS ((STM32F4_LED2) << OFF_SETBITS_SHIFT) +#define LED_IRQSENABLED_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_STACKCREATED_ON_SETBITS ((STM32F4_LED3) << ON_SETBITS_SHIFT) +#define LED_STACKCREATED_ON_CLRBITS ((STM32F4_LED1|STM32F4_LED2|STM32F4_LED4) << ON_CLRBITS_SHIFT) +#define LED_STACKCREATED_OFF_SETBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_SETBITS_SHIFT) +#define LED_STACKCREATED_OFF_CLRBITS ((STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_INIRQ_ON_SETBITS ((STM32F4_LED1) << ON_SETBITS_SHIFT) +#define LED_INIRQ_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_INIRQ_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_INIRQ_OFF_CLRBITS ((STM32F4_LED1) << OFF_CLRBITS_SHIFT) + +#define LED_SIGNAL_ON_SETBITS ((STM32F4_LED2) << ON_SETBITS_SHIFT) +#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_SIGNAL_OFF_CLRBITS ((STM32F4_LED2) << OFF_CLRBITS_SHIFT) + +#define LED_ASSERTION_ON_SETBITS ((STM32F4_LED4) << ON_SETBITS_SHIFT) +#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_ASSERTION_OFF_CLRBITS ((STM32F4_LED4) << OFF_CLRBITS_SHIFT) + +#define LED_PANIC_ON_SETBITS ((STM32F4_LED4) << ON_SETBITS_SHIFT) +#define LED_PANIC_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT) +#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT) +#define LED_PANIC_OFF_CLRBITS ((STM32F4_LED4) << OFF_CLRBITS_SHIFT) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const uint16_t g_ledbits[8] = +{ + (LED_STARTED_ON_SETBITS | LED_STARTED_ON_CLRBITS | + LED_STARTED_OFF_SETBITS | LED_STARTED_OFF_CLRBITS), + + (LED_HEAPALLOCATE_ON_SETBITS | LED_HEAPALLOCATE_ON_CLRBITS | + LED_HEAPALLOCATE_OFF_SETBITS | LED_HEAPALLOCATE_OFF_CLRBITS), + + (LED_IRQSENABLED_ON_SETBITS | LED_IRQSENABLED_ON_CLRBITS | + LED_IRQSENABLED_OFF_SETBITS | LED_IRQSENABLED_OFF_CLRBITS), + + (LED_STACKCREATED_ON_SETBITS | LED_STACKCREATED_ON_CLRBITS | + LED_STACKCREATED_OFF_SETBITS | LED_STACKCREATED_OFF_CLRBITS), + + (LED_INIRQ_ON_SETBITS | LED_INIRQ_ON_CLRBITS | + LED_INIRQ_OFF_SETBITS | LED_INIRQ_OFF_CLRBITS), + + (LED_SIGNAL_ON_SETBITS | LED_SIGNAL_ON_CLRBITS | + LED_SIGNAL_OFF_SETBITS | LED_SIGNAL_OFF_CLRBITS), + + (LED_ASSERTION_ON_SETBITS | LED_ASSERTION_ON_CLRBITS | + LED_ASSERTION_OFF_SETBITS | LED_ASSERTION_OFF_CLRBITS), + + (LED_PANIC_ON_SETBITS | LED_PANIC_ON_CLRBITS | + LED_PANIC_OFF_SETBITS | LED_PANIC_OFF_CLRBITS) +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static inline void led_clrbits(unsigned int clrbits) +{ + if ((clrbits & STM32F4_LED1) != 0) + { + stm32_gpiowrite(GPIO_LED1, false); + } + + if ((clrbits & STM32F4_LED2) != 0) + { + stm32_gpiowrite(GPIO_LED2, false); + } + + if ((clrbits & STM32F4_LED3) != 0) + { + stm32_gpiowrite(GPIO_LED3, false); + } + + if ((clrbits & STM32F4_LED4) != 0) + { + stm32_gpiowrite(GPIO_LED4, false); + } +} + +static inline void led_setbits(unsigned int setbits) +{ + if ((setbits & STM32F4_LED1) != 0) + { + stm32_gpiowrite(GPIO_LED1, true); + } + + if ((setbits & STM32F4_LED2) != 0) + { + stm32_gpiowrite(GPIO_LED2, true); + } + + if ((setbits & STM32F4_LED3) != 0) + { + stm32_gpiowrite(GPIO_LED3, true); + } + + if ((setbits & STM32F4_LED4) != 0) + { + stm32_gpiowrite(GPIO_LED4, true); + } +} + +static void led_setonoff(unsigned int bits) +{ + led_clrbits(CLRBITS(bits)); + led_setbits(SETBITS(bits)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure LED1-4 GPIOs for output */ + + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); + stm32_configgpio(GPIO_LED3); + stm32_configgpio(GPIO_LED4); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + led_setonoff(ON_BITS(g_ledbits[led])); +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + led_setonoff(OFF_BITS(g_ledbits[led])); +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_boot.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_boot.c new file mode 100644 index 00000000000..31228991c6b --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_boot.c @@ -0,0 +1,120 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_boot.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include "arm_internal.h" +#include "nvic.h" +#include "itm.h" + +#include "stm32.h" +#include "stm32f4discovery.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This + * entry point is called early in the initialization -- after all memory + * has been configured and mapped but before any devices have been + * initialized. + * + ****************************************************************************/ + +void stm32_boardinitialize(void) +{ +#ifdef CONFIG_SCHED_CRITMONITOR + up_perf_init((void *)STM32_SYSCLK_FREQUENCY); +#endif + +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) + /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak + * function stm32_spidev_initialize() has been brought into the link. + */ + + if (stm32_spidev_initialize) + { + stm32_spidev_initialize(); + } +#endif + +#ifdef CONFIG_STM32_OTGFS + /* Initialize USB if the 1) OTG FS controller is in the configuration and + * 2) disabled, and 3) the weak function stm32_usbinitialize() has been + * brought into the build. Presumably either CONFIG_USBDEV or + * CONFIG_USBHOST is also selected. + */ + + if (stm32_usbinitialize) + { + stm32_usbinitialize(); + } +#endif + +#ifdef HAVE_NETMONITOR + /* Configure board resources to support networking. */ + + if (stm32_netinitialize) + { + stm32_netinitialize(); + } +#endif + +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_late_initialize + * + * Description: + * If CONFIG_BOARD_LATE_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_late_initialize(). board_late_initialize() will be + * called immediately after up_initialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_LATE_INITIALIZE +void board_late_initialize(void) +{ + /* Perform board-specific initialization */ + + stm32_bringup(); +} +#endif diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_bringup.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_bringup.c new file mode 100644 index 00000000000..9a4340b421a --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_bringup.c @@ -0,0 +1,565 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#ifdef CONFIG_USBMONITOR +# include +#endif + +#include "stm32.h" +#include "stm32_romfs.h" + +#ifdef CONFIG_STM32_OTGFS +# include "stm32_usbhost.h" +#endif + +#ifdef CONFIG_INPUT_BUTTONS +# include +#endif + +#ifdef CONFIG_USERLED +# include +#endif + +#ifdef CONFIG_RNDIS +# include +#endif + +#include "stm32f4discovery.h" + +/* Conditional logic in stm32f4discovery.h will determine if certain features + * are supported. Tests for these features need to be made after including + * stm32f4discovery.h. + */ + +#ifdef HAVE_RTC_DRIVER +# include +# include "stm32_rtc.h" +#endif + +/* The following are includes from board-common logic */ + +#ifdef CONFIG_SENSORS_BMP180 +#include "stm32_bmp180.h" +#endif + +#ifdef CONFIG_SENSORS_MS5611 +#include "stm32_ms5611.h" +#endif + +#ifdef CONFIG_SENSORS_MAX6675 +#include "stm32_max6675.h" +#endif + +#ifdef CONFIG_INPUT_NUNCHUCK +#include "stm32_nunchuck.h" +#endif + +#ifdef CONFIG_SENSORS_ZEROCROSS +#include "stm32_zerocross.h" +#endif + +#ifdef CONFIG_SENSORS_QENCODER +#include "board_qencoder.h" +#endif + +#ifdef CONFIG_SENSORS_BH1750FVI +#include "stm32_bh1750.h" +#endif + +#ifdef CONFIG_LIS3DSH +#include "stm32_lis3dsh.h" +#endif + +#ifdef CONFIG_LCD_BACKPACK +#include "stm32_lcd_backpack.h" +#endif + +#ifdef CONFIG_SENSORS_MAX31855 +#include "stm32_max31855.h" +#endif + +#ifdef CONFIG_SENSORS_MLX90614 +#include "stm32_mlx90614.h" +#endif + +#ifdef CONFIG_SENSORS_XEN1210 +#include "stm32_xen1210.h" +#endif + +#ifdef CONFIG_USBADB +# include +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_i2c_register + * + * Description: + * Register one I2C drivers for the I2C tool. + * + ****************************************************************************/ + +#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL) +static void stm32_i2c_register(int bus) +{ + struct i2c_master_s *i2c; + int ret; + + i2c = stm32_i2cbus_initialize(bus); + if (i2c == NULL) + { + syslog(LOG_ERR, "ERROR: Failed to get I2C%d interface\n", bus); + } + else + { + ret = i2c_register(i2c, bus); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to register I2C%d driver: %d\n", + bus, ret); + stm32_i2cbus_uninitialize(i2c); + } + } +} +#endif + +/**************************************************************************** + * Name: stm32_i2ctool + * + * Description: + * Register I2C drivers for the I2C tool. + * + ****************************************************************************/ + +#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL) +static void stm32_i2ctool(void) +{ + stm32_i2c_register(1); +#if 0 + stm32_i2c_register(1); + stm32_i2c_register(2); +#endif +} +#else +# define stm32_i2ctool() +#endif + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_LATE_INITIALIZE=y : + * Called from board_late_initialize(). + * + * CONFIG_BOARD_LATE_INITIALIZE=n && CONFIG_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void) +{ +#ifdef HAVE_RTC_DRIVER + struct rtc_lowerhalf_s *lower; +#endif + int ret = OK; + +#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL) + stm32_i2ctool(); +#endif + +#ifdef CONFIG_SENSORS_BMP180 + /* Initialize the BMP180 pressure sensor. */ + + ret = board_bmp180_initialize(0, 1); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize BMP180, error %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_SENSORS_MS5611 + /* Initialize the MS5611 pressure sensor. */ + + ret = board_ms5611_initialize(0, 1); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize MS5611, error %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_SENSORS_BH1750FVI + ret = board_bh1750_initialize(0, 1); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_bh1750initialize() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_SENSORS_ZEROCROSS + /* Configure the zero-crossing driver */ + + board_zerocross_initialize(0); +#endif + +#ifdef CONFIG_LEDS_MAX7219 + ret = stm32_max7219init("/dev/numdisp0"); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: max7219_leds_register failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_LCD_ST7032 + ret = stm32_st7032init("/dev/slcd0"); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: st7032_register failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_RGBLED + /* Configure the RGB LED driver */ + + stm32_rgbled_setup(); +#endif + +#if defined(CONFIG_PCA9635PW) + /* Initialize the PCA9635 chip */ + + ret = stm32_pca9635_initialize(); + if (ret < 0) + { + serr("ERROR: stm32_pca9635_initialize failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_VIDEO_FB + /* Initialize and register the framebuffer driver */ + + ret = fb_register(0, 0); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: fb_register() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_LCD_BACKPACK + /* slcd:0, i2c:1, rows=2, cols=16 */ + + ret = board_lcd_backpack_init(0, 1, 2, 16); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize PCF8574 LCD, error %d\n", ret); + return ret; + } +#endif + +#ifdef HAVE_SDIO + /* Initialize the SDIO block driver */ + + ret = stm32_sdio_initialize(); + if (ret != OK) + { + ferr("ERROR: Failed to initialize MMC/SD driver: %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_MMCSD_SPI + /* Initialize the MMC/SD SPI driver (SPI2 is used) */ + + ret = stm32_mmcsd_initialize(2, CONFIG_NSH_MMCSDMINOR); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize SD slot %d: %d\n", + CONFIG_NSH_MMCSDMINOR, ret); + } +#endif + +#ifdef HAVE_USBHOST + /* Initialize USB host operation. stm32_usbhost_initialize() starts a + * thread will monitor for USB connection and disconnection events. + */ + + ret = stm32_usbhost_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to initialize USB host: %d\n", ret); + return ret; + } +#endif + +#ifdef HAVE_USBMONITOR + /* Start the USB Monitor */ + + ret = usbmonitor_start(); + if (ret != OK) + { + uerr("ERROR: Failed to start USB monitor: %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_PWM + /* Initialize PWM and register the PWM device. */ + + ret = stm32_pwm_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_pwm_setup() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_CAPTURE + /* Initialize Capture and register the Capture driver. */ + + ret = stm32_capture_setup("/dev/capture0"); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_capture_setup failed: %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_STM32_CAN_CHARDRIVER + /* Initialize CAN and register the CAN driver. */ + + ret = stm32_can_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_can_setup failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_INPUT_BUTTONS + /* Register the BUTTON driver */ + + ret = btn_lower_initialize("/dev/buttons"); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: btn_lower_initialize() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_INPUT_NUNCHUCK + /* Register the Nunchuck driver */ + + ret = board_nunchuck_initialize(0, 1); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: nunchuck_initialize() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_SENSORS_MLX90614 + ret = board_mlx90614_initialize(0, 1); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize MLX90614, error %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_SENSORS_QENCODER + /* Initialize and register the qencoder driver */ + + ret = board_qencoder_initialize(0, CONFIG_STM32F4DISCO_QETIMER); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the qencoder: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_USERLED + /* Register the LED driver */ + + ret = userled_lower_initialize("/dev/userleds"); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_RTC_DS1307 + ret = stm32_ds1307_init(); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize DS1307 RTC driver: %d\n", ret); + return ret; + } +#endif + +#ifdef HAVE_RTC_DRIVER + /* Instantiate the STM32 lower-half RTC driver */ + + lower = stm32_rtc_lowerhalf(); + if (!lower) + { + serr("ERROR: Failed to instantiate the RTC lower-half driver\n"); + return -ENOMEM; + } + else + { + /* Bind the lower half driver and register the combined RTC driver + * as /dev/rtc0 + */ + + ret = rtc_initialize(0, lower); + if (ret < 0) + { + serr("ERROR: Failed to bind/register the RTC driver: %d\n", ret); + return ret; + } + } +#endif + +#ifdef HAVE_CS43L22 + /* Configure CS43L22 audio */ + + ret = stm32_cs43l22_initialize(1); + if (ret != OK) + { + serr("Failed to initialize CS43L22 audio: %d\n", ret); + } +#endif + +#ifdef CONFIG_SENSORS_MAX31855 + /* Register device 0 on spi channel 2 */ + + ret = board_max31855_initialize(0, 2); + if (ret < 0) + { + serr("ERROR: stm32_max31855initialize failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_SENSORS_MAX6675 + ret = board_max6675_initialize(0, 2); + if (ret < 0) + { + serr("ERROR: stm32_max6675initialize failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = nx_mount(NULL, STM32_PROCFS_MOUNTPOINT, "procfs", 0, NULL); + if (ret < 0) + { + serr("ERROR: Failed to mount procfs at %s: %d\n", + STM32_PROCFS_MOUNTPOINT, ret); + } +#endif + +#ifdef CONFIG_STM32_ROMFS + ret = stm32_romfs_initialize(); + if (ret < 0) + { + serr("ERROR: Failed to mount romfs at %s: %d\n", + CONFIG_STM32_ROMFS_MOUNTPOINT, ret); + } +#endif + +#ifdef CONFIG_SENSORS_XEN1210 + ret = board_xen1210_initialize(0, 1); + if (ret < 0) + { + serr("ERROR: xen1210_archinitialize failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_LIS3DSH + /* Create a lis3dsh driver instance fitting the chip built into + * stm32f4discovery + */ + + ret = board_lis3dsh_initialize(0, 1); + if (ret < 0) + { + serr("ERROR: Failed to initialize LIS3DSH driver: %d\n", ret); + } +#endif + +#ifdef HAVE_HCIUART + ret = hciuart_dev_initialize(); + if (ret < 0) + { + serr("ERROR: Failed to initialize HCI UART driver: %d\n", ret); + } +#endif + +#if defined(CONFIG_RNDIS) + uint8_t mac[6]; + mac[0] = 0xa0; /* TODO */ + mac[1] = (CONFIG_NETINIT_MACADDR_2 >> (8 * 0)) & 0xff; + mac[2] = (CONFIG_NETINIT_MACADDR_1 >> (8 * 3)) & 0xff; + mac[3] = (CONFIG_NETINIT_MACADDR_1 >> (8 * 2)) & 0xff; + mac[4] = (CONFIG_NETINIT_MACADDR_1 >> (8 * 1)) & 0xff; + mac[5] = (CONFIG_NETINIT_MACADDR_1 >> (8 * 0)) & 0xff; + usbdev_rndis_initialize(mac); +#endif + +#ifdef CONFIG_WL_GS2200M + ret = stm32_gs2200m_initialize("/dev/gs2200m", 3); + if (ret < 0) + { + serr("ERROR: Failed to initialize GS2200M: %d\n", ret); + } +#endif + +#ifdef CONFIG_LPWAN_SX127X + ret = stm32_lpwaninitialize(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to initialize wireless driver:" + " %d\n", ret); + } +#endif /* CONFIG_LPWAN_SX127X */ + +#ifdef CONFIG_USBADB + usbdev_adb_initialize(); +#endif + + return ret; +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_buttons.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_buttons.c new file mode 100644 index 00000000000..11219ea68c5 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_buttons.c @@ -0,0 +1,149 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_buttons.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "stm32.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Pin configuration for each STM32F4 Discovery button. This array is indexed + * by the BUTTON_* definitions in board.h + */ + +static const uint32_t g_buttons[NUM_BUTTONS] = +{ + GPIO_BTN_USER +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. + * After that, board_buttons() may be called to collect the current state + * of all buttons or board_button_irq() may be called to register button + * interrupt handlers. + * + ****************************************************************************/ + +uint32_t board_button_initialize(void) +{ + int i; + + /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are + * configured for all pins. + */ + + for (i = 0; i < NUM_BUTTONS; i++) + { + stm32_configgpio(g_buttons[i]); + } + + return NUM_BUTTONS; +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint32_t board_buttons(void) +{ + uint32_t ret = 0; + int i; + + /* Check that state of each key */ + + for (i = 0; i < NUM_BUTTONS; i++) + { + /* A LOW value means that the key is pressed. */ + + bool released = stm32_gpioread(g_buttons[i]); + + /* Accumulate the set of depressed (not released) keys */ + + if (!released) + { + ret |= (1 << i); + } + } + + return ret; +} + +/**************************************************************************** + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. + * After that, board_buttons() may be called to collect the current state + * of all buttons or board_button_irq() may be called to register button + * interrupt handlers. + * + * After board_button_initialize() has been called, board_buttons() may be + * called to collect the state of all buttons. board_buttons() returns an + * 32-bit bit set with each bit associated with a button. See the + * BUTTON_*_BIT definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that + * will be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See + * the BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ****************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, void *arg) +{ + int ret = -EINVAL; + + /* The following should be atomic */ + + if (id >= MIN_IRQBUTTON && id <= MAX_IRQBUTTON) + { + ret = stm32_gpiosetevent(g_buttons[id], true, true, true, + irqhandler, arg); + } + + return ret; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_can.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_can.c new file mode 100644 index 00000000000..1b66bd67bb5 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_can.c @@ -0,0 +1,100 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_can.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" +#include "stm32.h" +#include "stm32_can.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_CAN + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_can_setup + * + * Description: + * Initialize CAN and register the CAN device + * + ****************************************************************************/ + +int stm32_can_setup(void) +{ +#if defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2) + struct can_dev_s *can; + int ret; + + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + if (can == NULL) + { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + if (ret < 0) + { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + return OK; +#else + return -ENODEV; +#endif +} + +#endif /* CONFIG_CAN */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_capture.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_capture.c new file mode 100644 index 00000000000..811bdabbe04 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_capture.c @@ -0,0 +1,109 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_capture.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include "chip.h" + +#include "stm32.h" +#include "stm32_capture.h" +#include "arm_internal.h" + +#include "stm32f4discovery.h" + +#if defined(CONFIG_CAPTURE) +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Capture + * + * The stm32f4discovery has no real on-board pwm capture devices, but the + * board can be configured to capture pwm using TIM3 CH2 PB5. + */ + +#define HAVE_CAPTURE 1 + +#ifndef CONFIG_CAPTURE +# undef HAVE_CAPTURE +#endif + +#ifndef CONFIG_STM32_TIM3 +# undef HAVE_CAPTURE +#endif + +#ifndef CONFIG_STM32_TIM3_CAP +# undef HAVE_CAPTURE +#endif + +#if !defined(CONFIG_STM32_TIM3_CHANNEL) || CONFIG_STM32_TIM3_CHANNEL != STM32F4DISCOVERY_CAPTURECHANNEL +# undef HAVE_CAPTURE +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_capture_setup + * + * Description: + * Initialize and register the pwm capture driver. + * + * Input parameters: + * devpath - The full path to the driver to register. E.g., "/dev/capture0" + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int stm32_capture_setup(FAR const char *devpath) +{ +#ifdef HAVE_CAPTURE + struct cap_lowerhalf_s *capture; + int ret; + + capture = stm32_cap_initialize(STM32F4DISCOVERY_CAPTURETIMER); + + /* Then register the pwm capture sensor */ + + ret = cap_register(devpath, capture); + if (ret < 0) + { + mtrerr("ERROR: Error registering capture\n"); + } + + return ret; +#else + return -ENODEV; +#endif +} + +#endif /* CONFIG_CAPTURE */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_cs43l22.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_cs43l22.c new file mode 100644 index 00000000000..6c835b53292 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_cs43l22.c @@ -0,0 +1,385 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_cs43l22.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include "stm32.h" +#include "stm32f4discovery.h" + +#ifdef HAVE_CS43L22 + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32_mwinfo_s +{ + /* Standard CS43L22 interface */ + + struct cs43l22_lower_s lower; + + /* Extensions for the stm32f4discovery board */ + + cs43l22_handler_t handler; + void *arg; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* IRQ/PIO access callbacks. These operations all hidden behind + * callbacks to isolate the CS43L22 driver from differences in PIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the CS43L22 interrupt handler to the PIO interrupt + * enable - Enable or disable the PIO interrupt + */ + +static int cs43l22_attach(const struct cs43l22_lower_s *lower, + cs43l22_handler_t isr, void *arg); +static bool cs43l22_enable(const struct cs43l22_lower_s *lower, + bool enable); +static void cs43l22_hw_reset(const struct cs43l22_lower_s *lower); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the CS43L22 + * driver. This structure provides information about the configuration + * of the CS43L22 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. + */ + +#define CONFIG_STM32_CS43L22_I2CFREQUENCY 100000 +#define BOARD_MAINCK_FREQUENCY 8000000 + +static struct stm32_mwinfo_s g_cs43l22info = +{ + .lower = + { + .address = CS43L22_I2C_ADDRESS, + .frequency = CONFIG_STM32_CS43L22_I2CFREQUENCY, +#ifdef CONFIG_STM32_CS43L22_SRCSCK + .mclk = BOARD_SLOWCLK_FREQUENCY, +#else + .mclk = BOARD_MAINCK_FREQUENCY, +#endif + .attach = cs43l22_attach, + .enable = cs43l22_enable, + .reset = cs43l22_hw_reset, + }, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * IRQ/PIO access callbacks. These operations all hidden behind + * callbacks to isolate the CS43L22 driver from differences in PIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the CS43L22 interrupt handler to the PIO interrupt + * enable - Enable or disable the PIO interrupt + * clear - Acknowledge/clear any pending PIO interrupt + * + ****************************************************************************/ + +static int cs43l22_attach(const struct cs43l22_lower_s *lower, + cs43l22_handler_t isr, void *arg) +{ + if (isr) + { + /* Just save the address of the handler and its argument for now. The + * new handler will called via cs43l22_interrupt() when the interrupt + * occurs. + */ + + audinfo("Attaching %p\n", isr); + g_cs43l22info.handler = isr; + g_cs43l22info.arg = arg; + } + else + { + audinfo("Detaching %p\n", g_cs43l22info.handler); + cs43l22_enable(lower, false); + g_cs43l22info.handler = NULL; + g_cs43l22info.arg = NULL; + } + + return OK; +} + +static bool cs43l22_enable(const struct cs43l22_lower_s *lower, + bool enable) +{ + static bool enabled; + irqstate_t flags; + bool ret; + + /* Has the interrupt state changed */ + + flags = enter_critical_section(); + if (enable != enabled) + { + /* Enable or disable interrupts */ + + if (enable && g_cs43l22info.handler) + { + audinfo("Enabling\n"); + + /* TODO: stm32_pioirqenable(IRQ_INT_CS43L22); */ + + enabled = true; + } + else + { + audinfo("Disabling\n"); + + /* TODO: stm32_pioirqdisable(IRQ_INT_CS43L22); */ + + enabled = false; + } + } + + ret = enabled; + leave_critical_section(flags); + return ret; +} + +#if 0 +static int cs43l22_interrupt(int irq, void *context) +{ + /* Just forward the interrupt to the CS43L22 driver */ + + audinfo("handler %p\n", g_cs43l22info.handler); + if (g_cs43l22info.handler) + { + return g_cs43l22info.handler(&g_cs43l22info.lower, g_cs43l22info.arg); + } + + /* We got an interrupt with no handler. This should not + * happen. + */ + + /* TODO: stm32_pioirqdisable(IRQ_INT_CS43L22); */ + + return OK; +} +#endif + +static void cs43l22_hw_reset(const struct cs43l22_lower_s *lower) +{ + int i; + + /* Reset the codec */ + + stm32_gpiowrite(GPIO_CS43L22_RESET, false); + for (i = 0; i < 0x4fff; i++) + { + __asm__ volatile("nop"); + } + + stm32_gpiowrite(GPIO_CS43L22_RESET, true); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_cs43l22_initialize + * + * Description: + * This function is called by platform-specific, setup logic to configure + * and register the CS43L22 device. This function will register the driver + * as /dev/audio/pcm[x] where x is determined by 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 stm32_cs43l22_initialize(int minor) +{ + struct audio_lowerhalf_s *cs43l22; + struct audio_lowerhalf_s *pcm; + struct i2c_master_s *i2c; + struct i2s_dev_s *i2s; + static bool initialized = false; + char devname[12]; + int ret; + + audinfo("minor %d\n", minor); + DEBUGASSERT(minor >= 0 && minor <= 25); + + /* Have we already initialized? Since we never uninitialize we must + * prevent multiple initializations. This is necessary, for example, + * when the touchscreen example is used as a built-in application in + * NSH and can be called numerous time. It will attempt to initialize + * each time. + */ + + if (!initialized) + { + stm32_configgpio(GPIO_CS43L22_RESET); + + /* Configure the CS43L22 interrupt pin */ + + /* TODO: stm32_configgpio(PIO_INT_CS43L22); */ + + /* Get an instance of the I2C interface for the CS43L22 chip select */ + + i2c = stm32_i2cbus_initialize(CS43L22_I2C_BUS); + if (!i2c) + { + auderr("ERROR: Failed to initialize TWI%d\n", CS43L22_I2C_BUS); + ret = -ENODEV; + goto errout; + } + + /* Get an instance of the I2S interface for the CS43L22 data channel */ + + i2s = stm32_i2sbus_initialize(CS43L22_I2S_BUS); + if (!i2s) + { + auderr("ERROR: Failed to initialize I2S%d\n", CS43L22_I2S_BUS); + ret = -ENODEV; + goto errout_with_i2c; + } + + /* Configure the DAC master clock. This clock is provided by + * PCK2 (PB10) that is connected to the CS43L22 MCLK. + */ + + /* Configure CS43L22 interrupts */ + +#if 0 /* TODO: */ + stm32_pioirq(PIO_INT_CS43L22); + ret = irq_attach(IRQ_INT_CS43L22, cs43l22_interrupt); + if (ret < 0) + { + auderr("ERROR: Failed to attach CS43L22 interrupt: %d\n", ret); + goto errout_with_i2s; + } +#endif + + /* Now we can use these I2C and I2S interfaces to initialize the + * CS43L22 which will return an audio interface. + */ + + cs43l22 = cs43l22_initialize(i2c, i2s, &g_cs43l22info.lower); + if (!cs43l22) + { + auderr("ERROR: Failed to initialize the CS43L22\n"); + ret = -ENODEV; + goto errout_with_irq; + } + + /* No we can embed the CS43L22/I2C/I2S conglomerate into a PCM decoder + * instance so that we will have a PCM front end for the the CS43L22 + * driver. + */ + + pcm = pcm_decode_initialize(cs43l22); + if (!pcm) + { + auderr("ERROR: Failed create the PCM decoder\n"); + ret = -ENODEV; + goto errout_with_cs43l22; + } + + /* Create a device name */ + + snprintf(devname, 12, "pcm%d", minor); + + /* Finally, we can register the PCM/CS43L22/I2C/I2S audio device. + * + * Is anyone young enough to remember Rube Goldberg? + */ + + ret = audio_register(devname, pcm); + if (ret < 0) + { + auderr("ERROR: Failed to register /dev/%s device: %d\n", + devname, ret); + goto errout_with_pcm; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; + + /* Error exits. Unfortunately there is no mechanism in place now to + * recover resources from most errors on initialization failures. + */ + +errout_with_pcm: +errout_with_cs43l22: +errout_with_irq: + +#if 0 + irq_detach(IRQ_INT_CS43L22); +errout_with_i2s: +#endif + +errout_with_i2c: +errout: + return ret; +} + +#endif /* HAVE_CS43L22 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ds1307.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ds1307.c new file mode 100644 index 00000000000..713823208ac --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ds1307.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_ds1307.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "stm32.h" +#include "stm32_i2c.h" +#include "stm32f4discovery.h" + +#if defined(CONFIG_I2C) && defined(CONFIG_RTC_DS1307) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define DS1307_I2C_ADDR 0x6f /* DS1307 I2C Address */ +#define DS1307_I2C_BUS 1 /* DS1307 is on I2C1 */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ds1307_init + * + * Description: + * Initialize and configure the DS1307 RTC + * + ****************************************************************************/ + +int stm32_ds1307_init(void) +{ + struct i2c_master_s *i2c; + static bool initialized = false; + int ret; + + /* Have we already initialized? */ + + if (!initialized) + { + /* No.. Get the I2C bus driver */ + + rtcinfo("Initialize I2C%d\n", DS1307_I2C_BUS); + i2c = stm32_i2cbus_initialize(DS1307_I2C_BUS); + if (!i2c) + { + rtcerr("ERROR: Failed to initialize I2C%d\n", DS1307_I2C_BUS); + return -ENODEV; + } + + /* Now bind the I2C interface to the DS1307 RTC driver */ + + rtcinfo("Bind the DS1307 RTC driver to I2C%d\n", DS1307_I2C_BUS); + ret = dsxxxx_rtc_initialize(i2c); + if (ret < 0) + { + rtcerr("ERROR: Failed to bind I2C%d to the DS1307 RTC driver\n", + DS1307_I2C_BUS); + return -ENODEV; + } + +#ifdef CONFIG_I2C_DRIVER + /* Register the I2C to get the "nsh> i2c bus" command working */ + + ret = i2c_register(i2c, DS1307_I2C_BUS); + if (ret < 0) + { + rtcerr("ERROR: Failed to register I2C%d driver: %d\n", bus, ret); + return -ENODEV; + } +#endif + + /* Synchronize the system time to the RTC time */ + + clock_synchronize(NULL); + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_I2C && CONFIG_RTC_DS1307 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_enc28j60.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_enc28j60.c new file mode 100644 index 00000000000..68cd9f71a68 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_enc28j60.c @@ -0,0 +1,217 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_enc28j60.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* 2MBit SPI FLASH OR ENC28J60 + * + * -- ---- ------------ ----------------------------------------------------- + * PIN NAME SIGNAL NOTES + * -- ---- ------------ ----------------------------------------------------- + * + * 29 PA4 PA4-SPI1-NSS 10Mbit ENC28J60, SPI 2M FLASH + * 30 PA5 PA5-SPI1-SCK 2.4" TFT + Touchscreen, 10Mbit ENC28J60, SPI 2M FLASH + * 31 PA6 PA6-SPI1-MISO 2.4" TFT + Touchscreen, 10Mbit ENC28J60, SPI 2M FLASH + * 32 PA7 PA7-SPI1-MOSI 2.4" TFT + Touchscreen, 10Mbit ENC28J60, SPI 2M FLASH + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include + +#include "chip.h" +#include "arm_internal.h" +#include "stm32_spi.h" + +#include "stm32f4discovery.h" + +#ifdef CONFIG_ENC28J60 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* ENC28J60 + * + * --- ------ -------------- ------------------------------------------------ + * PIN NAME SIGNAL NOTES + * --- ------ -------------- ------------------------------------------------ + * + * 29 PA4 PA4-SPI1-NSS 10Mbit ENC28J60, SPI 2M FLASH + * 30 PA5 PA5-SPI1-SCK 2.4" TFT + Touchscreen, + * 10Mbit ENC28J60, SPI 2M FLASH + * 31 PA6 PA6-SPI1-MISO 2.4" TFT + Touchscreen, + * 10Mbit ENC28J60, SPI 2M FLASH + * 32 PA7 PA7-SPI1-MOSI 2.4" TFT + Touchscreen, + * 10Mbit ENC28J60, SPI 2M FLASH + * 98 PE1 PE1-FSMC_NBL1 2.4" TFT + Touchscreen, + * 10Mbit EN28J60 Reset + * 4 PE5 (no name) 10Mbps ENC28J60 Interrupt + */ + +/* ENC28J60 is on SPI1 */ + +#ifndef CONFIG_STM32_SPI1 +# error "Need CONFIG_STM32_SPI1 in the configuration" +#endif + +/* SPI Assumptions **********************************************************/ + +#define ENC28J60_SPI_PORTNO 1 /* On SPI1 */ +#define ENC28J60_DEVNO 0 /* Only one ENC28J60 */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32_lower_s +{ + const struct enc_lower_s lower; /* Low-level MCU interface */ + xcpt_t handler; /* ENC28J60 interrupt handler */ + void *arg; /* Argument that accompanies the interrupt */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int up_attach(const struct enc_lower_s *lower, xcpt_t handler, + void *arg); +static void up_enable(const struct enc_lower_s *lower); +static void up_disable(const struct enc_lower_s *lower); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* The ENC28J60 normal provides interrupts to the MCU via a GPIO pin. The + * following structure provides an MCU-independent mechanixm for controlling + * the ENC28J60 GPIO interrupt. + */ + +static struct stm32_lower_s g_enclower = +{ + .lower = + { + .attach = up_attach, + .enable = up_enable, + .disable = up_disable + }, + .handler = NULL, + .arg = NULL +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: struct enc_lower_s methods + ****************************************************************************/ + +static int up_attach(const struct enc_lower_s *lower, xcpt_t handler, + void *arg) +{ + struct stm32_lower_s *priv = (struct stm32_lower_s *)lower; + + /* Just save the handler for use when the interrupt is enabled */ + + priv->handler = handler; + priv->arg = arg; + return OK; +} + +static void up_enable(const struct enc_lower_s *lower) +{ + struct stm32_lower_s *priv = (struct stm32_lower_s *)lower; + + DEBUGASSERT(priv->handler); + stm32_gpiosetevent(GPIO_ENC28J60_INTR, false, true, true, + priv->handler, priv->arg); +} + +/* REVISIT: Since the interrupt is completely torn down, not just disabled, + * in interrupt requests that occurs while the interrupt is disabled will be + * lost. + */ + +static void up_disable(const struct enc_lower_s *lower) +{ + stm32_gpiosetevent(GPIO_ENC28J60_INTR, false, true, true, + NULL, NULL); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arm_netinitialize + ****************************************************************************/ + +void arm_netinitialize(void) +{ + struct spi_dev_s *spi; + int ret; + + /* Assumptions: + * 1) ENC28J60 pins were configured in up_spi.c early in the boot-up phase. + * 2) Clocking for the SPI1 peripheral was also provided earlier in + * boot-up. + */ + + spi = stm32_spibus_initialize(ENC28J60_SPI_PORTNO); + if (!spi) + { + nerr("ERROR: Failed to initialize SPI port %d\n", ENC28J60_SPI_PORTNO); + return; + } + + /* Take ENC28J60 out of reset (active low) */ + + stm32_gpiowrite(GPIO_ENC28J60_RESET, true); + + /* Bind the SPI port to the ENC28J60 driver */ + + ret = enc_initialize(spi, &g_enclower.lower, ENC28J60_DEVNO); + if (ret < 0) + { + nerr("ERROR: Failed to bind SPI port %d ENC28J60 device %d: %d\n", + ENC28J60_SPI_PORTNO, ENC28J60_DEVNO, ret); + return; + } + + ninfo("Bound SPI port %d to ENC28J60 device %d\n", + ENC28J60_SPI_PORTNO, ENC28J60_DEVNO); +} + +#endif /* CONFIG_ENC28J60 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ethernet.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ethernet.c new file mode 100644 index 00000000000..ed2b0aefcdb --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ethernet.c @@ -0,0 +1,240 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_ethernet.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/* Force verbose debug on in this file only to support unit-level testing. */ + +#ifdef CONFIG_NETDEV_PHY_DEBUG +# undef CONFIG_DEBUG_INFO +# define CONFIG_DEBUG_INFO 1 +# undef CONFIG_DEBUG_NET +# define CONFIG_DEBUG_NET 1 +#endif + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_eth.h" + +#include "stm32f4discovery.h" + +#if defined(CONFIG_STM32F4DISBB) && defined(CONFIG_STM32_ETHMAC) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define STM32_ETHMAC_DEVNAME "eth0" + +#define AT24XX_MACADDR_OFFSET 0x9a + +/* Debug ********************************************************************/ + +/* Extra, in-depth debug output that is only available if + * CONFIG_NETDEV_PHY_DEBUG us defined. + */ + +#ifdef CONFIG_NETDEV_PHY_DEBUG +# define phyerr _err +# define phywarn _warn +# define phyinfo _info +#else +# define phyerr(x...) +# define phywarn(x...) +# define phyinfo(x...) +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef HAVE_NETMONITOR +static xcpt_t g_ethmac_handler; +static void *g_ethmac_arg; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_emac0_phy_enable + ****************************************************************************/ + +#ifdef HAVE_NETMONITOR +static void stm32_emac0_phy_enable(bool enable) +{ + phyinfo("enable=%d\n", enable); + if (enable && g_ethmac_handler != NULL) + { + /* Attach and enable GPIO interrupt (and event) on the falling edge */ + + stm32_gpiosetevent(GPIO_EMAC_NINT, false, true, true, + g_ethmac_handler, g_ethmac_arg); + } + else + { + /* Detach and disable GPIO interrupt */ + + stm32_gpiosetevent(GPIO_EMAC_NINT, false, false, false, + NULL, NULL); + } +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_netinitialize + * + * Description: + * Configure board resources to support networking. + * + ****************************************************************************/ + +void weak_function stm32_netinitialize(void) +{ +#ifdef HAVE_NETMONITOR + /* Configure the PHY interrupt GPIO */ + + phyinfo("Configuring %08x\n", GPIO_EMAC_NINT); + stm32_configgpio(GPIO_EMAC_NINT); +#endif + + /* Configure PHY /RESET output */ + + stm32_configgpio(GPIO_EMAC_NRST); +} + +/**************************************************************************** + * Name: arch_phy_irq + * + * Description: + * This function may be called to register an interrupt handler that will + * be called when a PHY interrupt occurs. This function both attaches + * the interrupt handler and enables the interrupt if 'handler' is non- + * NULL. If handler is NULL, then the interrupt is detached and disabled + * instead. + * + * The PHY interrupt is always disabled upon return. The caller must + * call back through the enable function point to control the state of + * the interrupt. + * + * This interrupt may or may not be available on a given platform depending + * on how the network hardware architecture is implemented. In a typical + * case, the PHY interrupt is provided to board-level logic as a GPIO + * interrupt (in which case this is a board-specific interface and really + * should be called board_phy_irq()); In other cases, the PHY interrupt + * may be cause by the chip's MAC logic (in which case arch_phy_irq()) is + * an appropriate name. Other other boards, there may be no PHY interrupts + * available at all. If client attachable PHY interrupts are available + * from the board or from the chip, then CONFIG_ARCH_PHY_INTERRUPT should + * be defined to indicate that fact. + * + * Typical usage: + * a. OS service logic (not application logic*) attaches to the PHY + * PHY interrupt and enables the PHY interrupt. + * b. When the PHY interrupt occurs: (1) the interrupt should be + * disabled and () work should be scheduled on the worker thread (or + * perhaps a dedicated application thread). + * c. That worker thread should use the SIOCGMIIPHY, SIOCGMIIREG, + * and SIOCSMIIREG ioctl calls** to communicate with the PHY, + * determine what network event took place (Link Up/Down?), and + * take the appropriate actions. + * d. It should then interact the PHY to clear any pending + * interrupts, then re-enable the PHY interrupt. + * + * * This is an OS internal interface and should not be used from + * application space. Rather applications should use the SIOCMIISIG + * ioctl to receive a signal when a PHY event occurs. + * ** This interrupt is really of no use if the Ethernet MAC driver + * does not support these ioctl calls. + * + * Input Parameters: + * intf - Identifies the network interface. For example "eth0". Only + * useful on platforms that support multiple Ethernet interfaces + * and, hence, multiple PHYs and PHY interrupts. + * handler - The client interrupt handler to be invoked when the PHY + * asserts an interrupt. Must reside in OS space, but can + * signal tasks in user space. A value of NULL can be passed + * in order to detach and disable the PHY interrupt. + * arg - The argument that will accompany the interrupt + * enable - A function pointer that be unused to enable or disable the + * PHY interrupt. + * + * Returned Value: + * Zero (OK) returned on success; a negated errno value is returned on + * failure. + * + ****************************************************************************/ + +#ifdef HAVE_NETMONITOR +int arch_phy_irq(const char *intf, xcpt_t handler, void *arg, + phy_enable_t *enable) +{ + phy_enable_t enabler; + irqstate_t flags; + + ninfo("%s: handler=%p\n", intf, handler); + phyinfo("ETHMAC: devname=%s\n", STM32_ETHMAC_DEVNAME); + + DEBUGASSERT(intf); + + flags = enter_critical_section(); + + if (strcmp(intf, STM32_ETHMAC_DEVNAME) == 0) + { + phyinfo("Select ETHMAC\n"); + g_ethmac_handler = handler; + g_ethmac_arg = arg; + enabler = stm32_emac0_phy_enable; + } + else + { + nerr("ERROR: Unsupported interface: %s\n", intf); + enabler = NULL; + } + + if (enable) + { + *enable = enabler; + } + + leave_critical_section(flags); + return OK; +} +#endif + +#endif /* CONFIG_STM32F4DISBB && CONFIG_STM32_ETHMAC */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_extmem.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_extmem.c new file mode 100644 index 00000000000..fcad766ac50 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_extmem.c @@ -0,0 +1,138 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_extmem.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "chip.h" +#include "arm_internal.h" +#include "stm32.h" +#include "stm32f4discovery.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 address 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); +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_gs2200m.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_gs2200m.c new file mode 100644 index 00000000000..1b4eecca549 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_gs2200m.c @@ -0,0 +1,248 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_gs2200m.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "arm_internal.h" +#include "chip.h" +#include "stm32.h" + +#include +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define GPIO_GS2200M_INT (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI | \ + GPIO_OPENDRAIN | GPIO_PORTD | GPIO_PIN2) + +#define GPIO_GS2200M_XRST (GPIO_OUTPUT | GPIO_PUSHPULL | \ + GPIO_OUTPUT_SET | GPIO_SPEED_50MHz | \ + GPIO_PORTE | GPIO_PIN4) + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int gs2200m_irq_attach(xcpt_t, void *); +static void gs2200m_irq_enable(void); +static void gs2200m_irq_disable(void); +static uint32_t gs2200m_dready(int *); +static void gs2200m_reset(bool); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct gs2200m_lower_s g_wifi_lower = +{ + .attach = gs2200m_irq_attach, + .enable = gs2200m_irq_enable, + .disable = gs2200m_irq_disable, + .dready = gs2200m_dready, + .reset = gs2200m_reset +}; + +static void *g_devhandle = NULL; +static volatile int32_t _enable_count = 0; +static volatile uint32_t _n_called; + +static xcpt_t g_irq_handler = NULL; +static void *g_irq_arg = NULL; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gs2200m_irq_attach + ****************************************************************************/ + +static int gs2200m_irq_attach(xcpt_t handler, void *arg) +{ + /* NOTE: Just save the handler and arg here */ + + g_irq_handler = handler; + g_irq_arg = arg; + return 0; +} + +/**************************************************************************** + * Name: gs2200m_irq_enable + ****************************************************************************/ + +static void gs2200m_irq_enable(void) +{ + irqstate_t flags = spin_lock_irqsave(NULL); + uint32_t dready = 0; + + wlinfo("== ec:%" PRId32 " called=%" PRId32 "\n", + _enable_count, _n_called++); + + if (0 == _enable_count) + { + /* Check if irq has been asserted */ + + dready = gs2200m_dready(NULL); + + /* NOTE: stm32 does not support level-triggered irq */ + + stm32_gpiosetevent(GPIO_GS2200M_INT, true, false, + true, g_irq_handler, g_irq_arg); + } + + _enable_count++; + + spin_unlock_irqrestore(NULL, flags); + + if (dready) + { + /* Call g_irq_handler directly */ + + wlinfo("== ** call irq handler **\n"); + g_irq_handler(0, NULL, g_irq_arg); + } +} + +/**************************************************************************** + * Name: gs2200m_irq_disable + ****************************************************************************/ + +static void gs2200m_irq_disable(void) +{ + irqstate_t flags = spin_lock_irqsave(NULL); + + wlinfo("== ec:%" PRId32 " called=%" PRId32 "\n", + _enable_count, _n_called++); + + _enable_count--; + + if (0 == _enable_count) + { + stm32_gpiosetevent(GPIO_GS2200M_INT, false, false, + false, NULL, NULL); + } + + spin_unlock_irqrestore(NULL, flags); +} + +/**************************************************************************** + * Name: gs2200m_dready + ****************************************************************************/ + +static uint32_t gs2200m_dready(int *ec) +{ + irqstate_t flags = spin_lock_irqsave(NULL); + + uint32_t r = stm32_gpioread(GPIO_GS2200M_INT); + + if (ec) + { + /* Copy enable count (just for debug) */ + + *ec = _enable_count; + } + + spin_unlock_irqrestore(NULL, flags); + return r; +} + +/**************************************************************************** + * Name: gs2200m_reset + ****************************************************************************/ + +static void gs2200m_reset(bool reset) +{ + stm32_gpiowrite(GPIO_GS2200M_XRST, !reset); +} + +/**************************************************************************** + * Name: spi_pincontrol + * + * Description: + * Configure SPI1 pins + * + ****************************************************************************/ + +static void _config_pin(void) +{ + stm32_configgpio(GPIO_GS2200M_XRST); /* Assign PD6 as XRST */ + stm32_configgpio(GPIO_GS2200M_INT); /* Assign PD2 as IRQ */ + stm32_configgpio(GPIO_SPI3_SCK_1); /* Assign PB3 as SPI3_SCK */ + stm32_configgpio(GPIO_SPI3_MISO_1); /* Assign PB4 as SPI3_MISO */ + stm32_configgpio(GPIO_SPI3_MOSI_1); /* Assign PB5 as SPI3_MOSI */ + stm32_configgpio(GPIO_GS2200M_CS); /* Assign PD7 as chip select */ +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_gs2200m_initialize + ****************************************************************************/ + +int stm32_gs2200m_initialize(const char *devpath, int bus) +{ + struct spi_dev_s *spi; + + wlinfo("Initializing GS2200M..\n"); + + if (!g_devhandle) + { + /* Configure pin */ + + _config_pin(); + + /* Initialize spi device */ + + spi = stm32_spibus_initialize(bus); + + if (!spi) + { + wlerr("ERROR: Failed to initialize spi%d.\n", bus); + return -ENODEV; + } + + g_devhandle = gs2200m_register(devpath, spi, &g_wifi_lower); + + if (!g_devhandle) + { + wlerr("ERROR: Failed to register gs2200m driver.\n"); + return -ENODEV; + } + } + + return OK; +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_hciuart.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_hciuart.c new file mode 100644 index 00000000000..d44a033f9ae --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_hciuart.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_hciuart.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#include "stm32_hciuart.h" +#include "stm32f4discovery.h" + +#include + +#ifdef HAVE_HCIUART + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: hciuart_dev_initialize + * + * Description: + * This function is called by board initialization logic to configure the + * Bluetooth HCI UART driver + * + * Input Parameters: + * None + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int hciuart_dev_initialize(void) +{ + int ret; + + /* Perform one-time initialization */ + + hciuart_initialize(); + + /* Instantiate the HCI UART lower half interface + * Then initialize the HCI UART upper half driver with the bluetooth stack + */ + + ret = btuart_register(hciuart_instantiate(HCIUART_SERDEV)); + if (ret < 0) + { + wlerr("ERROR: btuart_register() failed: %d\n", ret); + } + + return ret; +} + +#endif /* HAVE_HCIUART */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_idle.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_idle.c new file mode 100644 index 00000000000..2c7583012ba --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_idle.c @@ -0,0 +1,258 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_idle.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include + +#include +#include +#include +#include + +#include + +#include "arm_internal.h" +#include "stm32_pm.h" +#include "stm32_rcc.h" +#include "stm32_exti.h" + +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* Does the board support an IDLE LED to indicate that the board is in the + * IDLE state? + */ + +#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE) +# define BEGIN_IDLE() board_autoled_on(LED_IDLE) +# define END_IDLE() board_autoled_off(LED_IDLE) +#else +# define BEGIN_IDLE() +# define END_IDLE() +#endif + +/* Values for the RTC Alarm to wake up from the PM_STANDBY mode */ + +#ifndef CONFIG_PM_ALARM_SEC +# define CONFIG_PM_ALARM_SEC 3 +#endif + +#ifndef CONFIG_PM_ALARM_NSEC +# define CONFIG_PM_ALARM_NSEC 0 +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#if 0 /* Not used */ +static void up_alarmcb(void); +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_idlepm + * + * Description: + * Perform IDLE state power management. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void stm32_idlepm(void) +{ + static enum pm_state_e oldstate = PM_NORMAL; + enum pm_state_e newstate; + irqstate_t flags; + int ret; + + /* Decide, which power saving level can be obtained */ + + newstate = pm_checkstate(PM_IDLE_DOMAIN); + + /* Check for state changes */ + + if (newstate != oldstate) + { + sinfo("newstate= %d oldstate=%d\n", newstate, oldstate); + + flags = enter_critical_section(); + + /* Force the global state change */ + + ret = pm_changestate(PM_IDLE_DOMAIN, newstate); + if (ret < 0) + { + /* The new state change failed, revert to the preceding state */ + + pm_changestate(PM_IDLE_DOMAIN, oldstate); + + /* No state change... */ + + goto errout; + } + + /* Then perform board-specific, state-dependent logic here */ + + switch (newstate) + { + case PM_NORMAL: + { + } + break; + + case PM_IDLE: + { + } + break; + + case PM_STANDBY: + { +#ifdef CONFIG_RTC_ALARM + /* Disable RTC Alarm interrupt */ + +#warning "missing logic" + + /* Configure the RTC alarm to Auto Wake the system */ + +#warning "missing logic" + + /* The tv_nsec value must not exceed 1,000,000,000. That + * would be an invalid time. + */ + +#warning "missing logic" + + /* Set the alarm */ + +#warning "missing logic" +#endif + /* Call the STM32 stop mode */ + + stm32_pmstop(true); + + /* We have been re-awakened by some even: A button press? + * An alarm? Cancel any pending alarm and resume the normal + * operation. + */ + +#ifdef CONFIG_RTC_ALARM +#warning "missing logic" +#endif + /* Resume normal operation */ + + pm_changestate(PM_IDLE_DOMAIN, PM_NORMAL); + newstate = PM_NORMAL; + } + break; + + case PM_SLEEP: + { + /* We should not return from standby mode. The only way out + * of standby is via the reset path. + */ + + stm32_pmstandby(); + } + break; + + default: + break; + } + + /* Save the new state */ + + oldstate = newstate; + +errout: + leave_critical_section(flags); + } +} +#else +# define stm32_idlepm() +#endif + +/**************************************************************************** + * Name: up_alarmcb + * + * Description: + * RTC alarm service routine + * + ****************************************************************************/ + +#if 0 /* Not used */ +static void up_alarmcb(void) +{ + /* This alarm occurs because there wasn't any EXTI interrupt during the + * PM_STANDBY period. So just go to sleep. + */ + + pm_changestate(PM_IDLE_DOMAIN, PM_SLEEP); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_idle + * + * Description: + * up_idle() is the logic that will be executed when their is no other + * ready-to-run task. This is processor idle time and will continue until + * some interrupt occurs to cause a context switch from the idle task. + * + * Processing in this state may be processor-specific. e.g., this is where + * power management operations might be performed. + * + ****************************************************************************/ + +void up_idle(void) +{ +#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS) + /* If the system is idle and there are no timer interrupts, then process + * "fake" timer interrupts. Hopefully, something will wake up. + */ + + nxsched_process_timer(); +#else + + /* Perform IDLE mode power management */ + + BEGIN_IDLE(); + stm32_idlepm(); + END_IDLE(); +#endif +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_max7219.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_max7219.c new file mode 100644 index 00000000000..4c647a41107 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_max7219.c @@ -0,0 +1,112 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_max7219.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_spi.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_NX_LCDDRIVER + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define LCD_SPI_PORTNO 1 /* On SPI1 */ + +#ifndef CONFIG_LCD_CONTRAST +# define CONFIG_LCD_CONTRAST 60 +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct spi_dev_s *g_spidev; +struct lcd_dev_s *g_lcddev; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_lcd_initialize + ****************************************************************************/ + +int board_lcd_initialize(void) +{ + g_spidev = stm32_spibus_initialize(LCD_SPI_PORTNO); + + if (g_spidev == NULL) + { + lcderr("ERROR: Failed to initialize SPI port %d\n", LCD_SPI_PORTNO); + return -ENODEV; + } + + return OK; +} + +/**************************************************************************** + * Name: board_lcd_getdev + ****************************************************************************/ + +struct lcd_dev_s *board_lcd_getdev(int lcddev) +{ + g_lcddev = max7219_initialize(g_spidev, lcddev); + if (!g_lcddev) + { + lcderr("ERROR: Failed to bind SPI port 1 to LCD %d\n", lcddev); + } + else + { + lcdinfo("SPI port 1 bound to LCD %d\n", lcddev); + + return g_lcddev; + } + + return NULL; +} + +/**************************************************************************** + * Name: board_lcd_uninitialize + ****************************************************************************/ + +void board_lcd_uninitialize(void) +{ + /* TO-FIX */ +} + +#endif /* CONFIG_NX_LCDDRIVER */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_max7219_leds.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_max7219_leds.c new file mode 100644 index 00000000000..ac51331e00e --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_max7219_leds.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_max7219_leds.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "stm32.h" +#include "stm32_spi.h" +#include "stm32f4discovery.h" + +#if defined(CONFIG_SPI) && defined(CONFIG_STM32_SPI1) && \ + defined(CONFIG_LEDS_MAX7219) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define MAX7219_SPI_PORTNO 1 /* On SPI1 */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_max7219init + * + * Description: + * Initialize the max7219 to control 7-segment numeric display + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/numdisp0" + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int stm32_max7219init(const char *devpath) +{ + struct spi_dev_s *spi; + int ret; + + spi = stm32_spibus_initialize(MAX7219_SPI_PORTNO); + if (spi == NULL) + { + return -ENODEV; + } + + /* Register the MAX7219 Driver at the specified location. */ + + ret = max7219_leds_register(devpath, spi); + if (ret < 0) + { + lederr("ERROR: max7219_leds_register(%s) failed: %d\n", + devpath, ret); + return ret; + } + + return OK; +} + +#endif /* CONFIG_SPI && CONFIG_LEDS_MAX7219 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_mmcsd.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_mmcsd.c new file mode 100644 index 00000000000..7815a7fc4bb --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_mmcsd.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_mmcsd.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "arm_internal.h" +#include "chip.h" +#include "stm32.h" + +#include +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_DISABLE_MOUNTPOINT +# error "SD driver requires CONFIG_DISABLE_MOUNTPOINT to be disabled" +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_spi1register + * + * Description: + * Registers media change callback + ****************************************************************************/ + +int stm32_spi2register(struct spi_dev_s *dev, spi_mediachange_t callback, + void *arg) +{ + /* TODO: media change callback */ + + return OK; +} + +/**************************************************************************** + * Name: stm32_mmcsd_initialize + * + * Description: + * Initialize SPI-based SD card and card detect thread. + ****************************************************************************/ + +int stm32_mmcsd_initialize(int port, int minor) +{ + struct spi_dev_s *spi; + int rv; + + stm32_configgpio(GPIO_MMCSD_NCD); /* Assign SD_DET */ + stm32_configgpio(GPIO_SPI2_SCK_2); /* Assign PB13 as SPI2_SCK */ + stm32_configgpio(GPIO_MMCSD_NSS); /* Assign CS */ + stm32_gpiowrite(GPIO_MMCSD_NSS, 1); /* Ensure the CS is inactive */ + + mcinfo("INFO: Initializing mmcsd port %d minor %d\n", + port, minor); + + spi = stm32_spibus_initialize(port); + if (spi == NULL) + { + mcerr("ERROR: Failed to initialize SPI port %d\n", port); + return -ENODEV; + } + + rv = mmcsd_spislotinitialize(minor, minor, spi); + if (rv < 0) + { + mcerr("ERROR: Failed to bind SPI port %d to SD slot %d\n", + port, minor); + return rv; + } + + spiinfo("INFO: mmcsd card has been initialized successfully\n"); + return OK; +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_netinit.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_netinit.c new file mode 100644 index 00000000000..91110823600 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_netinit.c @@ -0,0 +1,39 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_netinit.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arm_netinitialize + ****************************************************************************/ + +#if defined(CONFIG_NET) && !defined(CONFIG_NETDEV_LATEINIT) +void arm_netinitialize(void) +{ +} +#endif diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pca9635.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pca9635.c new file mode 100644 index 00000000000..d6fd285b904 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pca9635.c @@ -0,0 +1,89 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_pca9635.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include + +#include "stm32_gpio.h" +#include "stm32_i2c.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_PCA9635PW + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_pca9635_initialize + * + * Description: + * This function is called by board initialization logic to configure the + * LED PWM chip. This function will register the driver as /dev/leddrv0. + * + * Input Parameters: + * None + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stm32_pca9635_initialize(void) +{ + struct i2c_master_s *i2c; + int ret; + + /* Get the I2C driver that interfaces with the pca9635 + * (PCA9635_I2CBUS) + */ + + i2c = stm32_i2cbus_initialize(PCA9635_I2CBUS); + if (!i2c) + { + _err("ERROR: Failed to initialize I2C%d\n", PCA9635_I2CBUS); + return -1; + } + + ret = pca9635pw_register("/dev/leddrv0", i2c, PCA9635_I2CADDR); + if (ret < 0) + { + snerr("ERROR: Failed to register PCA9635 driver: %d\n", ret); + return ret; + } + + return OK; +} + +#endif /* CONFIG_PCA9635PW */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pm.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pm.c new file mode 100644 index 00000000000..37a02351377 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pm.c @@ -0,0 +1,73 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_pm.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include "arm_internal.h" +#include "stm32_pm.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_PM + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_pminitialize + * + * Description: + * This function is called by MCU-specific logic at power-on reset in + * order to provide one-time initialization the power management subsystem. + * This function must be called *very* early in the initialization sequence + * *before* any other device drivers are initialized (since they may + * attempt to register with the power management subsystem). + * + * Input Parameters: + * None. + * + * Returned Value: + * None. + * + ****************************************************************************/ + +void arm_pminitialize(void) +{ + /* Initialize the NuttX power management subsystem proper */ + + pm_initialize(); + +#if defined(CONFIG_ARCH_IDLE_CUSTOM) && defined(CONFIG_PM_BUTTONS) + /* Initialize the buttons to wake up the system from low power modes */ + + stm32_pm_buttons(); +#endif + + /* Initialize the LED PM */ + + stm32_led_pminitialize(); +} + +#endif /* CONFIG_PM */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pmbuttons.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pmbuttons.c new file mode 100644 index 00000000000..915b2b7f7e9 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pmbuttons.c @@ -0,0 +1,120 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_pmbuttons.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include +#include +#include + +#include "arm_internal.h" +#include "nvic.h" +#include "stm32_pwr.h" +#include "stm32_pm.h" +#include "stm32f4discovery.h" + +#if defined(CONFIG_PM) && defined(CONFIG_ARCH_IDLE_CUSTOM) && defined(CONFIG_PM_BUTTONS) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_ARCH_BUTTONS +# error "CONFIG_ARCH_BUTTONS is not defined in the configuration" +#endif + +#ifndef CONFIG_ARCH_IRQBUTTONS +# warning "CONFIG_ARCH_IRQBUTTONS is not defined in the configuration" +#endif + +#ifndef CONFIG_PM_BUTTON_ACTIVITY +# define CONFIG_PM_BUTTON_ACTIVITY 10 +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +static int button_handler(int irq, void *context, void *arg); +#endif /* CONFIG_ARCH_IRQBUTTONS */ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: button_handler + * + * Description: + * Handle a button wake-up interrupt + * + ****************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +static int button_handler(int irq, void *context, void *arg) +{ + /* At this point the MCU should have already awakened. The state + * change will be handled in the IDLE loop when the system is re-awakened + * The button interrupt handler should be totally ignorant of the PM + * activities and should report button activity as if nothing + * special happened. + */ + + pm_activity(PM_IDLE_DOMAIN, CONFIG_PM_BUTTON_ACTIVITY); + return OK; +} +#endif /* CONFIG_ARCH_IRQBUTTONS */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_pm_buttons + * + * Description: + * Configure the user button of the STM32f4discovery board as EXTI, + * so it is able to wakeup the MCU from the PM_STANDBY mode + * + ****************************************************************************/ + +void stm32_pm_buttons(void) +{ + /* Initialize the button GPIOs */ + + board_button_initialize(); + +#ifdef CONFIG_ARCH_IRQBUTTONS + board_button_irq(0, button_handler, NULL); +#endif +} + +#endif /* CONFIG_PM && CONFIG_ARCH_IDLE_CUSTOM && CONFIG_PM_BUTTONS)*/ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pwm.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pwm.c new file mode 100644 index 00000000000..0ba219be46e --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_pwm.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_pwm.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" +#include "stm32_pwm.h" +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* PWM + * + * The stm32f4discovery has no real on-board PWM devices, but the board can + * be configured to output a pulse train using TIM4 CH2. This pin is used by + * FSMC is connected to CN5 just for this purpose: + * + * PD13 FSMC_A18 / MC_TIM4_CH2OUT pin 33 (EnB) + * + * FSMC must be disabled in this case! + */ + +#define HAVE_PWM 1 + +#ifndef CONFIG_PWM +# undef HAVE_PWM +#endif + +#ifndef CONFIG_STM32_TIM4 +# undef HAVE_PWM +#endif + +#ifndef CONFIG_STM32_TIM4_PWM +# undef HAVE_PWM +#endif + +#if !defined(CONFIG_STM32_TIM4_CHANNEL) || CONFIG_STM32_TIM4_CHANNEL != STM32F4DISCOVERY_PWMCHANNEL +# undef HAVE_PWM +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_pwm_setup + * + * Description: + * Initialize PWM and register the PWM device. + * + ****************************************************************************/ + +int stm32_pwm_setup(void) +{ +#ifdef HAVE_PWM + static bool initialized = false; + struct pwm_lowerhalf_s *pwm; + int ret; + + /* Have we already initialized? */ + + if (!initialized) + { + /* Call stm32_pwminitialize() to get an instance of the PWM interface */ + + pwm = stm32_pwminitialize(STM32F4DISCOVERY_PWMTIMER); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm0" */ + + ret = pwm_register("/dev/pwm0", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +#else + return -ENODEV; +#endif +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_reset.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_reset.c new file mode 100644 index 00000000000..495b70dcb5b --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_reset.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_reset.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#ifdef CONFIG_BOARDCTL_RESET + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_reset + * + * Description: + * Reset board. Support for this function is required by board-level + * logic if CONFIG_BOARDCTL_RESET is selected. + * + * Input Parameters: + * status - Status information provided with the reset event. This + * meaning of this status information is board-specific. If not + * used by a board, the value zero may be provided in calls to + * board_reset(). + * + * Returned Value: + * If this function returns, then it was not possible to power-off the + * board due to some constraints. The return value int this case is a + * board-specific reason for the failure to shutdown. + * + ****************************************************************************/ + +int board_reset(int status) +{ + up_systemreset(); + return 0; +} + +#endif /* CONFIG_BOARDCTL_RESET */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_rgbled.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_rgbled.c new file mode 100644 index 00000000000..4b916fa359d --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_rgbled.c @@ -0,0 +1,169 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_rgbled.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include "chip.h" +#include "arm_internal.h" +#include "stm32_pwm.h" +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#define HAVE_RGBLED 1 + +#ifndef CONFIG_PWM +# undef HAVE_RGBLED +#endif + +#ifndef CONFIG_STM32_TIM1 +# undef HAVE_RGBLED +#endif + +#ifndef CONFIG_STM32_TIM2 +# undef HAVE_RGBLED +#endif + +#ifndef CONFIG_STM32_TIM3 +# undef HAVE_RGBLED +#endif + +#ifndef CONFIG_STM32_TIM1_PWM +# undef HAVE_RGBLED +#endif + +#ifndef CONFIG_STM32_TIM2_PWM +# undef HAVE_RGBLED +#endif + +#ifndef CONFIG_STM32_TIM3_PWM +# undef HAVE_RGBLED +#endif + +#ifdef HAVE_RGBLED + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_rgbled_setup + * + * Description: + * Configure the RGB LED. + * + ****************************************************************************/ + +int stm32_rgbled_setup(void) +{ + static bool initialized = false; + struct pwm_lowerhalf_s *ledr; + struct pwm_lowerhalf_s *ledg; + struct pwm_lowerhalf_s *ledb; + struct pwm_info_s info; + int ret; + + /* Have we already initialized? */ + + if (!initialized) + { + /* Call stm32_pwminitialize() to get an instance of the PWM interface */ + + ledr = stm32_pwminitialize(1); + if (!ledr) + { + lederr("ERROR: Failed to get the STM32 PWM lower half to LEDR\n"); + return -ENODEV; + } + + /* Define frequency and duty cycle */ + + info.frequency = 100; + info.duty = 0; + + /* Initialize LED R */ + + ledr->ops->setup(ledr); + ledr->ops->start(ledr, &info); + + /* Call stm32_pwminitialize() to get an instance of the PWM interface */ + + ledg = stm32_pwminitialize(2); + if (!ledg) + { + lederr("ERROR: Failed to get the STM32 PWM lower half to LEDG\n"); + return -ENODEV; + } + + /* Initialize LED G */ + + ledg->ops->setup(ledg); + ledg->ops->start(ledg, &info); + + /* Call stm32_pwminitialize() to get an instance of the PWM interface */ + + ledb = stm32_pwminitialize(3); + if (!ledb) + { + lederr("ERROR: Failed to get the STM32 PWM lower half to LEDB\n"); + return -ENODEV; + } + + /* Initialize LED B */ + + ledb->ops->setup(ledb); + ledb->ops->start(ledb, &info); + + /* Register the RGB LED diver at "/dev/rgbled0" */ + + ret = rgbled_register("/dev/rgbled0", ledr, ledg, ledb); + if (ret < 0) + { + lederr("ERROR: rgbled_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#else +# error "HAVE_RGBLED is undefined" +#endif /* HAVE_RGBLED */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_romfs.h b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_romfs.h new file mode 100644 index 00000000000..97e041e7dc8 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_romfs.h @@ -0,0 +1,76 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_romfs.h + * + * Copyright (C) 2017 Tomasz Wozniak. All rights reserved. + * Author: Tomasz Wozniak + * + * 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. + * + ****************************************************************************/ + +#ifndef __BOARDS_ARM_STM32_STM32F4DISCOVERY_SRC_STM32_ROMFS_H +#define __BOARDS_ARM_STM32_STM32F4DISCOVERY_SRC_STM32_ROMFS_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef CONFIG_STM32_ROMFS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define ROMFS_SECTOR_SIZE 64 + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_romfs_initialize + * + * Description: + * Registers built-in ROMFS image as block device and mounts it. + * + * Returned Value: + * Zero (OK) on success, a negated errno value on error. + * + * Assumptions/Limitations: + * Memory addresses [&romfs_data_begin .. &romfs_data_begin) should contain + * ROMFS volume data, as included in the assembly snippet above (l. 84). + * + ****************************************************************************/ + +int stm32_romfs_initialize(void); + +#endif /* CONFIG_STM32_ROMFS */ + +#endif /* __BOARDS_ARM_STM32_STM32F4DISCOVERY_SRC_STM32_ROMFS_H */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_romfs_initialize.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_romfs_initialize.c new file mode 100644 index 00000000000..0e2c5e46da9 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_romfs_initialize.c @@ -0,0 +1,158 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_romfs_initialize.c + * This file provides contents of an optional ROMFS volume, mounted at boot. + * + * Copyright (C) 2017 Tomasz Wozniak. All rights reserved. + * Author: Tomasz Wozniak + * + * 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 + +#include +#include +#include +#include +#include + +#include +#include +#include "stm32_romfs.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef CONFIG_STM32_ROMFS +# error "CONFIG_STM32_ROMFS must be defined" +#else + +#ifndef CONFIG_STM32_ROMFS_IMAGEFILE +# error "CONFIG_STM32_ROMFS_IMAGEFILE must be defined" +#endif + +#ifndef CONFIG_STM32_ROMFS_DEV_MINOR +# error "CONFIG_STM32_ROMFS_DEV_MINOR must be defined" +#endif + +#ifndef CONFIG_STM32_ROMFS_MOUNTPOINT +# error "CONFIG_STM32_ROMFS_MOUNTPOINT must be defined" +#endif + +#define NSECTORS(size) (((size) + ROMFS_SECTOR_SIZE - 1)/ROMFS_SECTOR_SIZE) + +#define STR2(m) #m +#define STR(m) STR2(m) + +#define MKMOUNT_DEVNAME(m) "/dev/ram" STR(m) +#define MOUNT_DEVNAME MKMOUNT_DEVNAME(CONFIG_STM32_ROMFS_DEV_MINOR) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +__asm__ ( + ".section .rodata\n" + ".balign 16\n" + ".globl romfs_data_begin\n" +"romfs_data_begin:\n" + ".incbin " STR(CONFIG_STM32_ROMFS_IMAGEFILE) "\n"\ + \ + ".balign " STR(ROMFS_SECTOR_SIZE) "\n" + ".globl romfs_data_end\n" +"romfs_data_end:\n" + ".globl romfs_data_size\n" +"romfs_data_size:\n" + ".word romfs_data_end - romfs_data_begin\n" + ".previous\n"); + +extern const char romfs_data_begin; +extern const char romfs_data_end; +extern const int romfs_data_size; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_romfs_initialize + * + * Description: + * Registers the aboveincluded binary file as block device. + * Then mounts the block device as ROMFS filesystems. + * + * Returned Value: + * Zero (OK) on success, a negated errno value on error. + * + * Assumptions/Limitations: + * Memory addresses [&romfs_data_begin .. &romfs_data_begin) should contain + * ROMFS volume data, as included in the assembly snippet above (l. 84). + * + ****************************************************************************/ + +int stm32_romfs_initialize(void) +{ + uintptr_t romfs_data_len; + int ret; + + /* Create a ROM disk for the /etc filesystem */ + + romfs_data_len = (uintptr_t)&romfs_data_end - (uintptr_t)&romfs_data_begin; + + ret = romdisk_register(CONFIG_STM32_ROMFS_DEV_MINOR, &romfs_data_begin, + NSECTORS(romfs_data_len), ROMFS_SECTOR_SIZE); + if (ret < 0) + { + ferr("ERROR: romdisk_register failed: %d\n", -ret); + return ret; + } + + /* Mount the file system */ + + finfo("Mounting ROMFS filesystem at target=%s with source=%s\n", + CONFIG_STM32_ROMFS_MOUNTPOINT, MOUNT_DEVNAME); + + ret = nx_mount(MOUNT_DEVNAME, CONFIG_STM32_ROMFS_MOUNTPOINT, + "romfs", MS_RDONLY, NULL); + if (ret < 0) + { + ferr("ERROR: nx_mount(%s,%s,romfs) failed: %d\n", + MOUNT_DEVNAME, CONFIG_STM32_ROMFS_MOUNTPOINT, ret); + return ret; + } + + return OK; +} + +#endif /* CONFIG_STM32_ROMFS */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_sdio.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_sdio.c new file mode 100644 index 00000000000..81f55ecdb51 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_sdio.c @@ -0,0 +1,163 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_sdio.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "stm32.h" +#include "stm32f4discovery.h" + +#ifdef HAVE_SDIO + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(HAVE_SDIO) || !defined(GPIO_SDIO_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct sdio_dev_s *g_sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, void *context, void *arg) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDIO_NCD); + if (present != g_sd_inserted) + { + sdio_mediachange(g_sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDIO_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDIO_NCD, true, true, true, + stm32_ncd_interrupt, NULL); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + g_sdio_dev = sdio_initialize(SDIO_SLOTNO); + if (!g_sdio_dev) + { + ferr("ERROR: Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, g_sdio_dev); + if (ret != OK) + { + ferr("ERROR: Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDIO_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(g_sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(g_sdio_dev, true); +#endif + + return OK; +} + +#endif /* HAVE_SDIO */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_spi.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_spi.c new file mode 100644 index 00000000000..6e58e484351 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_spi.c @@ -0,0 +1,333 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_spi.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "arm_internal.h" +#include "chip.h" +#include "stm32.h" + +#include "stm32f4discovery.h" + +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the stm32f4discovery + * board. + * + ****************************************************************************/ + +void weak_function stm32_spidev_initialize(void) +{ +#ifdef CONFIG_ENC28J60 + stm32_configgpio(GPIO_ENC28J60_CS); + stm32_configgpio(GPIO_ENC28J60_RESET); + stm32_configgpio(GPIO_ENC28J60_INTR); +#endif + +#ifdef CONFIG_STM32_SPI1 + stm32_configgpio(GPIO_CS_MEMS); /* MEMS chip select */ +#endif +#if defined(CONFIG_STM32_SPI2) && defined(CONFIG_SENSORS_MAX31855) + stm32_configgpio(GPIO_MAX31855_CS); /* MAX31855 chip select */ +#endif +#if defined(CONFIG_LCD_MAX7219) || defined(CONFIG_LEDS_MAX7219) + stm32_configgpio(GPIO_MAX7219_CS); /* MAX7219 chip select */ +#endif +#ifdef CONFIG_LPWAN_SX127X + stm32_configgpio(GPIO_SX127X_CS); /* SX127x chip select */ +#endif + +#if defined(CONFIG_LCD_ST7567) || defined(CONFIG_LCD_ST7567) + stm32_configgpio(STM32_LCD_CS); /* ST7567/ST7789 chip select */ +#endif +#if defined(CONFIG_STM32_SPI2) && defined(CONFIG_SENSORS_MAX6675) + stm32_configgpio(GPIO_MAX6675_CS); /* MAX6675 chip select */ +#endif +#if defined(CONFIG_LCD_UG2864AMBAG01) || defined(CONFIG_LCD_UG2864HSWEG01) || \ + defined(CONFIG_LCD_SSD1351) + stm32_configgpio(GPIO_OLED_CS); /* OLED chip select */ +# if defined(CONFIG_LCD_UG2864AMBAG01) + stm32_configgpio(GPIO_OLED_A0); /* OLED Command/Data */ +# endif +# if defined(CONFIG_LCD_UG2864HSWEG01) || defined(CONFIG_LCD_SSD1351) + stm32_configgpio(GPIO_OLED_DC); /* OLED Command/Data */ +# endif +#endif +} + +/**************************************************************************** + * Name: stm32_spi1/2/3select and stm32_spi1/2/3status + * + * Description: + * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status + * must be provided by board-specific logic. They are implementations of + * the select and status methods of the SPI interface defined by struct + * spi_ops_s (see include/nuttx/spi/spi.h). All other methods (including + * stm32_spibus_initialize()) are provided by common STM32 logic. To use + * this common SPI logic on your board: + * + * 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 board-specific logic. These functions will perform chip + * selection and status operations using GPIOs in the way your board + * is configured. + * 3. Add a calls to stm32_spibus_initialize() in your low level + * application initialization logic + * 4. The handle returned by stm32_spibus_initialize() may then be used to + * bind the SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_SPI1 +void stm32_spi1select(struct spi_dev_s *dev, uint32_t devid, + bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : + "de-assert"); + +#ifdef CONFIG_ENC28J60 + if (devid == SPIDEV_ETHERNET(0)) + { + /* Set the GPIO low to select and high to de-select */ + + stm32_gpiowrite(GPIO_ENC28J60_CS, !selected); + } +#endif + +#ifdef CONFIG_LPWAN_SX127X + if (devid == SPIDEV_LPWAN(0)) + { + stm32_gpiowrite(GPIO_SX127X_CS, !selected); + } +#endif + +#if defined(CONFIG_LCD_ST7567) || defined(CONFIG_LCD_ST7789) + if (devid == SPIDEV_DISPLAY(0)) + { + stm32_gpiowrite(STM32_LCD_CS, !selected); + } +#endif + +#if defined(CONFIG_LCD_MAX7219) || defined(CONFIG_LEDS_MAX7219) + if (devid == SPIDEV_DISPLAY(0)) + { + stm32_gpiowrite(GPIO_MAX7219_CS, !selected); + } +#endif + +#if defined(CONFIG_LCD_UG2864AMBAG01) || defined(CONFIG_LCD_UG2864HSWEG01) || \ + defined(CONFIG_LCD_SSD1351) + if (devid == SPIDEV_DISPLAY(0)) + { + stm32_gpiowrite(GPIO_OLED_CS, !selected); + } + else +#endif + { + stm32_gpiowrite(GPIO_CS_MEMS, !selected); + } +} + +uint8_t stm32_spi1status(struct spi_dev_s *dev, uint32_t devid) +{ + uint8_t status = 0; + +#ifdef CONFIG_LPWAN_SX127X + if (devid == SPIDEV_LPWAN(0)) + { + status |= SPI_STATUS_PRESENT; + } +#endif + + return status; +} +#endif + +#ifdef CONFIG_STM32_SPI2 +void stm32_spi2select(struct spi_dev_s *dev, uint32_t devid, + bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : + "de-assert"); + +#if defined(CONFIG_SENSORS_MAX31855) + if (devid == SPIDEV_TEMPERATURE(0)) + { + stm32_gpiowrite(GPIO_MAX31855_CS, !selected); + } +#endif + +#if defined(CONFIG_SENSORS_MAX6675) + if (devid == SPIDEV_TEMPERATURE(0)) + { + stm32_gpiowrite(GPIO_MAX6675_CS, !selected); + } +#endif + +#if defined(CONFIG_MMCSD_SPI) + if (devid == SPIDEV_MMCSD(0)) + { + stm32_gpiowrite(GPIO_MMCSD_NSS, !selected); + } +#endif +} + +uint8_t stm32_spi2status(struct spi_dev_s *dev, uint32_t devid) +{ + uint8_t ret = 0; +#if defined(CONFIG_MMCSD_SPI) + if (devid == SPIDEV_MMCSD(0)) + { + /* Note: SD_DET is pulled high when there's no SD card present. */ + + ret = stm32_gpioread(GPIO_MMCSD_NCD) ? 0 : 1; + } +#endif + + return ret; +} +#endif + +#ifdef CONFIG_STM32_SPI3 +void stm32_spi3select(struct spi_dev_s *dev, uint32_t devid, + bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : + "de-assert"); + +#if defined(CONFIG_WL_GS2200M) + if (devid == SPIDEV_WIRELESS(0)) + { + stm32_gpiowrite(GPIO_GS2200M_CS, !selected); + } +#endif +} + +uint8_t stm32_spi3status(struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +/**************************************************************************** + * Name: stm32_spi1cmddata + * + * Description: + * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true) + * or command (false). This function must be provided by platform-specific + * logic. This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_CMDDATA +#ifdef CONFIG_STM32_SPI1 +int stm32_spi1cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ +#if defined(CONFIG_LCD_ST7567) || defined(CONFIG_LCD_ST7789) + if (devid == SPIDEV_DISPLAY(0)) + { + /* This is the Data/Command control pad which determines whether the + * data bits are data or a command. + */ + + stm32_gpiowrite(STM32_LCD_RS, !cmd); + + return OK; + } +#endif + +#if defined(CONFIG_LCD_UG2864AMBAG01) || defined(CONFIG_LCD_UG2864HSWEG01) || \ + defined(CONFIG_LCD_SSD1351) + if (devid == SPIDEV_DISPLAY(0)) + { + /* "This is the Data/Command control pad which determines whether the + * data bits are data or a command. + * + * A0 = "H": the inputs at D0 to D7 are treated as display data. + * A0 = "L": the inputs at D0 to D7 are transferred to the command + * registers." + */ + +# if defined(CONFIG_LCD_UG2864AMBAG01) + stm32_gpiowrite(GPIO_OLED_A0, !cmd); +# endif +# if defined(CONFIG_LCD_UG2864HSWEG01) || defined(CONFIG_LCD_SSD1351) + stm32_gpiowrite(GPIO_OLED_DC, !cmd); +# endif + return OK; + } +#endif + + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32_SPI2 +int stm32_spi2cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32_SPI3 +int stm32_spi3cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return -ENODEV; +} +#endif +#endif /* CONFIG_SPI_CMDDATA */ + +#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ssd1289.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ssd1289.c new file mode 100644 index 00000000000..c436e24183b --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ssd1289.c @@ -0,0 +1,388 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_ssd1289.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include "arm_internal.h" +#include "stm32.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_LCD_SSD1289 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_STM32_FSMC +# error "CONFIG_STM32_FSMC is required to use the LCD" +#endif + +/* STM32F4Discovery LCD Hardware Definitions ********************************/ + +/* LCD /CS is CE1 == NOR/SRAM Bank 1 + * + * Bank 1 = 0x60000000 | 0x00000000 + * Bank 2 = 0x60000000 | 0x04000000 + * Bank 3 = 0x60000000 | 0x08000000 + * Bank 4 = 0x60000000 | 0x0c000000 + * + * FSMC address bit 16 is used to distinguish command and data. + * FSMC address bits 0-24 correspond to ARM address bits 1-25. + */ + +#define STM32_LCDBASE ((uintptr_t)(0x60000000 | 0x00000000)) +#define LCD_INDEX (STM32_LCDBASE) +#define LCD_DATA (STM32_LCDBASE + 0x00020000) + +/* SRAM pin definitions */ + +#define LCD_NADDRLINES 1 /* A16 */ +#define LCD_NDATALINES 16 /* D0-15 */ + +/**************************************************************************** + * Private Function Protototypes + ****************************************************************************/ + +/* Low Level LCD access */ + +static void stm32_select(struct ssd1289_lcd_s *dev); +static void stm32_deselect(struct ssd1289_lcd_s *dev); +static void stm32_index(struct ssd1289_lcd_s *dev, uint8_t index); +#ifndef CONFIG_SSD1289_WRONLY +static uint16_t stm32_read(struct ssd1289_lcd_s *dev); +#endif +static void stm32_write(struct ssd1289_lcd_s *dev, uint16_t data); +static void stm32_backlight(struct ssd1289_lcd_s *dev, int power); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* LCD pin mapping (see boards/arm/stm32/stm324discovery/README.txt + * MAPPING TO STM32 F4: + * + * ---------------- ------------- ---------------------------------- + * STM32 FUNCTION LCD PIN STM32F4Discovery PIN + * ---------------- ------------- ---------------------------------- + * FSMC_D0 D0 pin 4 PD14 P1 pin 46 Conflict (Note 1) + * FSMC_D1 D1 pin 3 PD15 P1 pin 47 Conflict (Note 2) + * FSMC_D2 D2 pin 6 PD0 P2 pin 36 Free I/O + * FSMC_D3 D3 pin 5 PD1 P2 pin 33 Free I/O + * FSMC_D4 D4 pin 8 PE7 P1 pin 25 Free I/O + * FSMC_D5 D5 pin 7 PE8 P1 pin 26 Free I/O + * FSMC_D6 D6 pin 10 PE9 P1 pin 27 Free I/O + * FSMC_D7 D7 pin 9 PE10 P1 pin 28 Free I/O + * FSMC_D8 D8 pin 12 PE11 P1 pin 29 Free I/O + * FSMC_D9 D9 pin 11 PE12 P1 pin 30 Free I/O + * FSMC_D10 D10 pin 14 PE13 P1 pin 31 Free I/O + * FSMC_D11 D11 pin 13 PE14 P1 pin 32 Free I/O + * FSMC_D12 D12 pin 16 PE15 P1 pin 33 Free I/O + * FSMC_D13 D13 pin 15 PD8 P1 pin 40 Free I/O + * FSMC_D14 D14 pin 18 PD9 P1 pin 41 Free I/O + * FSMC_D15 D15 pin 17 PD10 P1 pin 42 Free I/O + * FSMC_A16 RS pin 19 PD11 P1 pin 27 Free I/O + * FSMC_NE1 ~CS pin 10 PD7 P2 pin 27 Free I/O + * FSMC_NWE ~WR pin 22 PD5 P2 pin 29 Conflict (Note 3) + * FSMC_NOE ~RD pin 21 PD4 P2 pin 32 Conflict (Note 4) + * PC6 RESET pin 24 PC6 P2 pin 47 Free I/O + * ---------------- ------------- ---------------------------------- + * + * 1 Used for the RED LED + * 2 Used for the BLUE LED + * 3 Used for the RED LED and for OTG FS Overcurrent. It may be okay to + * use for the parallel interface if PC0 is held high (or floating). + * PC0 enables the STMPS2141STR IC power switch that drives the OTG FS + * host VBUS. + * 4 Also the reset pin for the CS43L22 audio Codec. + */ + +#define GPIO_LCD_RESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6) + +/* GPIO configurations unique to the LCD */ + +static const uint32_t g_lcdconfig[] = +{ + /* PC6(RESET), FSMC_A16, FSMC_NOE, FSMC_NWE, and FSMC_NE1 */ + + GPIO_LCD_RESET, GPIO_FSMC_A16, GPIO_FSMC_NOE, GPIO_FSMC_NWE, GPIO_FSMC_NE1 +}; +#define NLCD_CONFIG (sizeof(g_lcdconfig)/sizeof(uint32_t)) + +/* This is the driver state structure + * (there is no retained state information) + */ + +static struct ssd1289_lcd_s g_ssd1289 = +{ + .select = stm32_select, + .deselect = stm32_deselect, + .index = stm32_index, +#ifndef CONFIG_SSD1289_WRONLY + .read = stm32_read, +#endif + .write = stm32_write, + .backlight = stm32_backlight +}; + +/* The saved instance of the LCD driver */ + +static struct lcd_dev_s *g_ssd1289drvr; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_select + * + * Description: + * Select the LCD device + * + ****************************************************************************/ + +static void stm32_select(struct ssd1289_lcd_s *dev) +{ + /* Does not apply to this hardware */ +} + +/**************************************************************************** + * Name: stm32_deselect + * + * Description: + * De-select the LCD device + * + ****************************************************************************/ + +static void stm32_deselect(struct ssd1289_lcd_s *dev) +{ + /* Does not apply to this hardware */ +} + +/**************************************************************************** + * Name: stm32_deselect + * + * Description: + * Set the index register + * + ****************************************************************************/ + +static void stm32_index(struct ssd1289_lcd_s *dev, uint8_t index) +{ + putreg16((uint16_t)index, LCD_INDEX); +} + +/**************************************************************************** + * Name: stm32_read + * + * Description: + * Read LCD data (GRAM data or register contents) + * + ****************************************************************************/ + +#ifndef CONFIG_SSD1289_WRONLY +static uint16_t stm32_read(struct ssd1289_lcd_s *dev) +{ + return getreg16(LCD_DATA); +} +#endif + +/**************************************************************************** + * Name: stm32_write + * + * Description: + * Write LCD data (GRAM data or register contents) + * + ****************************************************************************/ + +static void stm32_write(struct ssd1289_lcd_s *dev, uint16_t data) +{ + putreg16((uint16_t)data, LCD_DATA); +} + +/**************************************************************************** + * Name: stm32_write + * + * Description: + * Write LCD data (GRAM data or register contents) + * + ****************************************************************************/ + +static void stm32_backlight(struct ssd1289_lcd_s *dev, int power) +{ +#warning "Missing logic" +} + +/**************************************************************************** + * Name: stm32_selectlcd + * + * Description: + * Initialize to the LCD + * + ****************************************************************************/ + +void stm32_selectlcd(void) +{ + /* Configure GPIO pins */ + + 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_fsmc_enable(); + + /* 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 + */ + + /* Bank1 NOR/SRAM control register configuration */ + + putreg32(FSMC_BCR_SRAM | FSMC_BCR_MWID16 | FSMC_BCR_WREN, STM32_FSMC_BCR1); + + /* Bank1 NOR/SRAM timing register configuration */ + + putreg32(FSMC_BTR_ADDSET(5) | FSMC_BTR_ADDHLD(0) | + FSMC_BTR_DATAST(9) | FSMC_BTR_BUSTURN(0) | + FSMC_BTR_CLKDIV(0) | FSMC_BTR_DATLAT(0) | + FSMC_BTR_ACCMODA, STM32_FSMC_BTR1); + + putreg32(0xffffffff, STM32_FSMC_BWTR1); + + /* Enable the bank by setting the MBKEN bit */ + + putreg32(FSMC_BCR_MBKEN | FSMC_BCR_SRAM | + FSMC_BCR_MWID16 | FSMC_BCR_WREN, STM32_FSMC_BCR1); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_lcd_initialize + * + * 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 board_lcd_initialize(void) +{ + /* Only initialize the driver once */ + + if (!g_ssd1289drvr) + { + lcdinfo("Initializing\n"); + + /* Configure GPIO pins and configure the FSMC to support the LCD */ + + stm32_selectlcd(); + + /* Reset the LCD (active low) */ + + stm32_gpiowrite(GPIO_LCD_RESET, false); + up_mdelay(5); + stm32_gpiowrite(GPIO_LCD_RESET, true); + + /* Configure and enable the LCD */ + + up_mdelay(50); + g_ssd1289drvr = ssd1289_lcdinitialize(&g_ssd1289); + if (!g_ssd1289drvr) + { + lcderr("ERROR: ssd1289_lcdinitialize failed\n"); + return -ENODEV; + } + } + + /* Clear the display (setting it to the color 0=black) */ + +#if 0 /* Already done in the driver */ + ssd1289_clear(g_ssd1289drvr, 0); +#endif + + /* Turn the display off */ + + g_ssd1289drvr->setpower(g_ssd1289drvr, 0); + return OK; +} + +/**************************************************************************** + * Name: board_lcd_getdev + * + * Description: + * Return a a reference to the LCD object for the specified LCD. + * This allows support for multiple LCD devices. + * + ****************************************************************************/ + +struct lcd_dev_s *board_lcd_getdev(int lcddev) +{ + DEBUGASSERT(lcddev == 0); + return g_ssd1289drvr; +} + +/**************************************************************************** + * Name: board_lcd_uninitialize + * + * Description: + * Uninitialize the LCD support + * + ****************************************************************************/ + +void board_lcd_uninitialize(void) +{ + /* Turn the display off */ + + g_ssd1289drvr->setpower(g_ssd1289drvr, 0); +} + +#endif /* CONFIG_LCD_SSD1289 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ssd1351.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ssd1351.c new file mode 100644 index 00000000000..8b7d4c77afd --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ssd1351.c @@ -0,0 +1,116 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_ssd1351.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_spi.h" + +#include "stm32f4discovery.h" + +#ifdef CONFIG_LCD_SSD1351 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* The pin configurations here require that SPI1 is selected */ + +#ifndef CONFIG_STM32_SPI1 +# error "The OLED driver requires CONFIG_STM32_SPI1 in the configuration" +#endif + +#ifndef CONFIG_SSD1351_SPI4WIRE +# error "The configuration requires the SPI 4-wire interface" +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_graphics_setup + * + * Description: + * Called by NX initialization logic to configure the OLED. + * + ****************************************************************************/ + +struct lcd_dev_s *board_graphics_setup(unsigned int devno) +{ + struct spi_dev_s *spi; + struct lcd_dev_s *dev; + + /* Configure the OLED GPIOs. This initial configuration is RESET low, + * putting the OLED into reset state. + */ + + stm32_configgpio(GPIO_OLED_RESET); + + /* Wait a bit then release the OLED from the reset state */ + + up_mdelay(20); + stm32_gpiowrite(GPIO_OLED_RESET, true); + + /* Get the SPI1 port interface */ + + spi = stm32_spibus_initialize(1); + if (spi == NULL) + { + lcderr("ERROR: Failed to initialize SPI port 1\n"); + } + else + { + /* Bind the SPI port to the OLED */ + + dev = ssd1351_initialize(spi, devno); + if (dev == NULL) + { + lcderr("ERROR: Failed to bind SPI port 1 to OLED %d\n", devno); + } + else + { + lcdinfo("Bound SPI port 1 to OLED %d\n", devno); + + /* And turn the OLED on */ + + dev->setpower(dev, LCD_FULL_ON); + return dev; + } + } + + return NULL; +} + +#endif /* CONFIG_LCD_SSD1351 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7032.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7032.c new file mode 100644 index 00000000000..abe9005a5f1 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7032.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_st7032.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "stm32.h" +#include "stm32f4discovery.h" + +#if defined(CONFIG_I2C) && defined(CONFIG_STM32_I2C1) && \ + defined(CONFIG_LCD_ST7032) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define ST7032_I2C_PORTNO 1 /* On I2C1 */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_st7032init + * + * Description: + * Initialize the st7032 display + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/disp0" + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int stm32_st7032init(const char *devpath) +{ + struct i2c_master_s *i2c; + int ret; + + i2c = stm32_i2cbus_initialize(ST7032_I2C_PORTNO); + if (i2c == NULL) + { + return -ENODEV; + } + + /* Register the ST7032 Driver at the specified location. */ + + ret = st7032_register(devpath, i2c); + if (ret < 0) + { + lcderr("ERROR: st7032_register(%s) failed: %d\n", + devpath, ret); + return ret; + } + + return OK; +} + +#endif /* CONFIG_I2C && CONFIG_LEDS_ST7032 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7567.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7567.c new file mode 100644 index 00000000000..3fddc55d62c --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7567.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_st7567.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "arm_internal.h" +#include "stm32_gpio.h" +#include "stm32_spi.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_LCD_ST7567 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define LCD_SPI_PORTNO 1 /* On SPI1 */ + +#ifndef CONFIG_LCD_CONTRAST +# define CONFIG_LCD_CONTRAST 0x1f +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct spi_dev_s *g_spidev; +struct lcd_dev_s *g_lcddev; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_lcd_initialize + ****************************************************************************/ + +int board_lcd_initialize(void) +{ + stm32_configgpio(STM32_LCD_RST); + stm32_configgpio(STM32_LCD_RS); + stm32_gpiowrite(STM32_LCD_RST, 1); + stm32_gpiowrite(STM32_LCD_RS, 1); + + g_spidev = stm32_spibus_initialize(LCD_SPI_PORTNO); + + if (!g_spidev) + { + lcderr("ERROR: Failed to initialize SPI port %d\n", LCD_SPI_PORTNO); + return -ENODEV; + } + + stm32_gpiowrite(STM32_LCD_RST, 0); + up_mdelay(1); + stm32_gpiowrite(STM32_LCD_RST, 1); + return OK; +} + +/**************************************************************************** + * Name: board_lcd_getdev + ****************************************************************************/ + +struct lcd_dev_s *board_lcd_getdev(int lcddev) +{ + g_lcddev = st7567_initialize(g_spidev, lcddev); + if (!g_lcddev) + { + lcderr("ERROR: Failed to bind SPI port 1 to LCD %d\n", lcddev); + } + else + { + lcdinfo("SPI port 1 bound to LCD %d\n", lcddev); + + /* And turn the LCD on (CONFIG_LCD_MAXPOWER should be 1) */ + + g_lcddev->setpower(g_lcddev, CONFIG_LCD_MAXPOWER); + + /* Set contrast to right value, otherwise background too dark */ + + g_lcddev->setcontrast(g_lcddev, CONFIG_LCD_CONTRAST); + + return g_lcddev; + } + + return NULL; +} + +/**************************************************************************** + * Name: board_lcd_uninitialize + ****************************************************************************/ + +void board_lcd_uninitialize(void) +{ + /* TO-FIX */ +} + +#endif /* CONFIG_LCD_ST7567 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7789.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7789.c new file mode 100644 index 00000000000..e45890fee36 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_st7789.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_st7789.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "stm32.h" +#include "stm32_gpio.h" +#include "stm32_spi.h" +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define LCD_SPI_PORTNO 1 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct spi_dev_s *g_spidev; +static struct lcd_dev_s *g_lcd = NULL; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_lcd_initialize + * + * 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 board_lcd_initialize(void) +{ + stm32_configgpio(STM32_LCD_RST); + stm32_configgpio(STM32_LCD_RS); + + g_spidev = stm32_spibus_initialize(LCD_SPI_PORTNO); + if (!g_spidev) + { + lcderr("ERROR: Failed to initialize SPI port %d\n", LCD_SPI_PORTNO); + return -ENODEV; + } + + stm32_gpiowrite(STM32_LCD_RST, 0); + up_mdelay(1); + stm32_gpiowrite(STM32_LCD_RST, 1); + up_mdelay(120); + + return OK; +} + +/**************************************************************************** + * Name: board_lcd_getdev + * + * Description: + * Return a a reference to the LCD object for the specified LCD. This + * allows support for multiple LCD devices. + * + ****************************************************************************/ + +struct lcd_dev_s *board_lcd_getdev(int devno) +{ + g_lcd = st7789_lcdinitialize(g_spidev); + if (!g_lcd) + { + lcderr("ERROR: Failed to bind SPI port %d to LCD %d\n", LCD_SPI_PORTNO, + devno); + } + else + { + lcdinfo("SPI port %d bound to LCD %d\n", LCD_SPI_PORTNO, devno); + return g_lcd; + } + + return NULL; +} + +/**************************************************************************** + * Name: board_lcd_uninitialize + * + * Description: + * Uninitialize the LCD support + * + ****************************************************************************/ + +void board_lcd_uninitialize(void) +{ + /* Turn the display off */ + + g_lcd->setpower(g_lcd, 0); +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_sx127x.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_sx127x.c new file mode 100644 index 00000000000..89db7df8c09 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_sx127x.c @@ -0,0 +1,201 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_sx127x.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_exti.h" +#include "stm32_spi.h" + +#include "stm32f4discovery.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* SX127X on SPI1 bus */ + +#define SX127X_SPI 1 + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static void sx127x_chip_reset(void); +static int sx127x_opmode_change(int opmode); +static int sx127x_freq_select(uint32_t freq); +static int sx127x_pa_select(bool enable); +static int sx127x_irq0_attach(xcpt_t isr, void *arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct sx127x_lower_s lower = +{ + .irq0attach = sx127x_irq0_attach, + .reset = sx127x_chip_reset, + .opmode_change = sx127x_opmode_change, + .freq_select = sx127x_freq_select, + .pa_select = sx127x_pa_select, + .pa_force = false +}; + +static bool g_high_power_output = false; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sx127x_irq0_attach + ****************************************************************************/ + +static int sx127x_irq0_attach(xcpt_t isr, void *arg) +{ + wlinfo("Attach DIO0 IRQ\n"); + + /* IRQ on rising edge */ + + stm32_gpiosetevent(GPIO_SX127X_DIO0, true, false, false, isr, arg); + return OK; +} + +/**************************************************************************** + * Name: sx127x_chip_reset + ****************************************************************************/ + +static void sx127x_chip_reset(void) +{ + wlinfo("SX127X RESET\n"); + + /* Configure reset as output */ + + stm32_configgpio(GPIO_SX127X_RESET); + + /* Set pin to zero */ + + stm32_gpiowrite(GPIO_SX127X_RESET, false); + + /* Wait 1 ms */ + + nxsig_usleep(1000); + + /* Configure reset as input */ + + stm32_configgpio(GPIO_SX127X_RESET | GPIO_INPUT | GPIO_FLOAT); + + /* Wait 10 ms */ + + nxsig_usleep(10000); +} + +/**************************************************************************** + * Name: sx127x_opmode_change + ****************************************************************************/ + +static int sx127x_opmode_change(int opmode) +{ + /* Nothing to do */ + + return OK; +} + +/**************************************************************************** + * Name: sx127x_freq_select + ****************************************************************************/ + +static int sx127x_freq_select(uint32_t freq) +{ + int ret = OK; + + /* Only HF supported (BAND3 - 860-930 MHz) */ + + if (freq < SX127X_HFBAND_THR) + { + ret = -EINVAL; + wlerr("LF band not supported\n"); + } + + return ret; +} + +/**************************************************************************** + * Name: sx127x_pa_select + ****************************************************************************/ + +static int sx127x_pa_select(bool enable) +{ + g_high_power_output = enable; + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int stm32_lpwaninitialize(void) +{ + struct spi_dev_s *spidev; + int ret = OK; + + wlinfo("Register the sx127x module\n"); + + /* Setup DIO0 */ + + stm32_configgpio(GPIO_SX127X_DIO0); + + /* Init SPI bus */ + + spidev = stm32_spibus_initialize(SX127X_SPI); + if (!spidev) + { + wlerr("ERROR: Failed to initialize SPI %d bus\n", SX127X_SPI); + ret = -ENODEV; + goto errout; + } + + /* Initialize SX127X */ + + ret = sx127x_register(spidev, &lower); + if (ret < 0) + { + wlerr("ERROR: Failed to register sx127x\n"); + goto errout; + } + +errout: + return ret; +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_timer.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_timer.c new file mode 100644 index 00000000000..b9abcab9018 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_timer.c @@ -0,0 +1,65 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_timer.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include + +#include "stm32_tim.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_TIMER + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_timer_driver_setup + * + * Description: + * Configure the timer driver. + * + * Input Parameters: + * devpath - The full path to the timer device. + * This should be of the form /dev/timer0 + * timer - The timer's number. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned + * to indicate the nature of any failure. + * + ****************************************************************************/ + +int stm32_timer_driver_setup(const char *devpath, int timer) +{ + return stm32_timer_initialize(devpath, timer); +} + +#endif diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ug2864ambag01.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ug2864ambag01.c new file mode 100644 index 00000000000..e0ace3b80b0 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ug2864ambag01.c @@ -0,0 +1,141 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_ug2864ambag01.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_spi.h" + +#include "stm32f4discovery.h" + +#ifdef CONFIG_LCD_UG2864AMBAG01 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* The pin configurations here require that SPI1 is selected */ + +#ifndef CONFIG_STM32_SPI1 +# error "The OLED driver requires CONFIG_STM32_SPI1 in the configuration" +#endif + +#ifndef CONFIG_SPI_CMDDATA +# error "The OLED driver requires CONFIG_SPI_CMDDATA in the configuration" +#endif + +/* Pin Configuration ********************************************************/ + +/* UG-2864AMBAG01 OLED Display (SPI 4-wire): + * + * --------------------------+---------------------------------------------- + * Connector CON10 J1: | STM32F4Discovery + * --------------+-----------+---------------------------------------------- + * CON10 J1: | CON20 J2: | P1/P2: + * --------------+-----------+---------------------------------------------- + * 1 3v3 | 3,4 3v3 | P2 3V + * 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) + * 5 /CS | 7 /CS | P2 PB7 (Arbitrary selection)(2) + * 7 A0 | 9 A0 | P2 PB8 (Arbitrary selection)(2) + * 9 LED+ (N/C) | ----- | ----- + * 2 5V Vcc | 1,2 Vcc | P2 5V + * 4 DI | 18 D1/SI | P1 PA7 (GPIO_SPI1_MOSI==GPIO_SPI1_MOSI_1 (1)) + * 6 SCLK | 19 D0/SCL | P1 PA5 (GPIO_SPI1_SCK==GPIO_SPI1_SCK_1 (2)) + * 8 LED- (N/C) | ----- | ------ + * 10 GND | 20 GND | P2 GND + * --------------+-----------+---------------------------------------------- + * (1) Required because of on-board MEMS + * (2) Note that the OLED CS and A0 are managed in the stm32_spi.c file. + * ------------------------------------------------------------------------- + */ + +/* Definitions in stm32f4discovery.h */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_graphics_setup + * + * Description: + * Called by NX initialization logic to configure the OLED. + * + ****************************************************************************/ + +struct lcd_dev_s *board_graphics_setup(unsigned int devno) +{ + struct spi_dev_s *spi; + struct lcd_dev_s *dev; + + /* Configure the OLED GPIOs. This initial configuration is RESET low, + * putting the OLED into reset state. + */ + + stm32_configgpio(GPIO_OLED_RESET); + + /* Wait a bit then release the OLED from the reset state */ + + up_mdelay(20); + stm32_gpiowrite(GPIO_OLED_RESET, true); + + /* Get the SPI1 port interface */ + + spi = stm32_spibus_initialize(1); + if (!spi) + { + lcderr("ERROR: Failed to initialize SPI port 1\n"); + } + else + { + /* Bind the SPI port to the OLED */ + + dev = ug2864ambag01_initialize(spi, devno); + if (!dev) + { + lcderr("ERROR: Failed to bind SPI port 1 to OLED %d\n", devno); + } + else + { + lcdinfo("Bound SPI port 1 to OLED %d\n", devno); + + /* And turn the OLED on */ + + dev->setpower(dev, CONFIG_LCD_MAXPOWER); + return dev; + } + } + + return NULL; +} +#endif /* CONFIG_LCD_UG2864AMBAG01 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ug2864hsweg01.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ug2864hsweg01.c new file mode 100644 index 00000000000..6c872a7fa78 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_ug2864hsweg01.c @@ -0,0 +1,141 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_ug2864hsweg01.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_spi.h" + +#include "stm32f4discovery.h" + +#ifdef CONFIG_LCD_UG2864HSWEG01 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* The pin configurations here require that SPI1 is selected */ + +#ifndef CONFIG_STM32_SPI1 +# error "The OLED driver requires CONFIG_STM32_SPI1 in the configuration" +#endif + +#ifndef CONFIG_SPI_CMDDATA +# error "The OLED driver requires CONFIG_SPI_CMDDATA in the configuration" +#endif + +/* Pin Configuration ********************************************************/ + +/* UG-2864HSWEG01 OLED Display (SPI 4-wire): + * + * --------------------------+---------------------------------------------- + * Connector CON10 J1: | STM32F4Discovery + * --------------+-----------+---------------------------------------------- + * CON10 J1: | CON20 J2: | P1/P2: + * --------------+-----------+---------------------------------------------- + * 1 3v3 | 3,4 3v3 | P2 3V + * 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) + * 5 /CS | 7 /CS | P2 PB7 (Arbitrary selection)(2) + * 7 D/C | 9 D/C | P2 PB8 (Arbitrary selection)(2) + * 9 LED+ (N/C) | ----- | ----- + * 2 5V Vcc | 1,2 Vcc | P2 5V + * 4 DI | 18 D1/SI | P1 PA7 (GPIO_SPI1_MOSI==GPIO_SPI1_MOSI_1 (1)) + * 6 SCLK | 19 D0/SCL | P1 PA5 (GPIO_SPI1_SCK==GPIO_SPI1_SCK_1 (2)) + * 8 LED- (N/C) | ----- | ------ + * 10 GND | 20 GND | P2 GND + * --------------+-----------+---------------------------------------------- + * (1) Required because of on-board MEMS + * (2) Note that the OLED CS and D/C are managed in the stm32_spi.c file. + * ------------------------------------------------------------------------- + */ + +/* Definitions in stm32f4discovery.h */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_graphics_setup + * + * Description: + * Called by NX initialization logic to configure the OLED. + * + ****************************************************************************/ + +struct lcd_dev_s *board_graphics_setup(unsigned int devno) +{ + struct spi_dev_s *spi; + struct lcd_dev_s *dev; + + /* Configure the OLED GPIOs. This initial configuration is RESET low, + * putting the OLED into reset state. + */ + + stm32_configgpio(GPIO_OLED_RESET); + + /* Wait a bit then release the OLED from the reset state */ + + up_mdelay(20); + stm32_gpiowrite(GPIO_OLED_RESET, true); + + /* Get the SPI1 port interface */ + + spi = stm32_spibus_initialize(1); + if (!spi) + { + lcderr("ERROR: Failed to initialize SPI port 1\n"); + } + else + { + /* Bind the SPI port to the OLED */ + + dev = ssd1306_initialize(spi, NULL, devno); + if (!dev) + { + lcderr("ERROR: Failed to bind SPI port 1 to OLED %d\n", devno); + } + else + { + lcdinfo("Bound SPI port 1 to OLED %d\n", devno); + + /* And turn the OLED on */ + + dev->setpower(dev, CONFIG_LCD_MAXPOWER); + return dev; + } + } + + return NULL; +} +#endif /* CONFIG_LCD_UG2864AMBAG01 */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_uid.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_uid.c new file mode 100644 index 00000000000..5c03486606e --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_uid.c @@ -0,0 +1,70 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_uid.c + * + * Copyright (C) 2015 Marawan Ragab. All rights reserved. + * Author: Marawan Ragab + * + * 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 + +#include +#include "stm32_uid.h" + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef OK +# define OK 0 +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#if defined(CONFIG_BOARDCTL_UNIQUEID) +int board_uniqueid(uint8_t *uniqueid) +{ + if (uniqueid == NULL) + { + return -EINVAL; + } + + stm32_get_uniqueid(uniqueid); + return OK; +} +#endif diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_usb.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_usb.c new file mode 100644 index 00000000000..7b8c718060a --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_usb.c @@ -0,0 +1,338 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_usb.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "arm_internal.h" +#include "stm32.h" +#include "stm32_otgfs.h" +#include "stm32f4discovery.h" + +#ifdef CONFIG_STM32_OTGFS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST) +# define HAVE_USB 1 +#else +# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST" +# undef HAVE_USB +#endif + +#ifndef CONFIG_STM32F4DISCO_USBHOST_PRIO +# define CONFIG_STM32F4DISCO_USBHOST_PRIO 100 +#endif + +#ifndef CONFIG_STM32F4DISCO_USBHOST_STACKSIZE +# define CONFIG_STM32F4DISCO_USBHOST_STACKSIZE 1024 +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_USBHOST +static struct usbhost_connection_s *g_usbconn; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbhost_waiter + * + * Description: + * Wait for USB devices to be connected. + * + ****************************************************************************/ + +#ifdef CONFIG_USBHOST +static int usbhost_waiter(int argc, char *argv[]) +{ + struct usbhost_hubport_s *hport; + + uinfo("Running\n"); + for (; ; ) + { + /* Wait for the device to change state */ + + DEBUGVERIFY(CONN_WAIT(g_usbconn, &hport)); + uinfo("%s\n", hport->connected ? "connected" : "disconnected"); + + /* Did we just become connected? */ + + if (hport->connected) + { + /* Yes.. enumerate the newly connected device */ + + CONN_ENUMERATE(g_usbconn, hport); + } + } + + /* Keep the compiler from complaining */ + + return 0; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup + * USB-related GPIO pins for the STM32F4Discovery board. + * + ****************************************************************************/ + +void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up. + * No GPIO configuration is required + */ + + /* 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_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host + * functionality. + * This function will start a thread that will monitor for device + * connection/disconnection events. + * + ****************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_usbhost_initialize(void) +{ + int ret; + + /* First, register all of the class drivers needed to support the drivers + * that we care about: + */ + + uinfo("Register class drivers\n"); + +#ifdef CONFIG_USBHOST_HUB + /* Initialize USB hub class support */ + + ret = usbhost_hub_initialize(); + if (ret < 0) + { + uerr("ERROR: usbhost_hub_initialize failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_MSC + /* Register the USB mass storage class class */ + + ret = usbhost_msc_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to register the mass storage class: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_CDCACM + /* Register the CDC/ACM serial class */ + + ret = usbhost_cdcacm_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to register the CDC/ACM serial class: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_HIDKBD + /* Initialize the HID keyboard class */ + + ret = usbhost_kbdinit(); + if (ret != OK) + { + uerr("ERROR: Failed to register the HID keyboard class\n"); + } +#endif + +#ifdef CONFIG_USBHOST_HIDMOUSE + /* Initialize the HID mouse class */ + + ret = usbhost_mouse_init(); + if (ret != OK) + { + uerr("ERROR: Failed to register the HID mouse class\n"); + } +#endif + +#ifdef CONFIG_USBHOST_XBOXCONTROLLER + /* Initialize the HID mouse class */ + + ret = usbhost_xboxcontroller_init(); + if (ret != OK) + { + uerr("ERROR: Failed to register the XBox Controller class\n"); + } +#endif + + /* Then get an instance of the USB host interface */ + + uinfo("Initialize USB host\n"); + g_usbconn = stm32_otgfshost_initialize(0); + if (g_usbconn) + { + /* Start a thread to handle device connection. */ + + uinfo("Start usbhost_waiter\n"); + + ret = kthread_create("usbhost", CONFIG_STM32F4DISCO_USBHOST_PRIO, + CONFIG_STM32F4DISCO_USBHOST_STACKSIZE, + (main_t)usbhost_waiter, (char * const *)NULL); + return ret < 0 ? -ENOEXEC : OK; + } + + return -ENODEV; +} +#endif + +/**************************************************************************** + * Name: stm32_usbhost_vbusdrive + * + * Description: + * Enable/disable driving of VBUS 5V output. This function must be + * provided be each platform that implements the STM32 OTG FS host + * interface + * + * "On-chip 5 V VBUS generation is not supported. For this reason, a + * charge pump or, if 5 V are available on the application board, a + * basic power switch, must be added externally to drive the 5 V VBUS + * line. The external charge pump can be driven by any GPIO output. + * When the application decides to power on VBUS using the chosen GPIO, + * it must also set the port power bit in the host port control and + * status register (PPWR bit in OTG_FS_HPRT). + * + * "The application uses this field to control power to this port, + * and the core clears this bit on an overcurrent condition." + * + * Input Parameters: + * iface - For future growth to handle multiple USB host interface. + * Should be zero. + * enable - true: enable VBUS power; false: disable VBUS power + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_USBHOST +void stm32_usbhost_vbusdrive(int iface, bool enable) +{ + DEBUGASSERT(iface == 0); + + if (enable) + { + /* Enable the Power Switch by driving the enable pin low */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, false); + } + else + { + /* Disable the Power Switch by driving the enable pin high */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, true); + } +} +#endif + +/**************************************************************************** + * Name: stm32_setup_overcurrent + * + * Description: + * Setup to receive an interrupt-level callback if an overcurrent + * condition is detected. + * + * Input Parameters: + * handler - New overcurrent interrupt handler + * arg - The argument provided for the interrupt handler + * + * Returned Value: + * Zero (OK) is returned on success. Otherwise, a negated errno value + * is returned to indicate the nature of the failure. + * + ****************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_setup_overcurrent(xcpt_t handler, void *arg) +{ + return stm32_gpiosetevent(GPIO_OTGFS_OVER, true, true, true, handler, arg); +} +#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. + * + ****************************************************************************/ + +#ifdef CONFIG_USBDEV +void stm32_usbsuspend(struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} +#endif + +#endif /* CONFIG_STM32_OTGFS */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_usbmsc.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_usbmsc.c new file mode 100644 index 00000000000..a209fc1c79f --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_usbmsc.c @@ -0,0 +1,70 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_usbmsc.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "stm32.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_SYSTEM_USBMSC_DEVMINOR1 +# define CONFIG_SYSTEM_USBMSC_DEVMINOR1 0 +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_usbmsc_initialize + * + * Description: + * Perform architecture specific initialization of the USB MSC device. + * + ****************************************************************************/ + +int board_usbmsc_initialize(int port) +{ + /* If system/usbmsc is built as an NSH command, then SD slot should + * already have been initialized in board_app_initialize() + * (see stm32_appinit.c). + * In this case, there is nothing further to be done here. + */ + +#ifndef CONFIG_NSH_BUILTIN_APPS + return stm32_sdinitialize(CONFIG_SYSTEM_USBMSC_DEVMINOR1); +#else + return OK; +#endif +} diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32_userleds.c b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_userleds.c new file mode 100644 index 00000000000..a058cdaa5a2 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32_userleds.c @@ -0,0 +1,214 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32_userleds.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include "chip.h" +#include "arm_internal.h" +#include "stm32.h" +#include "stm32f4discovery.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This array maps an LED number to GPIO pin configuration */ + +static uint32_t g_ledcfg[BOARD_NLEDS] = +{ + GPIO_LED1, GPIO_LED2, GPIO_LED3, GPIO_LED4 +}; + +/**************************************************************************** + * Private Function Protototypes + ****************************************************************************/ + +/* LED Power Management */ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_PM +static struct pm_callback_s g_ledscb = +{ + .notify = led_pm_notify, + .prepare = led_pm_prepare, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: led_pm_notify + * + * Description: + * Notify the driver of new power state. This callback is called after + * all drivers have had the opportunity to prepare for the new power state. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + switch (pmstate) + { + case(PM_NORMAL): + { + /* Restore normal LEDs operation */ + } + break; + + case(PM_IDLE): + { + /* Entering IDLE mode - Turn leds off */ + } + break; + + case(PM_STANDBY): + { + /* Entering STANDBY mode - Logic for PM_STANDBY goes here */ + } + break; + + case(PM_SLEEP): + { + /* Entering SLEEP mode - Logic for PM_SLEEP goes here */ + } + break; + + default: + { + /* Should not get here */ + } + break; + } +} +#endif + +/**************************************************************************** + * Name: led_pm_prepare + * + * Description: + * Request the driver to prepare for a new power state. This is a warning + * that the system is about to enter into a new power state. The driver + * should begin whatever operations that may be required to enter power + * state. The driver may abort the state change mode by returning a + * non-zero value from the callback function. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + /* No preparation to change power modes is required by the LEDs driver. + * We always accept the state change by returning OK. + */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +uint32_t board_userled_initialize(void) +{ + /* Configure LED1-4 GPIOs for output */ + + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); + stm32_configgpio(GPIO_LED3); + stm32_configgpio(GPIO_LED4); + return BOARD_NLEDS; +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + if ((unsigned)led < BOARD_NLEDS) + { + stm32_gpiowrite(g_ledcfg[led], ledon); + } +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint32_t ledset) +{ + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(GPIO_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(GPIO_LED4, (ledset & BOARD_LED4_BIT) == 0); +} + +/**************************************************************************** + * Name: stm32_led_pminitialize + ****************************************************************************/ + +#ifdef CONFIG_PM +void stm32_led_pminitialize(void) +{ + /* Register to receive power management callbacks */ + + int ret = pm_register(&g_ledscb); + if (ret != OK) + { + board_autoled_on(LED_ASSERTION); + } +} +#endif /* CONFIG_PM */ + +#endif /* !CONFIG_ARCH_LEDS */ diff --git a/boards/arm/stm32/stm32f427a_Cubus/src/stm32f4discovery.h b/boards/arm/stm32/stm32f427a_Cubus/src/stm32f4discovery.h new file mode 100644 index 00000000000..15953dd4a66 --- /dev/null +++ b/boards/arm/stm32/stm32f427a_Cubus/src/stm32f4discovery.h @@ -0,0 +1,882 @@ +/**************************************************************************** + * boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __BOARDS_ARM_STM32_STM32F4DISCOVERY_SRC_STM32F4DISCOVERY_H +#define __BOARDS_ARM_STM32_STM32F4DISCOVERY_SRC_STM32F4DISCOVERY_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* How many SPI modules does this chip support? */ + +#if STM32_NSPI < 1 +# undef CONFIG_STM32_SPI1 +# undef CONFIG_STM32_SPI2 +# undef CONFIG_STM32_SPI3 +#elif STM32_NSPI < 2 +# undef CONFIG_STM32_SPI2 +# undef CONFIG_STM32_SPI3 +#elif STM32_NSPI < 3 +# undef CONFIG_STM32_SPI3 +#endif + +#define PCA9635_I2CBUS 1 +#define PCA9635_I2CADDR 0x40 + +/* Assume that we have everything */ + +#define HAVE_USBDEV 1 +#define HAVE_USBHOST 1 +#define HAVE_USBMONITOR 1 +#define HAVE_SDIO 1 +#define HAVE_CS43L22 1 +#define HAVE_RTC_DRIVER 1 +#define HAVE_NETMONITOR 1 +#define HAVE_HCIUART 1 + +/* Can't support USB host or device features if USB OTG FS is not enabled */ + +#ifndef CONFIG_STM32_OTGFS +# undef HAVE_USBDEV +# undef HAVE_USBHOST +#endif + +/* Can't support USB device if USB device is not enabled */ + +#ifndef CONFIG_USBDEV +# undef HAVE_USBDEV +#endif + +/* Can't support USB host is USB host is not enabled */ + +#ifndef CONFIG_USBHOST +# undef HAVE_USBHOST +#endif + +/* Check if we should enable the USB monitor before starting NSH */ + +#ifndef CONFIG_USBMONITOR +# undef HAVE_USBMONITOR +#endif + +#ifndef HAVE_USBDEV +# undef CONFIG_USBDEV_TRACE +#endif + +#ifndef HAVE_USBHOST +# undef CONFIG_USBHOST_TRACE +#endif + +#if !defined(CONFIG_USBDEV_TRACE) && !defined(CONFIG_USBHOST_TRACE) +# undef HAVE_USBMONITOR +#endif + +/* Can't support MMC/SD features if mountpoints are disabled or if SDIO + * support is not enabled. + */ + +#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO) +# undef HAVE_SDIO +#endif + +#undef SDIO_MINOR /* Any minor number, default 0 */ +#define SDIO_SLOTNO 0 /* Only one slot */ + +#ifdef HAVE_SDIO +# if !defined(CONFIG_NSH_MMCSDSLOTNO) +# define CONFIG_NSH_MMCSDSLOTNO SDIO_SLOTNO +# elif CONFIG_NSH_MMCSDSLOTNO != 0 +# warning "Only one MMC/SD slot, slot 0" +# undef CONFIG_NSH_MMCSDSLOTNO +# define CONFIG_NSH_MMCSDSLOTNO SDIO_SLOTNO +# endif + +# if defined(CONFIG_NSH_MMCSDMINOR) +# define SDIO_MINOR CONFIG_NSH_MMCSDMINOR +# else +# define SDIO_MINOR 0 +# endif +#endif + +/* The CS43L22 depends on the CS43L22 driver, I2C1, and I2S3 support */ + +#if !defined(CONFIG_AUDIO_CS43L22) || !defined(CONFIG_STM32_I2C1) || \ + !defined(CONFIG_STM32_I2S3) +# undef HAVE_CS43L22 +#endif + +#ifdef HAVE_CS43L22 + /* The CS43L22 communicates on I2C1, I2C address 0x1a for control + * operations + */ + +# define CS43L22_I2C_BUS 1 +# define CS43L22_I2C_ADDRESS (0x94 >> 1) + + /* The CS43L22 transfers data on I2S3 */ + +# define CS43L22_I2S_BUS 3 +#endif + +/* Check if we can support the RTC driver */ + +#if !defined(CONFIG_RTC) || !defined(CONFIG_RTC_DRIVER) +# undef HAVE_RTC_DRIVER +#endif + +/* NSH Network monitor */ + +#if !defined(CONFIG_NET) || !defined(CONFIG_STM32_EMACMAC) +# undef HAVE_NETMONITOR +#endif + +#if !defined(CONFIG_NSH_NETINIT_THREAD) || !defined(CONFIG_ARCH_PHY_INTERRUPT) || \ + !defined(CONFIG_NETDEV_PHY_IOCTL) || !defined(CONFIG_NET_UDP) +# undef HAVE_NETMONITOR +#endif + +/* The NSH Network Monitor cannot be used with the STM32F4DIS-BB base board. + * That is because the LAN8720 is configured in REF_CLK OUT mode. In that + * mode, the PHY interrupt is not supported. The NINT pin serves instead as + * REFLCK0. + */ + +#ifdef CONFIG_STM32F4DISBB +# undef HAVE_NETMONITOR +#endif + +/* procfs File System */ + +#ifdef CONFIG_FS_PROCFS +# ifdef CONFIG_NSH_PROC_MOUNTPOINT +# define STM32_PROCFS_MOUNTPOINT CONFIG_NSH_PROC_MOUNTPOINT +# else +# define STM32_PROCFS_MOUNTPOINT "/proc" +# endif +#endif + +/* Check if we have the prerequisites for an HCI UART */ + +#if !defined(CONFIG_STM32_HCIUART) || !defined(CONFIG_BLUETOOTH_UART) +# undef HAVE_HCIUART +#elif defined(CONFIG_STM32_USART1_HCIUART) +# define HCIUART_SERDEV HCIUART1 +#elif defined(CONFIG_STM32_USART2_HCIUART) +# define HCIUART_SERDEV HCIUART2 +#elif defined(CONFIG_STM32_USART3_HCIUART) +# define HCIUART_SERDEV HCIUART3 +#elif defined(CONFIG_STM32_USART6_HCIUART) +# define HCIUART_SERDEV HCIUART6 +#elif defined(CONFIG_STM32_UART7_HCIUART) +# define HCIUART_SERDEV HCIUART7 +#elif defined(CONFIG_STM32_UART8_HCIUART) +# define HCIUART_SERDEV HCIUART8 +#else +# error No HCI UART specifified +#endif + +/* STM32F4 Discovery GPIOs **************************************************/ + +/* LEDs */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12) +#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) +#define GPIO_LED3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) +#define GPIO_LED4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15) + +/* BUTTONS -- NOTE that all have EXTI interrupts configured */ + +#define MIN_IRQBUTTON BUTTON_USER +#define MAX_IRQBUTTON BUTTON_USER +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_USER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0) + +#define GPIO_CS43L22_RESET (GPIO_OUTPUT|GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN4) + +/* LoRa SX127x */ + +#define GPIO_SX127X_DIO0 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0) + +#define GPIO_SX127X_RESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_CLEAR|\ + GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN4) + +/* PWM + * + * The STM32F4 Discovery has no real on-board PWM devices, but the board can + * be configured to output a pulse train using TIM4 CH2 on PD13. + */ + +#define STM32F4DISCOVERY_PWMTIMER 4 +#define STM32F4DISCOVERY_PWMCHANNEL 2 + +/* Capture + * + * The STM32F4 Discovery has no real on-board pwm capture devices, but the + * board can be configured to capture pwm using TIM3 CH2 PB5. + */ + +#define STM32F4DISCOVERY_CAPTURETIMER 3 +#define STM32F4DISCOVERY_CAPTURECHANNEL 2 + +/* SPI chip selects */ + +#define GPIO_CS_MEMS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) + +#define GPIO_MAX31855_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN8) + +#define GPIO_MAX6675_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN8) + +#define GPIO_SX127X_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN8) + +#define GPIO_MAX7219_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN3) + +#define GPIO_GS2200M_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +#define GPIO_ENC28J60_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + +#define GPIO_ENC28J60_RESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN1) + +#define GPIO_ENC28J60_INTR (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|\ + GPIO_OPENDRAIN|GPIO_PORTE|GPIO_PIN4) + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) + * PC0 OTG_FS_PowerSwitchOn + * PD5 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_PORTC|GPIO_PIN0) + +#ifdef CONFIG_USBHOST +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_EXTI|GPIO_FLOAT|\ + GPIO_SPEED_100MHz|GPIO_PUSHPULL|\ + GPIO_PORTD|GPIO_PIN5) +#else +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|\ + GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5) +#endif + +/* UG-2864AMBAG01 or UG-2864HSWEG01 OLED Display (SPI 4-wire): + * + * --------------------------+---------------------------------------------- + * Connector CON10 J1: | STM32F4Discovery + * --------------+-----------+---------------------------------------------- + * CON10 J1: | CON20 J2: | P1/P2: + * --------------+-----------+---------------------------------------------- + * 1 3v3 | 3,4 3v3 | P2 3V + * 3 /RESET | 8 /RESET | P2 PB6 (Arbitrary selection) + * 5 /CS | 7 /CS | P2 PB7 (Arbitrary selection) + * 7 A0|D/C | 9 A0|D/C | P2 PB8 (Arbitrary selection) + * 9 LED+ (N/C) | ----- | ----- + * 2 5V Vcc | 1,2 Vcc | P2 5V + * 4 DI | 18 D1/SI | P1 PA7 (GPIO_SPI1_MOSI == GPIO_SPI1_MOSI_1(1)) + * 6 SCLK | 19 D0/SCL | P1 PA5 (GPIO_SPI1_SCK == GPIO_SPI1_SCK_1(1)) + * 8 LED- (N/C) | ----- | ------ + * 10 GND | 20 GND | P2 GND + * --------------+-----------+---------------------------------------------- + * (1) Required because of on-board MEMS + * ------------------------------------------------------------------------- + */ + +#if defined(CONFIG_LCD_UG2864AMBAG01) || defined(CONFIG_LCD_UG2864HSWEG01) || \ + defined(CONFIG_LCD_SSD1351) +# define GPIO_OLED_RESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6) +# define GPIO_OLED_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN7) +# define GPIO_OLED_A0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8) +# define GPIO_OLED_DC GPIO_OLED_A0 +#endif + +/* Display JLX12864G */ + +#define STM32_LCD_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN6) + +#define STM32_LCD_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN7) + +#define STM32_LCD_RS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) + +/* STM32F4DIS-BB MicroSD + * + * ---------- ------------- ------------------------------ + * PIO SIGNAL Comments + * ---------- ------------- ------------------------------ + * PB15 NCD Pulled up externally + * PC9 DAT1 Configured by driver + * PC8 DAT0 " " "" " " + * PC12 CLK " " "" " " + * PD2 CMD " " "" " " + * PC11 CD/DAT3 " " "" " " + * PC10 DAT2 " " "" " " + * ---------- ------------- ------------------------------ + */ + +#if defined(CONFIG_STM32F4DISBB) && defined(CONFIG_STM32_SDIO) +# define GPIO_SDIO_NCD (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|\ + GPIO_PORTB|GPIO_PIN15) +#endif + +/* STM32F4DIS-BB LAN8720 + * + * ---------- ------------- ------------------------------ + * PIO SIGNAL Comments + * ---------- ------------- ------------------------------ + * PB11 TXEN Configured by driver + * PB12 TXD0 " " "" " " + * PB13 TXD1 " " "" " " + * PC4 RXD0/MODE0 " " "" " " + * PC5 RXD1/MODE1 " " "" " " + * PA7 CRS_DIV/MODE2 " " "" " " + * PA2 MDIO " " "" " " + * PC1 MDC " " "" " " + * PA1 NINT/REFCLK0 " " "" " " + * PE2 DAT2 " " "" " " + * ---------- ------------- ------------------------------ + */ + +#if defined(CONFIG_STM32F4DISBB) && defined(CONFIG_STM32_ETHMAC) +# define GPIO_EMAC_NINT (GPIO_INPUT|GPIO_PULLUP|GPIO_EXTI|\ + GPIO_PORTA|GPIO_PIN1) +# define GPIO_EMAC_NRST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_LATE_INITIALIZE=y : + * Called from board_late_initialize(). + * + * CONFIG_BOARD_LATE_INITIALIZE=y && CONFIG_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void); + +/**************************************************************************** + * Name: stm32_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the stm32f4discovery + * board. + * + ****************************************************************************/ + +void weak_function stm32_spidev_initialize(void); + +/**************************************************************************** + * Name: stm32_i2sdev_initialize + * + * Description: + * Called to configure I2S chip select GPIO pins for the stm32f4discovery + * board. + * + ****************************************************************************/ + +void weak_function stm32_i2sdev_initialize(void); + +/**************************************************************************** + * Name: stm32_bh1750initialize + * + * Description: + * Called to configure an I2C and to register BH1750FVI for the + * stm32f4discovery board. + * + ****************************************************************************/ + +#ifdef CONFIG_SENSORS_BH1750FVI +int stm32_bh1750initialize(const char *devpath); +#endif + +/**************************************************************************** + * Name: stm32_lpwaninitialize + * + * Description: + * Initialize SX127X LPWAN interaface. + ****************************************************************************/ + +#ifdef CONFIG_LPWAN_SX127X +int stm32_lpwaninitialize(void); +#endif + +/**************************************************************************** + * Name: stm32_mmcsdinitialize + * + * Description: + * Sets up MMC/SD interface. + * + ****************************************************************************/ + +#ifdef CONFIG_MMCSD_SPI +int stm32_mmcsd_initialize(int port, int minor); +#endif + +/**************************************************************************** + * Name: nunchuck_initialize + * + * Description: + * Initialize and register the button joystick driver + * + ****************************************************************************/ + +#ifdef CONFIG_INPUT_NUNCHUCK +int nunchuck_initialize(char *devname); +#endif + +/**************************************************************************** + * Name: stm32_max7219init + * + * Description: + * Initialize and register the max7219 numeric display controller + * + ****************************************************************************/ + +#ifdef CONFIG_LEDS_MAX7219 +int stm32_max7219init(const char *devpath); +#endif + +/**************************************************************************** + * Name: stm32_ds1307_init + * + * Description: + * Initialize and register the DS1307 RTC + * + ****************************************************************************/ + +#ifdef CONFIG_RTC_DS1307 +int stm32_ds1307_init(void); +#endif + +/**************************************************************************** + * Name: stm32_st7032init + * + * Description: + * Initialize and register the Sitronix ST7032i + * + ****************************************************************************/ + +int stm32_st7032init(const char *devpath); + +/**************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in initialization to setup + * USB-related GPIO pins for the STM32F4Discovery board. + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_OTGFS +void weak_function stm32_usbinitialize(void); +#endif + +/**************************************************************************** + * Name: stm32_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host + * functionality. This function will start a thread that will monitor for + * device connection/disconnection events. + * + ****************************************************************************/ + +#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) +int stm32_usbhost_initialize(void); +#endif + +/**************************************************************************** + * Name: stm32_pwm_setup + * + * Description: + * Initialize PWM and register the PWM device. + * + ****************************************************************************/ + +#ifdef CONFIG_PWM +int stm32_pwm_setup(void); +#endif + +/**************************************************************************** + * Name: stm32_capture_setup + * + * Description: + * Initialize pwm capture support + * + ****************************************************************************/ + +#ifdef CONFIG_CAPTURE +int stm32_capture_setup(FAR const char *devpath); +#endif + +/**************************************************************************** + * Name: stm32_can_setup + * + * Description: + * Initialize CAN and register the CAN device + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_CAN_CHARDRIVER +int stm32_can_setup(void); +#endif + +/**************************************************************************** + * 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 address 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_led_pminitialize + * + * Description: + * Enable logic to use the LEDs on the STM32F4Discovery to support power + * management testing + * + ****************************************************************************/ + +#ifdef CONFIG_PM +void stm32_led_pminitialize(void); +#endif + +/**************************************************************************** + * Name: stm32_pm_buttons + * + * Description: + * Configure the user button of the STM32f4discovery board as EXTI, + * so it is able to wakeup the MCU from the PM_STANDBY mode + * + ****************************************************************************/ + +#if defined(CONFIG_PM) && defined(CONFIG_ARCH_IDLE_CUSTOM) && \ + defined(CONFIG_PM_BUTTONS) +void stm32_pm_buttons(void); +#endif + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +#if !defined(CONFIG_DISABLE_MOUNTPOINT) && defined(CONFIG_STM32_SDIO) +int stm32_sdio_initialize(void); +#endif + +/**************************************************************************** + * Name: stm32_netinitialize + * + * Description: + * Configure board resources to support networking. + * + ****************************************************************************/ + +#ifdef HAVE_NETMONITOR +void weak_function stm32_netinitialize(void); +#endif + +/**************************************************************************** + * Name: stm32_zerocross_initialize + * + * Description: + * Initialize and register the zero cross driver + * + ****************************************************************************/ + +#ifdef CONFIG_SENSORS_ZEROCROSS +int stm32_zerocross_initialize(void); +#endif + +/**************************************************************************** + * Name: stm32_max31855initialize + * + * Description: + * Initialize and register the MAX31855 Temperature Sensor driver. + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/temp0" + * bus - Bus number (for hardware that has multiple SPI interfaces) + * devid - ID associated to the device. E.g., 0, 1, 2, etc. + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +#ifdef CONFIG_SENSORS_MAX31855 +int stm32_max31855initialize(const char *devpath, int bus, + uint16_t devid); +#endif + +/**************************************************************************** + * Name: stm32_mlx90614init + * + * Description: + * Called to configure an I2C and to register MLX90614 for the + * stm32f103-minimum board. + * + ****************************************************************************/ + +#ifdef CONFIG_SENSORS_MLX90614 +int stm32_mlx90614init(const char *devpath); +#endif + +/**************************************************************************** + * Name: stm32_max6675initialize + * + * Description: + * Initialize and register the max6675 driver + * + ****************************************************************************/ + +#ifdef CONFIG_SENSORS_MAX6675 +int stm32_max6675initialize(const char *devpath); +#endif + +/**************************************************************************** + * Name: stm32_cs43l22_initialize + * + * Description: + * This function is called by platform-specific, setup logic to configure + * and register the CS43L22 device. This function will register the + * driver as /dev/cs43l22[x] where x is determined by 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. + * + ****************************************************************************/ + +#ifdef HAVE_CS43L22 +int stm32_cs43l22_initialize(int minor); +#endif /* HAVE_CS43L22 */ + +/**************************************************************************** + * Name: stm32_pca9635_initialize + * + * Description: + * This function is called by board initialization logic to configure the + * LED PWM chip. This function will register the driver as /dev/leddrv0. + * + * Input Parameters: + * None + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +#ifdef CONFIG_PCA9635PW +int stm32_pca9635_initialize(void); +#endif + +/**************************************************************************** + * Name: stm32_rgbled_setup + * + * Description: + * This function is called by board initialization logic to configure the + * RGB LED driver. This function will register the driver as /dev/rgbled0. + * + * Input Parameters: + * None + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +#ifdef CONFIG_RGBLED +int stm32_rgbled_setup(void); +#endif + +/**************************************************************************** + * Name: stm32_timer_driver_setup + * + * Description: + * Configure the timer driver. + * + * Input Parameters: + * devpath - The full path to the timer device. This should be of the + * form /dev/timer0 + * timer - The timer's number. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned + * to indicate the nature of any failure. + * + ****************************************************************************/ + +#ifdef CONFIG_TIMER +int stm32_timer_driver_setup(const char *devpath, int timer); +#endif + +/**************************************************************************** + * Name: xen1210_archinitialize + * + * Description: + * Each board that supports an xen1210 device must provide this function. + * This function is called by application-specific, setup logic to + * configure the accelerometer device. This function will register the + * driver as /dev/accelN 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. + * + ****************************************************************************/ + +#ifdef CONFIG_SENSORS_XEN1210 +int xen1210_archinitialize(int minor); +#endif + +/**************************************************************************** + * Name: hciuart_dev_initialize + * + * Description: + * This function is called by board initialization logic to configure the + * Bluetooth HCI UART driver + * + * Input Parameters: + * None + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +#ifdef HAVE_HCIUART +int hciuart_dev_initialize(void); +#endif + +/**************************************************************************** + * Name: stm32_gs2200m_initialize + * + * Description: + * Configure the gs2200m driver. + * + * Input Parameters: + * devpath - The full path to the device. + * bus - The SPI bus number + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned + * to indicate the nature of any failure. + * + ****************************************************************************/ + +#ifdef CONFIG_WL_GS2200M +int stm32_gs2200m_initialize(const char *devpath, int bus); +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __BOARDS_ARM_STM32_STM32F4DISCOVERY_SRC_STM32F4DISCOVERY_H */ diff --git a/drivers/mtd/Kconfig b/drivers/mtd/Kconfig index a06f66d8c42..040110fcc74 100644 --- a/drivers/mtd/Kconfig +++ b/drivers/mtd/Kconfig @@ -726,6 +726,64 @@ config MX25RXX_LXX endif # MTD_MX25RXX + +config MTD_MT25QL + bool "SPI based MT25QL flash, defaulted to Extended SPI MODE" + default n + select SPI + ---help--- + SPI-based driver for MT5QL series flash memory +if MTD_MT25QL + +config MT25QL_SPIMODE + int "MT25QL SPI Mode" + default 0 + +config MT25QL_SPIFREQUENCY + int "MT25QL SPI Frequency" + default 20000000 + ---help--- + Max SPI speed of MT25QL flash can reach upto 133MHz. + Using 20MHz as a defautl for now. +config MT25QL_MANUFACTURER + hex "Mt25QL Manufacturer ID" + default 0x20 + ---help--- + The library also supports similar flash by other + manufacturers, 0x20 is the manufacturer ID for + MICRON MT25QLxx serial flash. + +config MT25QL_MEMORY_TYPE + hex "Memory type of the flash" + default 0xBA + ---help--- + The commonly used and availble flash memory of MT25Q + class is 3.3V identified by 0xBA. The library also + supports the low voltage class memmory from Micron + identified by 0xBB. + +config MT25QL_SUBSECTOR_ERASE + bool "Sub-Sector Erase" + default n + ---help--- + Some devices support a smaller erase size (4K vs 64K). + This option enables support for sub-sector erase. The + SMART file system can take advantage of this option if + it is enabled. + +config MT25QL_4_BYTE_MODE + bool "Enable 4-Byte addressing mode of operation" + default n + ---help--- + By default the flash memory is configured for 3 bytes address mode + of operation, but it can be reonfigured to use 4-byte addresses. + +config MT25QL_DEBUG + bool "Enable driver debug feature" + default n + +endif # MTD_MT25QL + config MTD_SMART bool "Sector Mapped Allocation for Really Tiny (SMART) Flash support" default n diff --git a/drivers/mtd/Make.defs b/drivers/mtd/Make.defs index 893d8d50350..c8c51faeea1 100644 --- a/drivers/mtd/Make.defs +++ b/drivers/mtd/Make.defs @@ -144,6 +144,10 @@ ifeq ($(CONFIG_MTD_IS25XP),y) CSRCS += is25xp.c endif +ifeq ($(CONFIG_MTD_MT25QL), y) +CSRCS += mt25ql.c +endif + ifeq ($(CONFIG_MTD_SMART),y) ifeq ($(CONFIG_FS_SMARTFS),y) CSRCS += smart.c diff --git a/drivers/mtd/mt25ql.c b/drivers/mtd/mt25ql.c new file mode 100644 index 00000000000..ee05a40d4d9 --- /dev/null +++ b/drivers/mtd/mt25ql.c @@ -0,0 +1,1316 @@ +/**************************************************************************** + * drivers/mtd/mt25ql.c + * +*/ + +/* Driver for SPI-based MT25QL (2Gbit, 1Gbit, 512Mbit, 256MBit, 64Mbit) FLASH + * (and compatible) + */ +/**************************************************************************** + * Included Files + ****************************************************************************/ +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#ifndef MT25QL_H_ +#define MT25QL_H_ + +#ifdef __cplusplus +extern "C" { +#endif + + +/*************************************************************************** + * Pre-Processor Definitions +****************************************************************************/ +#ifndef CONFIG_MT25QL_SPIMODE +#define CONFIG_MT25QL_SPIMODE SPIDEV_MODE0 +#endif + +#ifndef CONFIG_MT25QL_SPIFREQUENCY +#define CONFIG_MT25QL_SPIFREQUENCY 20000000 +#endif + +#ifndef CONFIG_MT25QL_MANUFACTURER +#define CONFIG_MT25QL_MANUFACTURER 0x20 +#endif + +#ifndef CONFIG_MT25QL_MEMORY_TYPE +#define CONFIG_MT25QL_MEMORY_TYPE +#endif + + +/* MT25QL Registers ********************************************************/ + +/* Identification Registers values */ + +#define MT25QL_MANFACTURER CONFIG_MT25QL_MANUFACTURER // Micron Manufactrer ID assigned by JEDEC +#define MT25QL_MEMORY_TYPE CONFIG_MT25QL_MEMORY_TYPE +#define MT25QL_CAPACITY_2GB 0x22 // 2Gb +#define MT25QL_CAPACITY_1GB 0x21 // 1Gb +#define MT25QL_CAPACITY_512 0x20 // 512Mb +#define MT25QL_CAPACITY_256 0x19 // 256Mb +#define MT25QL_CAPACITY_128 0x18 // 128Mb +#define MT25QL_CAPACITY_64 0x17 // 64Mb + +/* SPI Commands ***********************************************************/ + +/* Basic configration operations */ + +#define MT25QL_RSTEN 0x66 /* Reset Enable */ +#define MT25QL_RSTMEM 0x99 /* Reset Memory */ +#define MT25QL_WRTEN 0x06 /* Write Enable */ +#define MT25QL_WRTDIS 0x04 /* Write Disable */ + +#define MT25QL_E4BYTMD 0xB7 /* Enter 4-Byte Addressing Mode */ +#define MT25QL_X4BYTMD 0xE9 /* Exit 4-Byte Addressing Mode */ +#define MT25QL_EDEPPWRDWN 0xB9 /* Enter Deep Power Down */ +#define MT25QL_XDEPPWRDWN 0xAB /* Exit Deep Power Down */ + +#define MT25QL_PRGERSSUS 0x75 /* Program Erase Suspend Operation */ +#define MT25QL_PRGERRES 0x7A /* Program Erase Resume Operation */ + +#define MT25QL_UNLCKPWD 0x29 /* Unlock Password*/ + +/* Registers Read Operations */ + +#define MT25QL_RDDEVID 0x9E /* READ device id */ +#define MT25QL_RDSRFFLSPARAM 0x5A /* Read serial flash discovery parameter */ +#define MT25QL_RDSECTPRCT 0x2D /* Sector protection bits read */ +#define MT25QL_RDVOLLCKBIT 0xE8 /* Volatile lock bits read */ +#define MT25QL_RDNVOLLCKBIT 0xE2 /* Non-Volatile lock bits read */ +#define MT25QL_RDGBLFRZBIT 0xA7 /* Global Freeze bits read */ +#define MT25QL_RDPWD 0x27 /* Read password */ +#define MT25QL_RDOTPARRY 0x4B /* Read OTP Array*/ + +#define MT25QL_RDSTATREG 0x05 /* Read status register */ +#define MT25QL_RDFLGSTATREG 0x70 /* Read flag status register */ +#define MT25QL_RDNVOLCONREG 0xB5 /* Read Non-Volatile Configuration Register */ +#define MT25QL_RDVOLCONREG 0x85 /* Read Volatile Configuration Register */ +#define MT25QL_RDEVOLCONREG 0x65 /* Read Enchanced Configuration Register */ +#define MT25QL_RDEXTADDRREG 0xC8 /* Read Extended Address Register */ +#define MT25QL_RDGENPUPRDREG 0x96 /* Read General Purpose Read Register */ + + +/* Registers Write Operations */ + +#define MT25QL_WRTSTATREG 0x01 /* Write Status Register */ +#define MT25QL_WRTNVOLCONREG 0xB1 /* Write Non-Volatile Configuration Register */ +#define MT25QL_WRTVOLCONREG 0x81 /* Write Volatile Configuration Register */ +#define MT25QL_WRTENVOLCONREG 0x61 /* Write Enhanced Volatile Configuration Register */ +#define MT25QL_WRTEXTADDRREG 0xC5 /* Write Extended Address Register */ + +#define MT25QL_WRTSECTPRCT 0x2c /* Program sector protection register */ +#define MT25QL_WRTVOLLCKBIT 0xE5 /* Write Volatile Lock Bits */ +#define MT25QL_WRTNVOLLCKBIT 0xE3 /* Write Non-Volatile Lock Bits */ +#define MT25QL_WRTGBLFRZBIT 0xA6 /* Write Global Freeze Bits */ +#define MT25QL_WRTPWD 0x28 /* Write Password */ +#define MT25QL_WRTOTPARRY 0xE9 /* Program OTP Array */ + +/* Registers Erase Operations */ +#define MT25QL_CLRFLGSTATREG 0x50 /* Clear Flag Status Register */ +#define MT25QL_CHIPERASE 0xC4 /* Chip Erase, all sectors */ +#define MT25QL_ERSNVOLLCKBIT 0xE4 /* Eraser Non-Volatile Lock Bits */ + + +#ifdef CONFIG_MT25QL_4_BYTE_MODE +/* 4-Byte Read Commands */ +#define MT25QL_RD 0x13 /* Read Memory 4-Byte Addressing Mode */ +#define MT25QL_FSTRD 0x0C /* Fast Read Memory 4-Byte Addressing Mode */ +/* 4-Byte Program Commands */ +#define MT25QL_PRGPG 0x12 /* Page Program 4-Byte Addressing Mode */ +/* 4-Byte Erase Commands */ +#define MT25QL_SECTERS 0xDC /* 64-KB Sector Erase 4-Byte Addressing Mode */ +#define MT25QL_32KSUBSECTERS 0x5C /* 32-KB Sub-Sector Erase 4-Byte Addressing Mode */ +#define MT25QL_4KSUBSECTERS 0x21 /* 4-KB Sub-Sector Erase 4-Byte Addressing Mode */ +#else +/* 3-byte addressing mode commands*/ +/* 3-Byte Read Commands */ +#define MT25QL_RD 0x03 /* Read memory 3-byte addressing Mode */ +#define MT25QL_FSTRD 0x0B /* Fast Read Memory 3-Byte Addressing Mode */ +/* 3-Byte Program Commands */ +#define MT25QL_PRGPG 0x02 /* Page Program 3-Byte addressing Mode */ +/* 3-Byte Erase Commands */ +#define MT25QL_SECTERS 0xD8 /* 64-KB Sector Erase 3-Byte addressing Mode */ +#define MT25QL_32KSUBSECTERS 0x52 /* 32-KB Sub-Sector Erase 3-Byte addressing Mode */ +#define MT25QL_4KSUBSECTERS 0x20 /* 4-KB Sub-Sector Erase 3-Byte addressing Mode */ +#endif //MT25QL_4_BYTE_MODE + +/* 4-Byte Addressing Mode Commands */ +#define MT25QL_DUMMY 0xA5 + +/* Status Register Bit Definations [Default] */ +#define MT25QL_SRWEN (1 << 7) /* Bit 7: Write Enable -> 0 | Write Disable -> 1 [used with W# Line]*/ +#define MT25QL_SRTP (1 << 5) /* Bit 5: Block protection from TOP/BOT [TOP -> 0 | BOT -> 1]*/ +#define MT25QL_SRBP ((1<< 6) | (7 << 2)) /* Bit 6, 4:2 : Block Protection bits against PRG/ERS*/ +#define MT25QL_SRWENL (1 << 1) /* Bit 1: Write Enable latch [Write Disable -> 0 | Write_Enable -> 1]*/ +#define MT25QL_SRRDY (1 << 0) /* Bit 0: Ready -> 0 | Busy -> 1 */ + +/* Status Flag Register Bit Definations */ +#define MT25QL_SFRRDY (1 << 7) /* Bit 7: Ready / Not Busy */ +#define MT25QL_SFRERSUS (1 << 6) /* Bit 6: Erase Suspend Clear */ +#define MT25QL_SFRERSTAT (1 << 5) /* Bit 5: Erase Success */ +#define MT25QL_SFRPRGSTAT (1 << 4) /* Bit 4: Program / CRC check success */ +#define MT25QL_SFRPRGSUS (1 << 2) /* Bit 2: Program Suspend Clear */ +#define MT25QL_SFRPRCTTRIG (1 << 1) /* Bit 1: Block Protection Tigger Clear */ +#define MT25QL_SFRADDRMD (1 << 0) /* Bit 0: 4-Byte Addressing Mode Enabled [3-Byte Mode default]*/ + +/* MT25QL 64 capacity is 8,388,608 bytes: + * (128 sectors) * (65,536 bytes per sector) + * (32768 pages) * (256 bytes per page) + */ + +#define MT25QL64_SECTOR_SHIFT 16 /* Sector size 1 << 16 = 65,536 */ +#define MT25QL64_NSECTORS 128 +#define MT25QL64_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */ +#define MT25QL64_NPAGES 32768 +#define MT25QL64_SUBSECT_SHIFT 12 /* Sub-Sector size 1 << 12 = 4,096 */ + +/* MT25QL 128 capacity is 16,777,216 bytes: + * (256 sectors) * (65,536 bytes per sector) + * (65536 pages) * (256 bytes per page) + */ + +#define MT25QL128_SECTOR_SHIFT 16 /* Sector size 1 << 16 = 65,536 */ +#define MT25QL128_NSECTORS 256 +#define MT25QL128_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */ +#define MT25QL128_NPAGES 65536 +#define MT25QL128_SUBSECT_SHIFT 12 /* Sub-Sector size 1 << 12 = 4,096 */ + +/* MT25QL 256 capacity is 33,554,432 bytes: + * (512 sectors) * (65,536 bytes per sector) + * (131072 pages) * (256 bytes per page) + */ + +#define MT25QL256_SECTOR_SHIFT 16 /* Sector size 1 << 16 = 65,536 */ +#define MT25QL256_NSECTORS 512 +#define MT25QL256_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */ +#define MT25QL256_NPAGES 131072 +#define MT25QL256_SUBSECT_SHIFT 12 /* Sub-Sector size 1 << 12 = 4,096 */ + +/* MT25QL 512 capacity is 67,108,864 bytes: + * (1024 sectors) * (65,536 bytes per sector) + * (262144 pages) * (256 bytes per page) + */ + +#define MT25QL512_SECTOR_SHIFT 16 /* Sector size 1 << 16 = 65,536 */ +#define MT25QL512_NSECTORS 1024 +#define MT25QL512_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */ +#define MT25QL512_NPAGES 262144 +#define MT25QL512_SUBSECT_SHIFT 12 /* Sub-Sector size 1 << 12 = 4,096 */ + +/* MT25QL 1G capacity is 134,217,728 bytes: + * (2048 sectors) * (65,536 bytes per sector) + * (524288 pages) * (256 bytes per page) + */ + +#define MT25QL1G_SECTOR_SHIFT 16 /* Sector size 1 << 16 = 65,536 */ +#define MT25QL1G_NSECTORS 2048 +#define MT25QL1G_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */ +#define MT25QL1G_NPAGES 524288 +#define MT25QL1G_SUBSECT_SHIFT 12 /* Sub-Sector size 1 << 12 = 4,096 */ + +/* MT25QL 2G capacity is 268,435,436 bytes: + * (4096 sectors) * (65,536 bytes per sector) + * (1048576 pages) * (256 bytes per page) + */ + +#define MT25QL2G_SECTOR_SHIFT 16 /* Sector size 1 << 16 = 65,536 */ +#define MT25QL2G_NSECTORS 4096 +#define MT25QL2G_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */ +#define MT25QL2G_NPAGES 1048576 +#define MT25QL2G_SUBSECT_SHIFT 12 /* Sub-Sector size 1 << 12 = 4,096 */ +/*************************************************************************************** + * Private Types + * + * ************************************************************************************* +*/ + +/* This type represents the state of the MTD Device. The Struct mtd_dev_s + * must appear at the beginning of the defination so that switching between + * mtd_dev_s strutcture and mt25QL_dev_s stucture will be smooth. +*/ + +struct mt25ql_dev_s +{ + struct mtd_dev_s mtd; /* MTD Interface */ + FAR struct spi_dev_s *dev; /* saved SPI interface instance */ + uint8_t sectorshift; + uint8_t pageshift; /* log2 of the page size*/ + uint16_t nsectors; + uint32_t npages; /* Number of pages in the devices*/ + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + uint8_t subsectorshift; + #endif +}; + + +/*************************************************************************************** + * Private Function Prototpyes + * ************************************************************************************* +*/ + +/* Lock and per-transaction configuration */ +/* This function is used for locking the SPI lines when using the connected device + * used when multiple devices are connected on the same bus +*/ +static void mt25ql_lock(FAR struct spi_dev_s *dev); +static inline void mt25ql_unlock(FAR struct spi_dev_s *dev); /* used for unlocking the spi bus */ + +/* use this prototype to define write disable the flash */ +/* use this prototpye to write enable the flash */ + +/* Power Management Modules */ + + +/* mt25ql low level helpers */ + +static inline void mt25ql_resetenable(struct mt25ql_dev_s *priv); /* Enables software reset of memory */ +static inline void mt25ql_resetflash(struct mt25ql_dev_s *priv); /* Reset the specified flash memory */ +static void mt25ql_writeenable(struct mt25ql_dev_s *priv); /* Write enable for flash */ +// static void mt25ql_writedisable(struct mt25ql_dev_s * priv); /* Write disable for flash */ + +static inline int mt25ql_readid(struct mt25ql_dev_s *priv); /* Read device id */ + + +static uint8_t mt25ql_readsr(struct mt25ql_dev_s *priv); /* Read status register */ +static uint8_t mt25ql_readsrflag(struct mt25ql_dev_s *priv); /* Read the flag status register */ +// static uint8_t mt25ql_readnvconreg(struct mt25ql_dev_s *priv); /* Reads the non-volatile status register of flash */ +// static uint8_t mt25ql_readvconreg(struct mt25ql_dev_s *priv); /* Reads volatile status register of the flash */ + +// static void mt25ql_writesr(struct mt25ql_dev_s *priv, +// FAR const uint8_t val); /* write to the status register */ +// static uint8_t mt25ql_writenvconreg(struct mt25ql_dev_s *priv, +// FAR const uint8_t val); /* write to non-volatile status register */ +// static uint8_t mt25ql_writevconreg(struct mt25ql_dev_s *priv, +// FAR const uint8_t val); /* Write to volatile status register */ +// static uint8_t mt25ql_writeenvconreg(struct mt25ql_dev_s *priv, +// FAR const uint8_t val); /* Write to Enahanced status register */ +// static uint8_t mt25ql_writeextaddreg(struct mt25ql_dev_s *priv, +// FAR const uint8_t val); /* Write to extended status register*/ + +// static void mt25ql_clearsrflag(struct mt25ql_dev_s *priv); /* Clear the status register flag */ + +static void mt25ql_waitbusy(struct mt25ql_dev_s *priv); /* Wait while operation on flash is going on */ + +#ifdef CONFIG_MT25QL_4_BYTE_MODE +// static void mt25ql_enter4byteaddress(struct mt25ql_dev_s *priv); /* Change the address mode to 4-byte */ +// static void mt25ql_exit4byteaddress(struct mt25ql_dev_s *priv); /* Change the address mode to default */ +#endif //MT25QL_4_BYTE_MODE + +static inline int mt25ql_sectorerase(struct mt25ql_dev_s *priv, + off_t sector, + uint8_t type); /* Erase the sector from the specified offset */ +static inline int mt25ql_chiperase(struct mt25ql_dev_s *priv); /* Erase the full flash completely */ + +static inline int mt25ql_pagewrite(struct mt25ql_dev_s *priv, + FAR const uint8_t *buffer, + off_t page); /* write data to the flash memory */ +#ifdef CONFIG_MTD_BYTE_WRITE +static void mt25ql_bytewrite(struct mt25ql_dev_s *priv, + FAR const uint8_t *buffer, + off_t offset, uint16_t count); /* Write data to the flash in byte wise mode */ +#endif //MT25QL_BYTE_WRITE + +/* MTD Driver Methods */ + +static int mt25ql_erase(FAR struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks); +static ssize_t mt25ql_bread(FAR struct mtd_dev_s *dev, + off_t start_block, + size_t nblocks, + FAR uint8_t *buffer); +static ssize_t mt25ql_bwrite(FAR struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks, + const uint8_t *buffer); +static ssize_t mt25ql_read(FAR struct mtd_dev_s *dev, + off_t offset, size_t nbytes, + FAR uint8_t *buffer); +#ifdef CONFIG_MTD_BYTE_WRITE +static ssize_t mt25ql_write(FAR struct mtd_dev_s *dev, + off_t offset, + size_t nbytes, + FAR const uint8_t *buffer); +#endif //CONFIG_MTD_BYTE_WRITE + +static int mt25ql_ioctl(FAR struct mtd_dev_s *dev, + int cmd, unsigned long arg); + + +/****************************************************************************************** + * Private Functions + * **************************************************************************************** +*/ +/****************************************************************************************** + * Name: mt25ql_lock +*******************************************************************************************/ + +static void mt25ql_lock(FAR struct spi_dev_s * dev) +{ + /* On SPI buses where there are multiple devices, it will be necessary to + * lock SPI to have exclusive access to the buses for a sequence of + * transfers. The bus should be locked before the chip is selected. + * + * This is a blocking call and will not return until we have exclusive + * access to the SPI bus. We will retain that exclusive access until the + * bus is unlocked. + */ + + SPI_LOCK(dev, true); + + /* After locking the SPI bus, the we also need call the setfrequency, + * setbits, and setmode methods to make sure that the SPI is properly + * configured for the device. + * If the SPI bus is being shared, then it may have been left in an + * incompatible state. + */ + + SPI_SETMODE(dev, CONFIG_MT25QL_SPIMODE); + SPI_SETBITS(dev, 8); + SPI_HWFEATURES(dev, 0); + SPI_SETFREQUENCY(dev, CONFIG_MT25QL_SPIFREQUENCY); +} + +/**************************************************************************** + * Name: mt25ql_unlock + ****************************************************************************/ + +static inline void mt25ql_unlock(FAR struct spi_dev_s *dev) +{ + SPI_LOCK(dev, false); +} + + +/**************************************************************************** + * Name: mt25ql_resetenable + ****************************************************************************/ +static inline void mt25ql_resetenable(struct mt25ql_dev_s *priv) +{ + /* Select the flash*/ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + nxsig_usleep(20); + /* Send reset enable command */ + SPI_SEND(priv->dev, MT25QL_RSTEN); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + nxsig_usleep(1000); + finfo("Reset Enabled\n"); + return; +} + + +/**************************************************************************** + * Name: mt25ql_resetflash + ****************************************************************************/ +static inline void mt25ql_resetflash(struct mt25ql_dev_s *priv) +{ + /* lock the spi bus */ + mt25ql_lock(priv->dev); + mt25ql_resetenable(priv); /* enabling software reset of flash */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + SPI_SEND(priv->dev, MT25QL_RSTMEM); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + nxsig_usleep(2000); + mt25ql_unlock(priv->dev); + finfo("Reset Done\n"); + return; +} + + +/**************************************************************************** + * Name: mt25ql_writeenable + ****************************************************************************/ +static void mt25ql_writeenable(struct mt25ql_dev_s *priv) +{ + /* spi bus should be locked by caller*/ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + SPI_SEND(priv->dev, MT25QL_WRTEN); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + nxsig_usleep(1000); + finfo("Enabled\n"); +} + +/**************************************************************************** + * Name: mt25ql_writedisable + ****************************************************************************/ + + +// static void mt25ql_writedisable(struct mt25ql_dev_s *priv) +// { +// /* spi bus should be locked by caller*/ +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); +// SPI_SEND(priv->dev, MT25QL_WRTDIS); +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); +// nxsig_usleep(1000); +// finfo("Disabled\n"); +// } + + +/**************************************************************************** + * Name: mt25ql_rdid + ****************************************************************************/ + +static inline int mt25ql_readid(FAR struct mt25ql_dev_s *priv) +{ + uint8_t manufacturer; + uint8_t memory; + uint8_t capacity; + uint8_t devid[20]; + + finfo("priv: %p\n", priv); + + /** + * configurng the bus, selecting the flash device. (caller needs to have already + * locked the bus for exclusive access) + * + */ + mt25ql_lock(priv->dev); + + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + + /** + * send the read id command and read 20 bytes id info from the flash + */ + + SPI_SEND(priv->dev, MT25QL_RDDEVID); // sending the command + // SPI_RECVBLOCK(priv->dev, devid, 20); + manufacturer= SPI_SEND(priv->dev, MT25QL_DUMMY); + memory = SPI_SEND(priv->dev, MT25QL_DUMMY); + capacity = SPI_SEND(priv->dev, MT25QL_DUMMY); + + /* deselecting the flash */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + mt25ql_unlock(priv->dev); + + // finfo("Read ID: "); + // for(int i=0; i<20; i++){ + // finfo("%02x ", devid[i]); + // } + // finfo("\n"); + // manufacturer = devid[0]; + // memory = devid[1]; + // capacity = devid[2]; + + /* checking for id validation */ + if(manufacturer == MT25QL_MANFACTURER && memory == MT25QL_MEMORY_TYPE) + { + /* checknig if the connected falsh memory is valid */ + + /* checking for the understandable flash capacity*/ + switch(capacity) + { + case MT25QL_CAPACITY_2GB: + /* save the flash geometry for the 2Gbit flash */ + priv->sectorshift = MT25QL2G_SECTOR_SHIFT; + priv->pageshift = MT25QL2G_PAGE_SHIFT; + priv->nsectors = MT25QL2G_NSECTORS; + priv->npages = MT25QL2G_NPAGES; + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + priv->subsectorshift = MT25QL2G_SUBSECT_SHIFT; + #endif //CONFIG_MT25QL_SUBSECTOR_ERASE + return OK; + + case MT25QL_CAPACITY_1GB: + /* save the flash geometry for 1Gbit flash */ + priv->sectorshift = MT25QL1G_SECTOR_SHIFT; + priv->pageshift = MT25QL1G_PAGE_SHIFT; + priv->nsectors = MT25QL1G_NSECTORS; + priv->npages = MT25QL1G_NPAGES; + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + priv->subsectorshift = MT25QL1G_SUBSECT_SHIFT; + #endif //CONFIG_MT25QL_SUBSECTOR_ERASE + return OK; + case MT25QL_CAPACITY_512: + /* save the flash geometry for 512Mbit flash */ + priv->sectorshift = MT25QL512_SECTOR_SHIFT; + priv->pageshift = MT25QL512_PAGE_SHIFT; + priv->nsectors = MT25QL512_NSECTORS; + priv->npages = MT25QL512_NPAGES; + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + priv->subsectorshift = MT25QL512_SUBSECT_SHIFT; + #endif //CONFIG_MT25QL_SUBSECTOR_ERASE + return OK; + case MT25QL_CAPACITY_256: + /* save the flash geometry for 256Mbit flash */ + priv->sectorshift = MT25QL256_SECTOR_SHIFT; + priv->pageshift = MT25QL256_PAGE_SHIFT; + priv->nsectors = MT25QL256_NSECTORS; + priv->npages = MT25QL256_NPAGES; + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + priv->subsectorshift = MT25QL256_SUBSECT_SHIFT; + #endif //CONFIG_MT25QL_SUBSECTOR_ERASE + return OK; + case MT25QL_CAPACITY_128: + /* save the flash geometry for 128Mbit flash */ + priv->sectorshift = MT25QL128_SECTOR_SHIFT; + priv->pageshift = MT25QL128_PAGE_SHIFT; + priv->nsectors = MT25QL128_NSECTORS; + priv->npages = MT25QL128_NPAGES; + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + priv->subsectorshift = MT25QL128_SUBSECT_SHIFT; + #endif //CONFIG_MT25QL_SUBSECTOR_ERASE + return OK; + case MT25QL_CAPACITY_64: + /* save the flash geometry for 64Mbit flash */ + priv->sectorshift = MT25QL64_SECTOR_SHIFT; + priv->pageshift = MT25QL64_PAGE_SHIFT; + priv->nsectors = MT25QL64_NSECTORS; + priv->npages = MT25QL64_NPAGES; + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + priv->subsectorshift = MT25QL64_SUBSECT_SHIFT; + #endif //CONFIG_MT25QL_SUBSECTOR_ERASE + return OK; + default: + return -ENODEV; + + } + } + return -ENODEV; +} + +/**************************************************************************** + * Name: mt25ql_readsr + ****************************************************************************/ +static uint8_t mt25ql_readsr(struct mt25ql_dev_s *priv) +{ + uint8_t status_byte; + /* caller should lock the spi bus */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + SPI_SEND(priv->dev, MT25QL_RDSTATREG); + status_byte = SPI_SEND(priv->dev, MT25QL_DUMMY); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + finfo("status: %02x", status_byte); + return status_byte; +} + +/**************************************************************************** + * Name: mt25ql_readsrflag + ****************************************************************************/ +static uint8_t mt25ql_readsrflag(struct mt25ql_dev_s *priv) +{ + uint8_t status_flag_byte; + /* caller needs to lock the spi bus */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + SPI_SEND(priv->dev, MT25QL_RDFLGSTATREG); + status_flag_byte=SPI_SEND(priv->dev, MT25QL_DUMMY); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + finfo("status flag: %02x\n", status_flag_byte); + return status_flag_byte; +} + +/**************************************************************************** + * Name: mt25ql_readnvconreg + ****************************************************************************/ +// static uint8_t mt25ql_readnvconreg(struct mt25ql_dev_s *priv) +// { +// uint8_t nvconreg_byte; +// /* caller needs to lock the spi bus */ +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); +// SPI_SEND(priv->dev, MT25QL_RDNVOLCONREG); +// nvconreg_byte=SPI_SEND(priv->dev, MT25QL_DUMMY); +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); +// finfo("NV Con reg: %02x\n", nvconreg_byte); +// return nvconreg_byte; +// } +/**************************************************************************** + * Name: mt25ql_readvconreg + ****************************************************************************/ +// static uint8_t mt25ql_readvconreg(struct mt25ql_dev_s *priv) +// { +// uint8_t vconreg_byte; +// /* caller needs to lock the spi bus */ +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); +// SPI_SEND(priv->dev, MT25QL_RDVOLCONREG); +// vconreg_byte=SPI_SEND(priv->dev, MT25QL_DUMMY); +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); +// finfo("V Con reg: %02x\n", vconreg_byte); +// return vconreg_byte; +// } + +/**************************************************************************** + * Name: mt25ql_writesr + ****************************************************************************/ +// static void mt25ql_writesr(struct mt25ql_dev_s *priv, +// FAR const uint8_t val) +// { +// /* caller needs to lock the spi bus */ +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); +// SPI_SEND(priv->dev, MT25QL_WRTSTATREG); +// SPI_SEND(priv->dev, val); +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); +// finfo("Stats reg updated"); +// return; +// } + + +/**************************************************************************** + * Name: mt25ql_clearsrflag + ****************************************************************************/ +// static void mt25ql_clearsrflag(struct mt25ql_dev_s *priv) +// { +// /* caller needs to lock the spi flag */ +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0),true); +// SPI_SEND(priv->dev, MT25QL_CLRFLGSTATREG); +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); +// finfo("Status Flag Cleared\n"); +// return; +// } + + +/**************************************************************************** + * Name: mt25ql_waitbusy + ****************************************************************************/ +static void mt25ql_waitbusy(struct mt25ql_dev_s *priv) +{ + uint8_t status; + + /* caller need to lock the SPI bus */ + do { + status = mt25ql_readsr(priv); + + if((status & MT25QL_SRRDY)!= 0) + { + mt25ql_unlock(priv->dev); + nxsig_usleep(1000); // free up spi bus for other processes + mt25ql_lock(priv->dev); + } + } + while ((status & MT25QL_SRRDY) != 0); + + finfo("Complete\n"); + return; +} + +#ifdef CONFIG_MT25QL_4_BYTE_MODE +/**************************************************************************** + * Name: mt25ql_enter4byteaddress + ****************************************************************************/ +// static void mt25ql_enter4byteaddress(struct mt25ql_dev_s *priv) +// { +// /* caller needs to lock the SPI Bus */ +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); +// SPI_SEND(priv->dev, MT25QL_E4BYTMD); +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); +// finfo("4-Byte Entered\n"); +// } + +/**************************************************************************** + * Name: mt25ql_exit4byteaddress + ****************************************************************************/ +// static void mt25ql_exit4byteaddress(struct mt25ql_dev_s *priv) +// { +// /* caller needs to lock the SPI Bus */ +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); +// SPI_SEND(priv->dev, MT25QL_X4BYTMD); +// SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); +// finfo("4-Byte Exited\n"); +// } +#endif + + +/**************************************************************************** + * Name: mt25ql_sectorerase + ****************************************************************************/ +static inline int mt25ql_sectorerase(struct mt25ql_dev_s *priv, + off_t sector, + uint8_t type) +{ + /* caller needs to lock the flash */ + off_t offset; + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + if (priv->subsectorshift > 0) + { + offset = sector << priv->subsectorshift; + } + else + #endif //CONFIG_MT25QL_SUBSECTOR_ERASE + { + offset = sector << priv->sectorshift; + } + finfo("sector: %08lx\n", (long)sector); + + /* Wait for preceding operations to complete */ + mt25ql_waitbusy(priv); + + /* Send write enable command */ + mt25ql_writeenable(priv); + + /* Select this FLASH part */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + + SPI_SEND(priv->dev, type); + #ifdef CONFIG_MT25QL_4_BYTE_MODE + /* if 4 byte mode send one additional byte*/ + SPI_SEND(priv->dev, (offset >> 24) & 0xFF); + #endif + SPI_SEND(priv->dev, (offset >> 16) & 0xFF); + SPI_SEND(priv->dev, (offset >> 8) & 0xFF); + SPI_SEND(priv->dev, offset & 0xFF); + /* Deselect the FLASH */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + /* wait for erase to complete */ + mt25ql_waitbusy(priv); + finfo("Erased\n"); + return 1; +} + +/**************************************************************************** + * Name: mt25ql_chiperase + ****************************************************************************/ +static inline int mt25ql_chiperase(struct mt25ql_dev_s *priv) +{ + uint8_t status_flag; + uint8_t status; + finfo("priv: %p\n", priv); + + mt25ql_waitbusy(priv); + + mt25ql_writeenable(priv); + + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + + /* Send the "Chip Erase (CE)" command */ + SPI_SEND(priv->dev, MT25QL_CHIPERASE); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + + /* read the status flag to check for Erase Operation staus */ + status_flag = mt25ql_readsrflag(priv); + if((status_flag & MT25QL_SFRERSTAT) != 0) + { + finfo("Erase Failed\n"); + return 0; + } else + { + finfo("Erasing\n"); + do + { + mt25ql_lock(priv->dev); + status =mt25ql_readsr(priv) ; + if((status & MT25QL_SRRDY) != 0) + { + mt25ql_unlock(priv->dev); + } + }while((status &MT25QL_SRRDY)!= 0); + mt25ql_unlock(priv->dev); + finfo("Erased\n"); + return OK; + } +} + +/**************************************************************************** + * Name: mt25ql_pagewrite + ****************************************************************************/ +static inline int mt25ql_pagewrite(struct mt25ql_dev_s *priv, + FAR const uint8_t *buffer, + off_t page) +{ + /* caller needs to lock the flash */ + off_t offset = page << priv->pageshift; + + finfo("page: %08lx Address: %08lx\n", (long)page, (long)offset); + + mt25ql_waitbusy(priv); + + mt25ql_writeenable(priv); + + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + SPI_SEND(priv->dev, MT25QL_PRGPG); + + /* sending the address */ + #ifdef CONFIG_MT25QL_4_BYTE_MODE + /* if 4-Byte mode send one additional byte */ + SPI_SEND(priv->dev, (offset >> 24) &0xFF); + #endif + SPI_SEND(priv->dev, (offset >> 16) &0xFF); + SPI_SEND(priv->dev, (offset >> 8) & 0xFF); + SPI_SEND(priv->dev, offset & 0xff); + + /* Sending the specified no of bytes*/ + SPI_SNDBLOCK(priv->dev, buffer, 1<pageshift); + + /* Deselect the FLASH: CS high */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + finfo("written\n"); + return OK; +} + + +/**************************************************************************** + * Name: mt25ql_bytewrite + ****************************************************************************/ + +#ifdef CONFIG_MTD_BYTE_WRITE +static void mt25ql_bytewrite(struct mt25ql_dev_s *priv, + FAR const uint8_t *buffer, + off_t offset, uint16_t count) +{ + finfo("offset: %08lx count:%d\n", (long)offset, count); + + /* Wait for any preceding operations to complete. + * + */ + mt25ql_waitbusy(priv); + + /* Enable write access to flash memory */ + mt25ql_writeenable(priv); + + /* Select this flash part */ + + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + + /* send "page program" command */ + SPI_SEND(priv->dev, MT25QL_PRGPG); + + /* Send the page offset high byte */ + #ifdef CONFIG_MT25QL_4_BYTE_MODE + SPI_SEND(priv->dev, (offset >>24) & 0xff); + #endif + SPI_SEND(priv->dev, (offset>>16) & 0xff); + SPI_SEND(priv->dev, (offset>>8) & 0xff); + SPI_SEND(priv->dev, offset & 0xff); + + /* Then write the data byte*/ + SPI_SNDBLOCK(priv->dev, buffer, count); + + /* Deselect the FLASH: CS high */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + finfo("Written\n"); +} +#endif + + +/**************************************************************************** + * Name: mt25ql_erase + ****************************************************************************/ + +static int mt25ql_erase(FAR struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks) +{ + FAR struct mt25ql_dev_s *priv = (FAR struct mt25ql_dev_s *)dev; + size_t blocksleft = nblocks; + + finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + /*locking the access to the SPI bus until operation completes */ + mt25ql_lock(priv->dev); + while (blocksleft > 0) + { + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + size_t sectorboundary; + size_t blkper; + + /** + * Find as many full sector erase blocks as possible to increase + * operation speed in case of smaller erase sizes. + */ + if(priv->subsectorshift > 0) + { + blkper = 1 << (priv->sectorshift - priv->subsectorshift); + sectorboundary = (startblock + blkper -1) / blkper; + sectorboundary *= blkper; + + /** + * if we are on the sector boundary and have at least a + * full sector of blocks left to erase, then we can do + * a full sector erase. + */ + + if(startblock == sectorboundary && blocksleft >= blkper) + { + /* Do a full sector erase */ + + mt25ql_sectorerase(priv, startblock, MT25QL_SECTERS); + startblock += blkper; + blocksleft -= blkper; + continue; + } + else + { + /* Just do a sub-sector erase */ + + mt25ql_sectorerase(priv, startblock, MT25QL_4KSUBSECTERS); + startblock++; + blocksleft--; + continue; + } + } + #endif + + /* not using sub-sector erase. Erase each full sector*/ + mt25ql_sectorerase(priv, startblock, MT25QL_SECTERS); + startblock++; + blocksleft--; + + } + mt25ql_unlock(priv->dev); + return (int)nblocks; +} + +/**************************************************************************** + * Name: mt25ql_bread + ****************************************************************************/ + +static ssize_t mt25ql_bread(FAR struct mtd_dev_s *dev, + off_t start_block, + size_t nblocks, + FAR uint8_t *buffer) +{ + FAR struct mt25ql_dev_s *priv = (FAR struct mt25ql_dev_s *)dev; + ssize_t nbytes; + finfo("startblock: %08lx nblocks:%d\n", (long)start_block, (int)nblocks); + + /** + * On this device, we can handle the block read just like byte-oriented + * read + */ + + nbytes = mt25ql_read(dev, start_block << priv->pageshift, + nblocks << priv->pageshift, buffer); + if(nbytes > 0) + { + return nbytes >> priv->pageshift; + } + + return (int)nbytes; +} + +/**************************************************************************** + * Name: mt25ql_bwrite + ****************************************************************************/ + +static ssize_t mt25ql_bwrite(FAR struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks, + const uint8_t *buffer) +{ + FAR struct mt25ql_dev_s *priv = (FAR struct mt25ql_dev_s *)dev; + size_t blocksleft= nblocks; + size_t pagesize = 1 << priv->pageshift; + + finfo("start block: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + /* Lock the spi bus and write each page to FLASH */ + + mt25ql_lock(priv->dev); + while(blocksleft-->0) + { + mt25ql_pagewrite(priv, buffer, startblock); + buffer += pagesize; + startblock++; + } + + mt25ql_unlock(priv->dev); + return nblocks; +} + +/**************************************************************************** + * Name: mt25ql_read + ****************************************************************************/ +static ssize_t mt25ql_read(FAR struct mtd_dev_s *dev, + off_t offset, + size_t nbytes, + FAR uint8_t *buffer) +{ + FAR struct mt25ql_dev_s *priv = (FAR struct mt25ql_dev_s *)dev; + finfo ("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + + /** + * Lock the SPI bus NOW because the following call must be executed + * with the bus locked. + */ + + mt25ql_lock(priv->dev); + + /** + * wait for any preceding operations to complete. + */ + + mt25ql_waitbusy(priv); + + /* Select this Flash part */ + + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); + + /* Send "Read from Memory" instruction */ + + SPI_SEND(priv->dev, MT25QL_RD); + + /* Send the page offset high byte (address)*/ + + #ifdef CONFIG_MT25QL_4_BYTE_MODE + SPI_SEND(priv->dev, (offset>>24) &0xff); + #endif + SPI_SEND(priv->dev, (offset>>16) & 0xff); + SPI_SEND(priv->dev, (offset>>8) & 0xff); + SPI_SEND(priv->dev, offset & 0xff); + + /* Then read all of the requested bytes */ + + SPI_RECVBLOCK(priv->dev, buffer, nbytes); + + /* Deselect the FLASH and unlock the SPI bus */ + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + + mt25ql_unlock(priv->dev); + + finfo("return nbytes: %d\n", (int)nbytes); + return nbytes; +} + +/**************************************************************************** + * Name: mt25ql_write + ****************************************************************************/ +#ifdef CONFIG_MTD_BYTE_WRITE +static ssize_t mt25ql_write(FAR struct mtd_dev_s *dev, + off_t offset, + size_t nbytes, + FAR const uint8_t *buffer) +{ + FAR struct mt25ql_dev_s *priv = (FAR struct mt25ql_dev_s *)dev; + int startpage; + int endpage; + int count; + int index; + int pagesize; + int bytestowrite; + + finfo(" offset: %08lx nbytes: %d\n", (long) offset, (int)nbytes); + + /** + * we need to ensure count + offset does not cross one or more pages + * and perform individual writes. The device can only write in page + * increments. + */ + + startpage = offset / (1<< priv->pageshift); + endpage = (offset + nbytes) / (1<< priv->pageshift); + + mt25ql_lock(priv->dev); + if(startpage == endpage) + { + /* all bytes within one programmable page, just write*/ + mt25ql_bytewrite(priv, buffer, offset, nbytes); + } + else + { + /* write 1st partial page */ + count = nbytes; + pagesize = (1 << priv->pageshift); + bytestowrite = pagesize - (offset & (pagesize -1)); + mt25ql_bytewrite(priv, buffer, offset, bytestowrite); + + /* Update offset and count */ + + offset += bytestowrite; + count -= bytestowrite; + index = bytestowrite; + + /* Writing full pages */ + while (count >= pagesize) + { + mt25ql_bytewrite(priv, &buffer[index], offset, pagesize); + + /* Update offset and count */ + + offset += pagesize; + count -= pagesize; + index += pagesize; + + } + + /* Now write any partial page at the end */ + if (count >0) + { + mt25ql_bytewrite(priv, &buffer[index], offset, count); + } + } + + mt25ql_unlock(priv->dev); + return nbytes; +} +#endif + +/**************************************************************************** + * Name: m25p_ioctl + ****************************************************************************/ + + +static int mt25ql_ioctl(FAR struct mtd_dev_s *dev, + int cmd, unsigned long arg) +{ + FAR struct mt25ql_dev_s *priv = (FAR struct mt25ql_dev_s *)dev; + + int ret = -EINVAL; /* Assume good command with bad parameters */ + + finfo("cmd: %d\n", cmd); + + switch(cmd) + { + case MTDIOC_GEOMETRY: + { + FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *) + ((uintptr_t)arg); + if(geo) + { + /** + * Populate the geometry structure with information + * need to know the capacity and how to access the + * device. + * + * NOTE: + * That the device is treated as though it where just + * as array of fixed size blocks. + * That is most likely not true, but the client will + * expect the device logic to do whatever is necessary + * to make it appear so. + */ + + geo->blocksize = (1 << priv->pageshift); + #ifdef CONFIG_MT25QL_SUBSECTOR_ERASE + if (priv->subsectorshift > 0) + { + geo->erasesize = (1 << priv->subsectorshift); + geo->neraseblocks = priv->nsectors * + (1 << (priv->sectorshift - + priv->subsectorshift)); + } + else + #endif + { + geo->erasesize = (1 << priv->sectorshift); + geo->neraseblocks = priv->nsectors; + } + ret = OK; + + finfo("blocksize: %" PRId32 " erasesize: %" PRId32 + " neraseblocks: %" PRId32 "\n", + geo->blocksize, geo->erasesize, geo->neraseblocks); + } + } + break; + case BIOC_PARTINFO: + { + FAR struct partition_info_s *info = + (FAR struct partition_info_s *)arg; + if (info != NULL) + { + info->numsectors = priv->nsectors << + (priv->sectorshift - priv->pageshift); + info->sectorsize = 1 << priv->pageshift; + info->startsector = 0; + info->parent[0] = '\0'; + ret = OK; + } + } + break; + + case MTDIOC_BULKERASE: + { + /* Erase the entire device */ + + mt25ql_lock(priv->dev); + ret = mt25ql_chiperase(priv); + mt25ql_unlock(priv->dev); + } + break; + + default: + ret = -ENOTTY; /* Bad command */ + break; + + } + finfo("return %d\n", ret); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: m25p_initialize + * + * Description: + * Create an initialize MTD device instance. + * MTD devices are not registered in the file system, but are created as + * instances that can be bound to other functions (such as a block or + * character driver front end). + * + ****************************************************************************/ + +FAR struct mtd_dev_s *mt25ql_initialize(FAR struct spi_dev_s *dev) +{ + FAR struct mt25ql_dev_s *priv; + int ret; + + finfo("dev: %p\n", dev); + + /* Allocate a state structure (we allocate the structure instead of using + * a fixed, static allocation so that we can handle multiple FLASH devices. + * The current implementation would handle only one FLASH part per SPI + * device (only because of the SPIDEV_FLASH(0) definition) and so would + * have to be extended to handle multiple FLASH parts on the same SPI bus. + */ + + priv = (FAR struct mt25ql_dev_s *)kmm_zalloc(sizeof(struct mt25ql_dev_s)); + if (priv) + { + /* Initialize the allocated structure. (unsupported methods were + * nullified by kmm_zalloc). + */ + + priv->mtd.erase = mt25ql_erase; + priv->mtd.bread = mt25ql_bread; + priv->mtd.bwrite = mt25ql_bwrite; + priv->mtd.read = mt25ql_read; +#ifdef CONFIG_MTD_BYTE_WRITE + priv->mtd.write = mt25ql_write; +#endif + priv->mtd.ioctl = mt25ql_ioctl; + priv->mtd.name = "mt25ql"; + priv->dev = dev; + + /* Deselect the FLASH */ + + SPI_SELECT(dev, SPIDEV_FLASH(0), false); + + /* Identify the FLASH chip and get its capacity */ + + ret = mt25ql_readid(priv); + if (ret != OK) + { + /* Unrecognized! + * Discard all of that work we just did and return NULL + */ + + ferr("ERROR: Unrecognized\n"); + kmm_free(priv); + return NULL; + } + } + + /* Return the implementation-specific state structure as the MTD device */ + + finfo("Return %p\n", priv); + return (FAR struct mtd_dev_s *)priv; +} +#ifdef __cplusplus + } +#endif +#endif //MT25QL_H_ diff --git a/include/nuttx/mtd/mtd.h b/include/nuttx/mtd/mtd.h index 3039bf950a0..22fcd7f4a0a 100644 --- a/include/nuttx/mtd/mtd.h +++ b/include/nuttx/mtd/mtd.h @@ -444,6 +444,16 @@ FAR struct mtd_dev_s *mx35_initialize(FAR struct spi_dev_s *dev); FAR struct mtd_dev_s *rammtd_initialize(FAR uint8_t *start, size_t size); +/**************************************************************************** + * Name: mt25ql_initialize + * + * Description: + * Initializes the for SPI-based MT25QL (1Gbit, 2Gbit, 512MBit). + * + ****************************************************************************/ + +FAR struct mtd_dev_s *mt25ql_initialize(FAR struct spi_dev_s *dev); + /**************************************************************************** * Name: ramtron_initialize *