diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index acfac81aa0..4fcaa756f2 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -138,6 +138,7 @@ config STM32_STM32F10XX config STM32_VALUELINE bool + select ARMV7M_CMNVECTOR config STM32_HIGHDENSITY bool diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h index a95d13100e..fa0969601f 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h @@ -59,6 +59,7 @@ #define STM32_AFIO_EXTICR2_OFFSET 0x000c /* External interrupt configuration register 2 */ #define STM32_AFIO_EXTICR3_OFFSET 0x0010 /* External interrupt configuration register 3 */ #define STM32_AFIO_EXTICR4_OFFSET 0x0014 /* External interrupt configuration register 4 */ +#define STM32_AFIO_MAPR2_OFFSET 0x001c /* AF remap and debug I/O configuration register 2 */ /* Register Addresses ***************************************************************/ @@ -373,5 +374,27 @@ #define AFIO_EXTICR4_EXTI15_SHIFT (12) /* Bits 15-12: EXTI 15 configuration */ #define AFIO_EXTICR4_EXTI15_MASK (AFIO_EXTICR_PORT_MASK << AFIO_EXTICR4_EXTI15_SHIFT) +/* AF remap and debug I/O configuration register 2 */ + +#ifdef CONFIG_STM32_VALUELINE +# define AFIO_MAPR2_TIM15_REMAP (1 << 0) /* Bit 0: TIM15 remapping */ +# define AFIO_MAPR2_TIM16_REMAP (1 << 1) /* Bit 1: TIM16 remapping */ +# define AFIO_MAPR2_TIM17_REMAP (1 << 2) /* Bit 2: TIM17 remapping */ +# define AFIO_MAPR2_CEC_REMAP (1 << 3) /* Bit 3: CEC remapping */ +# define AFIO_MAPR2_TIM1_DMA_REMAP (1 << 4) /* Bit 4: TIM1 DMA remapping */ +#else +# define AFIO_MAPR2_TIM9_REMAP (1 << 5) /* Bit 5: TIM9 remapping */ +# define AFIO_MAPR2_TIM10_REMAP (1 << 6) /* Bit 6: TIM10 remapping */ +# define AFIO_MAPR2_TIM11_REMAP (1 << 7) /* Bit 7: TIM11 remapping */ +#endif +#define AFIO_MAPR2_TIM13_REMAP (1 << 8) /* Bit 8: TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP (1 << 9) /* Bit 9: TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV (1 << 10) /* Bit 10: NADV connect/disconnect */ +#ifdef CONFIG_STM32_VALUELINE +# define AFIO_MAPR2_TIM76_DAC_DMA_REMAP (1 << 11) /* Bit 11: TIM67_DAC DMA remapping */ +# define AFIO_MAPR2_TIM12_REMAP (1 << 12) /* Bit 12: TIM12 remapping */ +# define AFIO_MAPR2_MISC_REMAP (1 << 13) /* Bit 13: Miscellaneous features remapping */ +#endif + #endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F10XXX_GPIO_H */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h index e38414f311..a1d2e26d30 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h @@ -60,14 +60,9 @@ #define STM32_TIM5_BASE 0x40000c00 /* 0x40000c00 - 0x40000fff: TIM5 timer */ #define STM32_TIM6_BASE 0x40001000 /* 0x40001000 - 0x400013ff: TIM6 timer */ #define STM32_TIM7_BASE 0x40001400 /* 0x40001400 - 0x400007ff: TIM7 timer */ -#if defined(CONFIG_STM32_VALUELINE) -# 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 */ - /* 0x40002400 - 0x400027ff: Reserved */ -#else - /* 0x40001800 - 0x40027fff: Reserved */ -#endif +#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 */ #define STM32_WWDG_BASE 0x40002c00 /* 0x40002C00 - 0x40002fff: Window watchdog (WWDG) */ #define STM32_IWDG_BASE 0x40003000 /* 0x40003000 - 0x400033ff: Independent watchdog (IWDG) */ @@ -90,13 +85,8 @@ #define STM32_BKP_BASE 0x40006c00 /* 0x40006c00 - 0x40006fff: Backup registers (BKP) */ #define STM32_PWR_BASE 0x40007000 /* 0x40007000 - 0x400073ff: Power control PWR */ #define STM32_DAC_BASE 0x40007400 /* 0x40007400 - 0x400077ff: DAC */ -#if defined(CONFIG_STM32_VALUELINE) -# define STM32_CEC_BASE 0x40007800 /* 0x40007800 - 0x40007bff: CEC */ +#define STM32_CEC_BASE 0x40007800 /* 0x40007800 - 0x40007bff: CEC */ /* 0x40007c00 - 0x4000ffff: Reserved */ -#else - /* 0x40007800 - 0x4000ffff: Reserved */ -#endif - /* APB2 bus */ #define STM32_AFIO_BASE 0x40010000 /* 0x40010000 - 0x400103ff: AFIO */ @@ -115,15 +105,11 @@ #define STM32_TIM8_BASE 0x40013400 /* 0x40013400 - 0x400137ff: TIM8 timer */ #define STM32_USART1_BASE 0x40013800 /* 0x40013800 - 0x40013bff: USART1 */ #define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013c00: ADC3 */ -#if defined(CONFIG_STM32_VALUELINE) /* 0x40013c00 - 0x40013fff: Reserved */ -# define STM32_TIM15_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM15 */ -# define STM32_TIM16_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM16 */ -# define STM32_TIM17_BASE 0x40014800 /* 0x40014800 - 0x40014bff: TIM17 */ +#define STM32_TIM15_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM15 */ +#define STM32_TIM16_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM16 */ +#define STM32_TIM17_BASE 0x40014800 /* 0x40014800 - 0x40014bff: TIM17 */ /* 0x40014c00 - 0x4001ffff: Reserved */ -#else - /* 0x40013c00 - 0x4001ffff: Reserved */ -#endif /* AHB bus */ diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h index 60365b9218..1a792b7ebc 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h @@ -163,7 +163,9 @@ # define RCC_CFGR_PLLMUL_CLKx14 (12 << RCC_CFGR_PLLMUL_SHIFT) /* 1100: PLL input clock x 14 */ # define RCC_CFGR_PLLMUL_CLKx15 (13 << RCC_CFGR_PLLMUL_SHIFT) /* 1101: PLL input clock x 15 */ # define RCC_CFGR_PLLMUL_CLKx16 (14 << RCC_CFGR_PLLMUL_SHIFT) /* 111x: PLL input clock x 16 */ -#define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */ +#endif #define RCC_CFGR_MCO_SHIFT (24) /* Bits 26-24: Microcontroller Clock Output */ #define RCC_CFGR_MCO_MASK (0x0f << RCC_CFGR_MCO_SHIFT) # define RCC_CFGR_NOCLK (0 << RCC_CFGR_MCO_SHIFT) /* 0xx: No clock */ @@ -207,12 +209,22 @@ #define TCC_APB2RSTR_IOPFRST (1 << 7) /* Bit 7: IO port F reset */ #define TCC_APB2RSTR_IOPGRST (1 << 8) /* Bit 8: IO port G reset */ #define RCC_APB2RSTR_ADC1RST (1 << 9) /* Bit 9: ADC 1 interface reset */ -#define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */ +#endif #define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 Timer reset */ #define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI 1 reset */ -#define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */ +#endif #define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */ -#define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */ +#else +# define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */ +# define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */ +# define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */ +#endif /* APB1 Peripheral reset register */ @@ -222,6 +234,11 @@ #define RCC_APB1RSTR_TIM5RST (1 << 3) /* Bit 3: Timer 5 reset */ #define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: Timer 6 reset */ #define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: Timer 7 reset */ +#ifdef CONFIG_STM32_VALUELINE +# 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 */ +#endif #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 */ @@ -231,12 +248,17 @@ #define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 18: UART 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_USBRST (1 << 23) /* Bit 23: USB reset */ -#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ -#define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */ +# define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +# define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ +#endif #define RCC_APB1RSTR_BKPRST (1 << 27) /* Bit 27: Backup interface reset */ #define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */ #define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC interface reset */ +#ifdef CONFIG_STM32_VALUELINE +# define RCC_APB1RSTR_CECRST (1 << 30) /* Bit 30: CEC reset */ +#endif /* AHB Peripheral Clock enable register */ @@ -246,7 +268,9 @@ #define RCC_AHBENR_FLITFEN (1 << 4) /* Bit 4: FLITF clock enable */ #define RCC_AHBENR_CRCEN (1 << 6) /* Bit 6: CRC clock enable */ #define RCC_AHBENR_FSMCEN (1 << 8) /* Bit 8: FSMC clock enable */ -#define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */ +#endif #ifdef CONFIG_STM32_CONNECTIVITYLINE # define RCC_AHBENR_ETHMACEN (1 << 14) /* Bit 14: Ethernet MAC clock enable */ # define RCC_AHBENR_ETHMACTXEN (1 << 15) /* Bit 15: Ethernet MAC TX clock enable */ @@ -272,12 +296,22 @@ #define RCC_APB2ENR_IOPFEN (1 << 7) /* Bit 7: I/O port F clock enable */ #define RCC_APB2ENR_IOPGEN (1 << 8) /* Bit 8: I/O port G clock enable */ #define RCC_APB2ENR_ADC1EN (1 << 9) /* Bit 9: ADC 1 interface clock enable */ -#define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */ +#endif #define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 Timer clock enable */ #define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI 1 clock enable */ -#define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */ +#endif #define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 clock enable */ -#define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */ +#else +# define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 clock enable */ +# define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 clock enable */ +# define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 clock enable */ +#endif /* APB1 Peripheral Clock enable register */ @@ -287,6 +321,11 @@ #define RCC_APB1ENR_TIM5EN (1 << 3) /* Bit 3: Timer 5 clock enable */ #define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: Timer 6 clock enable */ #define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: Timer 7 clock enable */ +#ifdef CONFIG_STM32_VALUELINE +# define RCC_APB1ENR_TIM12EN (1 << 6) /* Bit 6: Timer 12 clock enable */ +# define RCC_APB1ENR_TIM13EN (1 << 7) /* Bit 7: Timer 13 clock enable */ +# define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: Timer 14 clock enable */ +#endif #define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window Watchdog clock enable */ #define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI 2 clock enable */ #define RCC_APB1ENR_SPI3EN (1 << 15) /* Bit 15: SPI 3 clock enable */ @@ -296,12 +335,17 @@ #define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART 5 clock enable */ #define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C 1 clock enable */ #define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C 2 clock enable */ -#define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ -#define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */ -#define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */ +#ifndef CONFIG_STM32_VALUELINE +# define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ +# define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */ +# define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */ +#endif #define RCC_APB1ENR_BKPEN (1 << 27) /* Bit 27: Backup interface clock enable */ #define RCC_APB1ENR_PWREN (1 << 28) /* Bit 28: Power interface clock enable */ #define RCC_APB1ENR_DACEN (1 << 29) /* Bit 29: DAC interface clock enable */ +#ifdef CONFIG_STM32_VALUELINE +# define RCC_APB1ENR_CECEN (1 << 30) /* Bit 30: CEC clock enable */ +#endif /* Backup domain control register */ @@ -331,7 +375,7 @@ #if defined(CONFIG_STM32_VALUELINE) || defined(CONFIG_STM32_CONNECTIVITYLINE) -/* Clock configuration register 2 (For connectivity line only) */ +/* Clock configuration register 2 (For value line and connectivity line only) */ #define RCC_CFGR2_PREDIV1_SHIFT (0) #define RCC_CFGR2_PREDIV1_MASK (0x0f << RCC_CFGR2_PREDIV1_SHIFT) @@ -352,6 +396,10 @@ # define RCC_CFGR2_PREDIV1d15 (14 << RCC_CFGR2_PREDIV1_SHIFT) # define RCC_CFGR2_PREDIV1d16 (15 << RCC_CFGR2_PREDIV1_SHIFT) +#endif + +#ifdef CONFIG_STM32_CONNECTIVITYLINE + #define RCC_CFGR2_PREDIV2_SHIFT (4) #define RCC_CFGR2_PREDIV2_MASK (0x0f << RCC_CFGR2_PREDIV2_SHIFT) # define RCC_CFGR2_PREDIV2d1 (0 << RCC_CFGR2_PREDIV2_SHIFT) diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c index 47ed5e016b..ed767db77f 100644 --- a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c +++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c @@ -92,7 +92,11 @@ static inline void rcc_reset(void) putreg32(regval, STM32_RCC_CR); regval = getreg32(STM32_RCC_CFGR); /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ - regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK|RCC_CFGR_USBPRE); + regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK +#ifndef CONFIG_STM32_VALUELINE + |RCC_CFGR_USBPRE +#endif + ); putreg32(regval, STM32_RCC_CFGR); putreg32(0, STM32_RCC_CIR); /* Disable all interrupts */